From 8f9a44637e5ebdbacc5150b899253186ef4a4ad1 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Tue, 4 Jul 2023 13:11:29 +0100 Subject: [PATCH] Gazebo: add X-UAV Mini Talon V-Tail - Add body link and visual and collision meshes. - Add wheel link. - Add wheel link - cleanup. - Add aileron links. - Add rudder links. - Update position controller PIDs. - Add rudder links - cleanup. - Position motor and prop. - Add motor link and thrust controller. - Rename cockpit frame to forward deck. - Rename rudder to ruddervator. - Change control surface limits. - Add ArduPilot plugin configured for v-tail. - Add initial ArduPilot param file. - Add doc. - Update wheel link orientation and inertial. - Move mesh origin to geometric centre. - Update inertial. - Update motor link inertial. - Update base link inertial. - Add cp visuals for main wing. - Add lift-drag plugin for main wing. - Switch order of wheel collision and visual elements. - Update aileron link orientation and inertial. - Move mesh origin to geometric centre. - Update inertial and controller PIDs. - Update motor velocity controller PIDs. - Update lift-drag plugin for main wing. - Update lift-drag plugin for v-tail. - Add visuals for v-tail centre of pressure. - Move mesh origin to geometric centre. - Update inertial and controller PIDs. - Add lift-drag plugins for v-tail and ruddervator. - Add notes. - Switch to lift-drag for prop thrust. - Use motor / pusher inertial from zephyr. - Increase gains on position controllers. - Update params autotuning roll and pitch. - Update doc. Signed-off-by: Rhys Mainwaring --- Gazebo/config/mini_talon_vtail.param | 28 + Gazebo/docs/X-UAV_Mini_Talon.md | 56 + .../mini_talon_vtail/meshes/iris_prop_cw.dae | 160 +++ .../meshes/mini_talon_forward_deck.dae | 89 ++ .../meshes/mini_talon_fuselage.dae | 385 ++++++ .../meshes/mini_talon_fuselage_collision.stl | Bin 0 -> 421934 bytes .../meshes/mini_talon_left_aileron.dae | 151 +++ .../meshes/mini_talon_left_ruddervator.dae | 151 +++ .../meshes/mini_talon_left_tail.dae | 89 ++ .../meshes/mini_talon_left_tail_collision.stl | Bin 0 -> 18984 bytes .../meshes/mini_talon_left_wing.dae | 167 +++ .../meshes/mini_talon_left_wing_collision.stl | Bin 0 -> 65334 bytes .../meshes/mini_talon_main_wheel.dae | 151 +++ .../mini_talon_main_wheel_collision.stl | Bin 0 -> 69284 bytes .../meshes/mini_talon_right_aileron.dae | 151 +++ .../meshes/mini_talon_right_ruddervator.dae | 151 +++ .../meshes/mini_talon_right_tail.dae | 89 ++ .../mini_talon_right_tail_collision.stl | Bin 0 -> 20384 bytes .../meshes/mini_talon_right_wing.dae | 167 +++ .../mini_talon_right_wing_collision.stl | Bin 0 -> 64734 bytes .../meshes/propdrive_3536_frontplate.dae | 89 ++ .../meshes/propdrive_3536_motor_can.dae | 1081 +++++++++++++++++ Gazebo/models/mini_talon_vtail/model.config | 37 + Gazebo/models/mini_talon_vtail/model.sdf | 992 +++++++++++++++ Gazebo/worlds/vtail_runway.sdf | 115 ++ 25 files changed, 4299 insertions(+) create mode 100644 Gazebo/config/mini_talon_vtail.param create mode 100644 Gazebo/docs/X-UAV_Mini_Talon.md create mode 100755 Gazebo/models/mini_talon_vtail/meshes/iris_prop_cw.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_forward_deck.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_fuselage.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_fuselage_collision.stl create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_aileron.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_ruddervator.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_tail.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_tail_collision.stl create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_wing.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_wing_collision.stl create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_main_wheel.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_main_wheel_collision.stl create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_aileron.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_ruddervator.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_tail.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_tail_collision.stl create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_wing.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_wing_collision.stl create mode 100644 Gazebo/models/mini_talon_vtail/meshes/propdrive_3536_frontplate.dae create mode 100644 Gazebo/models/mini_talon_vtail/meshes/propdrive_3536_motor_can.dae create mode 100644 Gazebo/models/mini_talon_vtail/model.config create mode 100644 Gazebo/models/mini_talon_vtail/model.sdf create mode 100755 Gazebo/worlds/vtail_runway.sdf diff --git a/Gazebo/config/mini_talon_vtail.param b/Gazebo/config/mini_talon_vtail.param new file mode 100644 index 00000000..5b6ece3f --- /dev/null +++ b/Gazebo/config/mini_talon_vtail.param @@ -0,0 +1,28 @@ +ARMING_RUDDER 0.000000 +RLL2SRV_RMAX 75.000000 +RLL_RATE_P 0.250811 +RLL_RATE_I 0.250811 +RLL_RATE_D 0.007486 +RLL_RATE_FF 0.339297 +RLL_RATE_FLTT 3.183099 +RLL_RATE_FLTD 10.000000 +PTCH2SRV_TCONST 0.750000 +PTCH2SRV_RMAX_UP 75.000000 +PTCH2SRV_RMAX_DN 75.000000 +PTCH_RATE_P 1.329862 +PTCH_RATE_I 1.022127 +PTCH_RATE_D 0.021373 +PTCH_RATE_FF 1.022127 +PTCH_RATE_FLTT 2.122066 +PTCH_RATE_FLTD 10.000000 +SERVO1_MIN 1000.000000 +SERVO1_MAX 2000.000000 +SERVO2_MIN 1000.000000 +SERVO2_MAX 2000.000000 +SERVO2_FUNCTION 79.000000 +SERVO3_MIN 1000.000000 +SERVO3_MAX 2000.000000 +SERVO4_MIN 1000.000000 +SERVO4_MAX 2000.000000 +SERVO4_FUNCTION 80.000000 +ARSPD_TYPE 0.000000 \ No newline at end of file diff --git a/Gazebo/docs/X-UAV_Mini_Talon.md b/Gazebo/docs/X-UAV_Mini_Talon.md new file mode 100644 index 00000000..e2f2a6e6 --- /dev/null +++ b/Gazebo/docs/X-UAV_Mini_Talon.md @@ -0,0 +1,56 @@ +# X-UAV Mini Talon V-Tail + +Model for the X-UAV Mini Talon V-Tail plane for use with ArduPilot. + +## Usage + +Gazebo and the plugins should be installed as per the [ArduPilot Gazebo Plugin](https://github.com/ArduPilot/ardupilot_gazebo) instructions. + +Update the `GZ_SIM_RESOURCE_PATH` to include these models: + +```bash +export GZ_SIM_RESOURCE_PATH=$GZ_SIM_RESOURCE_PATH:\ +$HOME/SITL_Models/Gazebo/models:\ +$HOME/SITL_Models/Gazebo/worlds +``` + +#### Run Gazebo + +```bash +gz sim -v4 -r vtail_runway.sdf +``` + +#### Run ArduPilot SITL + +```bash +sim_vehicle.py -v ArduPlane -f JSON --add-param-file=$HOME/SITL_Models/Gazebo/config/mini_talon_vtail.param --console --map +``` + +## Specifications + +- wingspan: 1300 mm +- length: 830 mm +- wing area: 30 dm^2 +- flying weight: 1.0 - 2.0 kg + +- 3s 11.1V + - 10x6 prop +- 4s 14.8V + - 9x5 prop + - 3536 930kV motor + - 40A ESC + +## General + +- Mark Qvale's [X-UAV Mini Talon Build Compilation](http://www.itsqv.com/QVM/index.php?title=X-UAV_Mini_Talon_Build_Compilation#Introduction). + +## Credits + +- Original Mini Talon X-UAV CAD model by Alessandro Bacchini, +retrieved from GrabCAD 04 July 2023. + - https://grabcad.com/alessandro.bacchini-2 + - https://grabcad.com/library/mini-talon-x-uav-1 + +- PropDrive 3536 motor model by Seth Schaffer, retrieved from GrabCAD 04 July 2023. + - https://grabcad.com/seth.schaffer-1 + - https://grabcad.com/library/configurable-propdrive-v2-brushless-motor-with-mount-plate-solidworks-2019-1 diff --git a/Gazebo/models/mini_talon_vtail/meshes/iris_prop_cw.dae b/Gazebo/models/mini_talon_vtail/meshes/iris_prop_cw.dae new file mode 100755 index 00000000..f939111f --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/iris_prop_cw.dae @@ -0,0 +1,160 @@ + + + + + Blender User + Blender 2.73.0 commit date:2015-01-07, commit time:13:17, hash:b4d8fb5 + + 2015-01-13T10:40:36 + 2015-01-13T10:40:36 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 0 + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0.000999987 + 1 + 0.1 + 0.1 + 1 + 1 + 1 + 2 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 2880 + 2 + 30.002 + 1.000799 + 0.04999995 + 29.99998 + 1 + 2 + 0 + 0 + 1 + 1 + 1 + 1 + 8192 + 1 + 1 + 0 + 1 + 1 + 1 + 3 + 0 + 0 + 0 + 0 + 0 + 1 + 1 + 1 + 3 + 0.15 + 75 + 1 + 1 + 0 + 1 + 1 + 0 + + + + + + + + + + 0.004280924 -3.49388e-4 0.005053937 8.01072e-4 9.88087e-5 0.005053937 7.80612e-4 -1.48083e-4 0.005053937 3.16992e-4 -0.001004755 0.005053937 0.003346145 -0.002840101 0.005053937 6.20291e-4 -6.15112e-4 0.005053937 0.003805875 -0.002070605 0.005053937 0.004120886 -0.001231372 0.005053937 -9.63807e-5 -0.001274824 0.005053937 0.002055525 -0.004074037 0.005053937 0.002756357 -0.003515124 0.005053937 -5.75051e-4 -0.001396059 0.005053937 -0.001067101 -0.00135529 0.005053937 -0.001370072 -0.00485593 0.005053937 -0.005618572 -7.93976e-4 0.005053937 -0.002117633 -3.8824e-4 0.005053937 -0.002198874 9.88087e-5 0.005053937 -0.002117633 5.85858e-4 0.005053937 -0.005618572 9.91593e-4 0.005053937 -0.005698919 9.88087e-5 0.005053937 -0.001882612 0.001020073 0.005053937 -0.004991114 0.002663254 0.005053937 -0.005380094 0.001855671 0.005053937 -4.74602e-4 -0.004896104 0.005053937 4.13686e-4 -0.004775822 0.005053937 0.001266181 -0.004498779 0.005053937 -0.001882612 -8.22511e-4 0.005053937 -0.003816366 -0.003810346 0.005053937 -0.001519322 -0.001156926 0.005053937 -0.003068268 -0.004304111 0.005053937 -0.002243995 -0.004656434 0.005053937 -0.005380094 -0.001658022 0.005053937 -0.004991114 -0.002465665 0.005053937 -0.004464268 -0.003190875 0.005053937 -5.75051e-4 0.001593649 0.005053937 -0.001370072 0.00505352 0.005053937 -0.001067101 0.001552879 0.005053937 -0.002243995 0.004854083 0.005053937 -0.001519322 0.001354515 0.005053937 -9.63807e-5 0.001472413 0.005053937 4.13686e-4 0.004973411 0.005053937 -4.74602e-4 0.005093753 0.005053937 -0.003068268 0.00450176 0.005053937 -0.003816366 0.004007935 0.005053937 -0.004464268 0.003388464 0.005053937 3.16992e-4 0.001202344 0.005053937 0.002055525 0.004271626 0.005053937 0.001266181 0.004696428 0.005053937 6.20291e-4 8.12729e-4 0.005053937 0.003346145 0.003037691 0.005053937 0.002756357 0.003712773 0.005053937 0.004301071 9.88087e-5 0.005053937 0.004280924 5.47005e-4 0.005053937 7.80612e-4 3.457e-4 0.005053937 0.004120886 0.001428961 0.005053937 0.003805875 0.002268195 0.005053937 7.80612e-4 3.457e-4 -0.0023247 8.01072e-4 9.88087e-5 -0.0023247 7.80612e-4 -1.48083e-4 -0.0023247 6.20291e-4 -6.15112e-4 -0.0023247 3.16992e-4 -0.001004755 -0.0023247 -9.63807e-5 -0.001274824 -0.0023247 -5.75051e-4 -0.001396059 -0.0023247 -0.001067101 -0.00135529 -0.0023247 -0.001519322 -0.001156926 -0.0023247 -0.001882612 -8.22511e-4 -0.0023247 -0.002117633 -3.8824e-4 -0.0023247 -0.002198874 9.88087e-5 -0.0023247 -0.002117633 5.85858e-4 -0.0023247 -0.001882612 0.001020073 -0.0023247 -0.001519322 0.001354515 -0.0023247 -0.001067101 0.001552879 -0.0023247 -5.75051e-4 0.001593649 -0.0023247 -9.63807e-5 0.001472413 -0.0023247 3.16992e-4 0.001202344 -0.0023247 6.20291e-4 8.12729e-4 -0.0023247 0.004280924 -3.49388e-4 -0.004945993 0.004301071 9.88087e-5 -0.004945993 0.004280924 5.47005e-4 -0.004945993 0.004120886 0.001428961 -0.004945993 0.003805875 0.002268195 -0.004945993 0.003346145 0.003037691 -0.004945993 0.002756357 0.003712773 -0.004945993 0.002055525 0.004271626 -0.004945993 0.001266181 0.004696428 -0.004945993 4.13686e-4 0.004973411 -0.004945993 -4.74602e-4 0.005093753 -0.004945993 -0.001370072 0.00505352 -0.004945993 -0.002243995 0.004854083 -0.004945993 -0.003068268 0.00450176 -0.004945993 -0.003816366 0.004007935 -0.004945993 -0.004464268 0.003388464 -0.004945993 -0.004991114 0.002663254 -0.004945993 -0.005380094 0.001855671 -0.004945993 -0.005618572 9.91593e-4 -0.004945993 -0.005698919 9.88087e-5 -0.004945993 -0.005618572 -7.93976e-4 -0.004945993 -0.005380094 -0.001658022 -0.004945993 -0.004991114 -0.002465665 -0.004945993 -0.004464268 -0.003190875 -0.004945993 -0.003816366 -0.003810346 -0.004945993 -0.003068268 -0.004304111 -0.004945993 -0.002243995 -0.004656434 -0.004945993 -0.001370072 -0.00485593 -0.004945993 -4.74602e-4 -0.004896104 -0.004945993 4.13686e-4 -0.004775822 -0.004945993 0.001266181 -0.004498779 -0.004945993 0.002055525 -0.004074037 -0.004945993 0.002756357 -0.003515124 -0.004945993 0.003346145 -0.002840101 -0.004945993 0.003805875 -0.002070605 -0.004945993 0.004120886 -0.001231372 -0.004945993 0.002231001 0.001790404 -0.004845976 0.002231001 0.001790404 -0.0023247 -6.98924e-4 0.003482043 -0.004845976 -6.98924e-4 0.003482043 -0.0023247 -0.003628849 0.001790404 -0.004845976 -0.003628849 0.001790404 -0.0023247 -0.003628849 -0.001592755 -0.004845976 -0.003628849 -0.001592755 -0.0023247 -6.98924e-4 -0.003284394 -0.004845976 -6.98924e-4 -0.003284394 -0.0023247 0.002231001 -0.001592755 -0.0023247 0.002231001 -0.001592755 -0.004845976 0.002260327 -0.001609683 -0.004916667 0.002238631 -0.001597166 -0.004884243 0.002238631 0.001794815 -0.004884243 0.002244412 0.001798152 -0.004895985 0.002262711 0.001808702 -0.004914283 0.002292752 -0.001628398 -0.004938364 0.00228101 0.001819252 -0.004932582 0.002293467 0.001826405 -0.00493592 0.002331018 0.001848161 -0.004945993 0.002331018 -0.001650512 -0.004945993 -6.98924e-4 0.003490805 -0.004884243 -6.98924e-4 0.003497481 -0.004895985 -6.98924e-4 0.00351864 -0.004914283 -6.98924e-4 0.003539741 -0.004932582 -6.98924e-4 0.003554105 -0.00493592 -6.98924e-4 0.003597497 -0.004945993 -0.003636479 0.001794815 -0.004884243 -0.003658175 0.001807332 -0.004916667 -0.0036906 0.001826047 -0.004938364 -0.003728866 0.001848161 -0.004945993 -0.003636479 -0.001597166 -0.004884243 -0.003658175 -0.001609683 -0.004916667 -0.0036906 -0.001628398 -0.004938364 -0.003728866 -0.001650512 -0.004945993 -6.98924e-4 -0.003293216 -0.004884243 -6.98924e-4 -0.00331819 -0.004916667 -6.98924e-4 -0.003355681 -0.004938364 -6.98924e-4 -0.003399848 -0.004945993 -7.03156e-4 -0.004901885 1.64569e-5 -7.03722e-4 -0.00490117 1.074e-5 -6.98924e-4 -0.00490117 1.03028e-4 -7.02426e-4 -0.00490278 2.45213e-5 -7.00653e-4 -0.00490427 4.84451e-5 -7.01174e-4 -0.004903972 4.05125e-5 -7.0177e-4 -0.004903435 3.2539e-5 -6.99505e-4 -0.004904031 7.20192e-5 -6.99818e-4 -0.00490427 6.41956e-5 -7.00206e-4 -0.004904389 5.63385e-5 -6.98969e-4 -0.004902184 9.53143e-5 -6.99073e-4 -0.004902958 8.7576e-5 -6.99252e-4 -0.004903614 7.9812e-5 -0.003919541 0.003923654 -0.001075148 -0.003919363 0.003923535 -0.001073122 -0.003922164 0.003921151 -0.001142859 -0.003920853 0.003924369 -0.001095473 -0.003920435 0.00392425 -0.001088619 -0.003920018 0.003924012 -0.001081705 -0.003921687 0.003923833 -0.001115918 -0.003921449 0.003924131 -0.001109123 -0.003921151 0.00392431 -0.001102328 -0.003922104 0.003922045 -0.001136183 -0.003922045 0.00392276 -0.001129448 -0.003921866 0.003923356 -0.001122713 0.009114444 -0.006102979 2.46061e-4 0.009207785 -0.005899012 1.12609e-4 0.01076149 -0.006091773 -1.28075e-5 0.01595389 -0.004363059 -0.001631557 0.01678526 -0.004452288 -0.001654803 0.01675945 -0.005290865 -0.001281142 0.01892793 -0.004682242 -0.001714646 0.01976054 -0.004718661 -0.001699626 0.01973795 -0.00538659 -0.001391708 0.03863102 -0.003488719 7.54078e-5 0.04343777 -0.003348231 6.30885e-4 0.04336595 -0.005101799 0.001442909 0.09390139 -0.003329336 0.001717686 0.09685456 -0.003185212 0.001672565 0.09682905 -0.004158496 0.001975178 0.09982579 -0.003040194 0.001627147 0.1011865 -0.009222269 0.002714812 0.1011025 -0.009727358 0.002804994 0.09968066 -0.01007646 0.002980828 0.1010371 -0.01012384 0.002869725 0.1008503 -0.01125639 0.003054678 0.1022341 -0.002922654 0.001590371 0.1017608 -0.005768775 0.002098381 0.1012549 -0.005756855 0.002109467 0.08463895 -0.003566741 0.001703023 0.09049308 -0.003416657 0.001712322 0.09089452 -0.004016876 0.001995205 0.09091544 -0.003405869 0.001712977 0.06710135 -0.005227744 0.002506852 0.07123064 -0.003616154 0.001637279 0.07897782 -0.005310237 0.002562403 0.07868301 -0.003588676 0.001673817 0.07904326 -0.003587365 0.001675605 0.05505269 -0.003453433 0.001496374 0.05528962 -0.00345689 0.00150609 0.05528175 -0.003612101 0.001617491 0.0557484 -0.003463566 0.001524806 0.06686091 -0.00357306 0.00160551 0.0671693 -0.003576099 0.001607775 0.05043619 -0.00338608 0.001307666 0.04934704 -0.00356853 0.001339077 0.04935801 -0.003374576 0.001206517 0.0437566 -0.003338873 6.67731e-4 0.04436421 -0.003321111 7.37948e-4 0.04934102 -0.003374397 0.001204907 0.03156125 -0.005112588 -2.09279e-4 0.03160762 -0.00398755 -7.45664e-4 0.03286665 -0.003898143 -5.98475e-4 0.03828549 -0.003513216 3.50187e-5 0.02477592 -0.004671275 -0.001462996 0.02568829 -0.004578411 -0.001367807 0.02566146 -0.005280494 -0.001026093 0.02746218 -0.004397928 -0.001182734 0.03123688 -0.004013895 -7.8901e-4 0.02174133 -0.004805326 -0.001663744 0.02178055 -0.004803597 -0.001661121 0.02470213 -0.004674553 -0.001467883 0.01884055 -0.004672825 -0.001712203 0.009541928 -0.005169332 -3.6484e-4 0.009791314 -0.004624783 -7.21134e-4 0.01078283 -0.004748225 -8.03023e-4 0.009864985 -0.004463851 -8.26405e-4 0.01544487 -0.004308462 -0.001617312 0.01377236 -0.005075275 -0.001058816 0.01379477 -0.004034936 -0.001536011 0.01078724 -0.003536403 -0.001387774 0.01031249 -0.003457725 -0.001364409 0.008373081 -0.007505238 0.001708865 0.008585751 -0.007166981 0.00120002 0.01072508 -0.007341563 0.001001656 0.008840322 -0.006654679 7.40685e-4 0.008306145 -0.007611751 0.001869082 0.008318901 -0.007591485 0.001838564 0.01069509 -0.008162498 0.002285778 0.010706 -0.00785464 0.001646161 0.01122009 -0.008283495 0.002377331 0.01367348 -0.008134782 0.001424491 0.01959258 -0.008956611 0.001797735 0.01659268 -0.009353935 0.003216624 0.0166226 -0.008801639 0.001937508 0.01374161 -0.00882852 0.002796053 0.01365345 -0.008561015 0.00215274 0.0136407 -0.008809924 0.002781152 0.01295733 -0.008683979 0.002680361 0.01954734 -0.009831488 0.003607749 0.01929605 -0.00979793 0.003579199 0.01955235 -0.009742319 0.00333029 0.0182287 -0.009655416 0.003457903 0.02546972 -0.01055914 0.004184007 0.02489006 -0.01049864 0.004143953 0.02547484 -0.01038539 0.003857016 0.02329915 -0.01033252 0.004034101 0.02272558 -0.01025593 0.003968954 0.03139436 -0.01114964 0.004450738 0.03044682 -0.0110597 0.004430949 0.03139567 -0.01104831 0.004341363 0.02929192 -0.01095008 0.004406809 0.02843815 -0.01086908 0.004388988 0.03392773 -0.01139008 0.004503607 0.03731662 -0.01134318 0.004209578 0.03731691 -0.01169645 0.004481554 0.04160404 -0.01208394 0.004453599 0.04323399 -0.01163011 0.00420022 0.04323881 -0.01223164 0.004442989 0.04915237 -0.01187723 0.004308164 0.04720389 -0.01254558 0.004402935 0.04360812 -0.01226502 0.004440546 0.05507856 -0.01205283 0.004413783 0.05281603 -0.0129835 0.004344165 0.04916256 -0.01269841 0.004382431 0.06071335 -0.01335126 0.004174113 0.0550903 -0.0130952 0.004297256 0.05306774 -0.01300311 0.004341542 0.06102395 -0.01335519 0.004166245 0.06101745 -0.01090151 0.004360496 0.06483685 -0.01340305 0.004069745 0.06696373 -0.01096022 0.004173398 0.07687914 -0.0132988 0.003767967 0.07884395 -0.01249754 0.003832936 0.07749384 -0.0132876 0.003752648 0.07884353 -0.01322591 0.003725111 0.06858897 -0.01345014 0.003974735 0.06696212 -0.01342976 0.004015922 0.07885181 -0.01108962 0.003910839 0.09299784 -0.01234978 0.00340712 0.09072732 -0.01253491 0.003463804 0.09073483 -0.01128083 0.003645539 0.08890467 -0.01268357 0.003509342 0.08844 -0.01272147 0.003520965 0.09913939 -0.01153665 0.003149151 0.09835696 -0.01166486 0.003192305 0.09668153 -0.01145279 0.00332266 0.09667766 -0.01187944 0.003259658 0.09489548 -0.01210725 0.003331065 0.0166679 -0.00782752 6.1091e-4 0.01961505 -0.008476018 0.00112611 0.01369488 -0.007624149 7.88715e-4 0.01963865 -0.007943153 5.14291e-4 0.02260351 -0.007966935 5.55349e-4 0.0255388 -0.008492231 0.00131601 0.02555984 -0.007916986 7.78756e-4 0.03146505 -0.007832586 0.001383543 0.01809751 -0.009631216 0.003438591 0.01957154 -0.009380221 0.002531766 0.02550268 -0.009524881 0.002505362 0.02551972 -0.00902903 0.001891076 0.03143179 -0.009032905 0.002284944 0.03734052 -0.00913918 0.002739846 0.04327642 -0.007990419 0.002698481 0.05507814 -0.01081603 0.004389584 0.04915153 -0.01070338 0.004108011 0.04323559 -0.01051533 0.003745138 0.03732287 -0.01029765 0.003462016 0.03140866 -0.01010835 0.003268718 0.02548766 -0.009977638 0.003160357 0.0670098 -0.008175015 0.003677427 0.06698107 -0.009588181 0.0040102 0.0610606 -0.008165538 0.003859281 0.06103259 -0.009560823 0.004202246 0.05511736 -0.008138656 0.003844022 0.0550909 -0.009511828 0.004202425 0.04919022 -0.008089601 0.003385663 0.04916417 -0.009439527 0.003804028 0.04324984 -0.009300708 0.00324577 0.090752 -0.009798884 0.003642857 0.09077757 -0.008338928 0.00344634 0.09670072 -0.009956121 0.003301143 0.09672772 -0.008499085 0.003073334 0.09970879 -0.008626639 0.002716422 0.1011968 -0.0086717 0.002621233 0.1012777 -0.008673787 0.002616941 0.09965819 -0.01145166 0.003120481 0.06704998 -0.006721377 0.003175139 0.06110179 -0.006715238 0.003323435 0.06115639 -0.005209565 0.002587258 0.09084969 -0.005454301 0.002597272 0.09976834 -0.005714297 0.00216943 0.09679305 -0.005609214 0.002377092 0.09081047 -0.006893157 0.003088116 0.0788958 -0.008230209 0.003575921 0.0788691 -0.009667277 0.00382626 0.0866025 -0.01287132 0.003566861 0.07893204 -0.00677812 0.003155291 0.01968795 -0.00674051 -5.40949e-4 0.01671493 -0.006635069 -4.47127e-4 0.01373714 -0.006419301 -2.5213e-4 0.05521261 -0.005188047 0.002560138 0.05515784 -0.006697058 0.003300666 0.04928183 -0.005150139 0.002160131 0.0492295 -0.006658315 0.002840757 0.04331517 -0.006589412 0.002098679 0.03150826 -0.006521701 5.54719e-4 0.02560728 -0.006661176 -1.89344e-4 0.0226528 -0.006742775 -4.74975e-4 0.09816354 0.007497012 -1.7873e-4 0.1038953 0.007092833 -8.31988e-5 0.1027694 2.96789e-4 0.001004755 0.03976333 0.002555072 -0.00234884 0.04529958 0.003440022 -0.001649498 0.04449719 -1.6207e-4 -4.67702e-4 0.01229608 0.001552522 -0.002744674 0.01230841 0.001597285 -0.002725601 0.01526743 0.001454293 -0.003397941 0.04954272 0.01013648 -0.003240704 0.04664981 0.009504079 -0.003528475 0.04684549 0.01042914 -0.003768384 0.04114824 0.008654236 -0.004291355 0.05271077 0.011675 -0.003260076 0.05871486 0.01238644 -0.002815723 0.05845838 0.01126611 -0.002518773 0.06665015 0.01352864 -0.002515792 0.07033759 0.01346588 -0.002305209 0.06929093 0.008346915 -0.001141667 0.1041265 0.008486807 -3.14278e-4 0.09892398 0.0120607 -9.83956e-4 0.104611 0.01140755 -7.98459e-4 0.1045539 0.01106309 -7.41353e-4 0.06461393 0.01343512 -0.002648234 0.0635094 0.008332788 -0.001403033 0.06764322 2.19451e-4 6.44472e-4 0.07769387 0.01334065 -0.001885175 0.08084756 0.008092463 -6.88597e-4 0.0817784 0.01311379 -0.001708269 0.09239667 0.007703363 -3.18953e-4 0.09722757 0.01225554 -0.001039266 0.09321534 0.01247841 -0.001213014 0.05889314 0.01315557 -0.003021657 0.05287671 0.01232516 -0.003453552 0.05134356 0.01211357 -0.003563582 0.04991424 0.01173901 -0.003674328 0.04699164 0.01097303 -0.003900825 0.04975593 0.01112812 -0.003508985 0.05248069 0.01062667 -0.002970993 0.0577358 0.008126497 -0.00168389 0.02368932 0.002654731 -0.00493288 0.02425444 0.002662837 -0.005073606 0.02128726 0.002171874 -0.004630386 0.01356196 0.001955389 -0.002693951 0.01537483 0.002007722 -0.003140568 0.0153712 0.00185436 -0.003220617 0.01833391 0.002093136 -0.003869652 0.01832246 0.001936674 -0.003975272 0.01996546 0.002140223 -0.004271626 0.02129507 0.002323925 -0.00450772 0.02424615 0.002823889 -0.004968285 0.02714419 0.00370419 -0.005152821 0.02714836 0.00356549 -0.005221247 0.02723896 0.003732979 -0.005158841 0.02994394 0.00471723 -0.005140364 0.01236635 0.001808643 -0.002635538 0.01535016 0.001752376 -0.003296792 0.01821196 0.001479268 -0.004125356 0.01829987 0.001817762 -0.004046201 0.02117747 0.001653671 -0.004742324 0.02126562 0.00203526 -0.004692196 0.02415466 0.002080857 -0.005140125 0.02423685 0.002508163 -0.005123198 0.02706211 0.002914905 -0.005242824 0.02713572 0.003392279 -0.005257725 0.02984565 0.003994941 -0.005124151 0.02992755 0.004525184 -0.005165159 0.0354107 0.005988895 -0.004674911 0.03553217 0.006633162 -0.004776835 0.04098933 0.007874071 -0.004118859 0.0355677 0.006868064 -0.004781961 0.04493612 0.01043432 -0.004060089 0.04126048 0.009103894 -0.004335522 0.03584432 0.007143378 -0.00474137 0.03558856 0.00704205 -0.004753828 0.02996206 0.00481218 -0.005026757 0.01178622 1.47263e-4 -0.002626061 0.01199358 7.18727e-4 -0.002674281 0.01493102 4.76282e-4 -0.003353834 0.01225477 0.001438617 -0.002735078 0.01785618 3.9762e-4 -0.003988683 0.02081209 4.59662e-4 -0.004504799 0.02379214 7.61879e-4 -0.004803895 0.02671062 0.001448631 -0.004825055 0.02947765 0.002368271 -0.004648447 0.03496617 0.004036664 -0.004088163 0.04047447 0.005564212 -0.003423273 0.04606401 0.006834924 -0.002740144 0.05182242 0.007663428 -0.002123892 0.03898537 -6.77845e-4 -0.00110048 0.03769552 -7.98549e-4 -0.001248598 0.0343042 0.001434743 -0.003053307 0.03354859 -0.001438558 -0.001742243 0.02887207 1.66199e-4 -0.003682672 0.02813684 -0.002273797 -0.00238645 0.02611666 -5.44473e-4 -0.003911852 0.02721524 -0.002416074 -0.002496182 0.02022337 -0.001193106 -0.003810465 0.01797717 -0.002950251 -0.00268805 0.01728749 -0.001123607 -0.003440678 0.01660698 -0.002784729 -0.00255078 0.01439094 -9.24482e-4 -0.00295484 0.02536857 -0.002657651 -0.002620518 0.02247339 -0.003036439 -0.002815425 0.02319467 -0.001042485 -0.003981769 0.02246224 -0.00303626 -0.002815127 0.0195105 -0.002979636 -0.002731502 0.0108934 -0.002094626 -0.001978158 0.01108181 -0.001629829 -0.002131402 0.07376223 1.93009e-4 7.62843e-4 0.09695792 2.16133e-4 0.00102663 0.09431344 1.79432e-4 0.001036584 0.09110814 1.8155e-4 9.93905e-4 0.07938075 1.89297e-4 8.37686e-4 0.01240569 0.00201267 -0.002452135 0.01239597 0.001944422 -0.002533555 0.01239359 0.001927554 -0.002553701 0.01238787 0.001886904 -0.002602159 0.05907517 0.01318073 -0.003008604 0.0115047 -5.86395e-4 -0.00247544 0.01165127 -2.24818e-4 -0.002594649 0.05099332 0.003964781 -0.001039147 0.05683743 0.004238247 -6.47306e-4 0.06177538 2.44808e-4 5.3096e-4 0.05628144 2.68549e-4 4.24682e-4 0.05591791 2.5952e-4 4.0007e-4 0.05014276 1.16061e-4 9.04733e-6 0.04650324 2.56533e-5 -2.37379e-4 0.01239359 0.002042293 -0.002322971 0.01238787 0.002056419 -0.002261281 0.01536321 0.001989603 -0.002911627 0.01232606 0.002007246 -0.002003312 0.01232051 0.002000391 -0.001984953 0.01529085 0.002011179 -0.002662658 0.03558754 0.007201969 -0.004679083 0.03559046 0.0071612 -0.004710912 0.02993214 0.004956424 -0.005012869 0.0123676 0.002040266 -0.002176642 0.01235532 0.002030551 -0.00212562 0.01533758 0.001982748 -0.00277704 0.03554517 0.007250785 -0.004501163 0.0355603 0.007255792 -0.004553079 0.02986907 0.005031466 -0.004795134 0.03840762 0.008359134 -0.004409492 0.04689514 0.01140433 -0.003898322 0.04702985 0.01143729 -0.003890693 0.04703146 0.01144349 -0.003901839 0.04557681 0.01098096 -0.004003822 0.04703354 0.01144003 -0.003918349 0.04703354 0.0114358 -0.003921151 0.05447763 0.01310962 -0.003458797 0.05297106 0.0128898 -0.003554642 0.05320841 0.01294785 -0.003541171 0.1046841 0.01184576 -8.80739e-4 0.09900712 0.01256084 -0.001083314 0.1046864 0.01185953 -8.84102e-4 0.1046867 0.01186126 -8.84622e-4 0.1046881 0.0118696 -8.87304e-4 0.1046885 0.01187157 -8.88169e-4 0.1046886 0.01187223 -8.88985e-4 0.1046879 0.01186859 -8.86834e-4 0.1046875 0.01186591 -8.86022e-4 0.08473533 0.01351094 -0.001692771 0.08759152 0.01334029 -0.00156778 0.08189767 0.0136578 -0.001805245 0.09330403 0.01299899 -0.001317799 0.09329879 0.01297581 -0.00130397 0.09742277 0.01275289 -0.001137554 0.08185648 0.01358044 -0.001766324 0.09328383 0.01291102 -0.001264035 0.09899359 0.01249659 -0.0010522 0.1046831 0.01184004 -8.79344e-4 0.06470197 0.01392221 -0.002747654 0.06735479 0.01411634 -0.002611994 0.07042402 0.01396536 -0.002388715 0.0704503 0.01404911 -0.002433419 0.07874172 0.0138691 -0.001955091 0.05894804 0.01341438 -0.003086566 0.05294698 0.01278299 -0.003541171 0.05898708 0.01358985 -0.003132224 0.05296444 0.01287472 -0.003557443 0.03842097 0.008327245 -0.004479408 0.04126548 0.009424686 -0.004294812 0.04126572 0.009409189 -0.004305601 0.04413104 0.01045531 -0.004116952 0.04412955 0.01043653 -0.004122853 0.04702627 0.01136875 -0.00393331 0.04703158 0.01140964 -0.003929495 0.04557669 0.01095443 -0.004020571 0.04413175 0.0104705 -0.004109919 0.04703295 0.01142454 -0.003925859 0.04557734 0.01096767 -0.00401467 0.04413163 0.01048225 -0.004101693 0.04126447 0.009436845 -0.004282891 0.03841876 0.008339881 -0.004463732 0.03558152 0.007231354 -0.004642128 0.05523276 0.01320588 -0.003409802 0.05561113 0.0132541 -0.003385245 0.05599033 0.01330244 -0.003360629 0.04851585 0.01180082 -0.003807127 0.04703229 0.01144748 -0.003908276 0.05000162 0.01216381 -0.003722608 0.0470333 0.01144337 -0.00391525 0.04557716 0.01097738 -0.004007697 0.04413002 0.01049339 -0.004087269 0.04412907 0.01049542 -0.004081904 0.04125684 0.009453833 -0.004240095 0.04125279 0.009452998 -0.004223644 0.04557627 0.01098358 -0.00399959 0.04412662 0.01049685 -0.004070401 0.04124796 0.009449064 -0.004206061 0.04851573 0.01180052 -0.00380665 0.02124285 0.002390801 -0.004182517 0.02120316 0.002417504 -0.003980696 0.02224731 0.002522587 -0.004210829 0.02418857 0.002921342 -0.00465089 0.02412617 0.002984762 -0.004434347 0.02584874 0.003408491 -0.004639267 0.02706032 0.003854334 -0.004836082 0.02699321 0.00386846 -0.004646182 0.01831459 0.002108931 -0.00366187 0.01828795 0.002111017 -0.003520131 0.02127271 0.002380669 -0.004325807 0.02422434 0.002905368 -0.004790067 0.02710163 0.003836274 -0.004966557 0.02990686 0.005013346 -0.004915118 0.0355724 0.007249295 -0.004600107 0.03841578 0.008349359 -0.004446804 0.04126268 0.009445726 -0.004269778 0.04126018 0.009451389 -0.004255533 0.04413074 0.01049053 -0.004092395 0.02953279 0.00488913 -0.004661619 0.02982181 0.005001902 -0.004650413 0.03552877 0.007228553 -0.004429221 0.03872895 0.00847721 -0.004305243 0.04126232 0.009385287 -0.004179 0.04125046 0.009246647 -0.00434488 0.03559035 0.007109224 -0.004737496 0.04700553 0.01124149 -0.003926634 0.04993897 0.01201432 -0.003716289 0.05291455 0.01262462 -0.003505587 0.05148684 0.01252692 -0.003638565 0.05296468 0.01288384 -0.003555774 0.03842198 0.008246183 -0.004529833 0.03842306 0.008292853 -0.004507124 0.04125875 0.009314119 -0.004336714 0.04126381 0.0093683 -0.004323601 0.04412412 0.01038843 -0.004131138 0.04701763 0.01131278 -0.003932356 0.04849082 0.01178431 -0.003836691 0.02994018 0.004913866 -0.005053281 0.02424716 0.002857506 -0.004906237 0.02128988 0.002341032 -0.004447162 0.02713012 0.003783106 -0.005073964 0.01239651 0.00203514 -0.002354145 0.01537704 0.001970231 -0.003029167 0.01832896 0.002079129 -0.003783822 0.02992105 0.004989624 -0.004966795 0.1046808 0.01182651 -8.76541e-4 0.1046701 0.0117619 -8.63167e-4 0.1046566 0.01168107 -8.48407e-4 0.08187931 0.01368159 -0.001817762 0.018251 0.002120614 -0.003330111 0.01723313 0.002018213 -0.003105819 0.05751544 0.01349681 -0.003261685 0.05902242 0.01368892 -0.003163874 0.06009376 0.01382547 -0.003094315 0.06473308 0.01401132 -0.002786159 0.01178419 0.001010656 -8.78131e-4 0.01153957 5.46128e-4 -3.99795e-4 0.01448857 4.80399e-4 -7.90174e-4 0.05769592 0.008141756 -0.001211106 0.05785888 0.004312157 -2.06479e-5 0.06261628 0.004347145 1.38751e-4 0.1045536 0.01107043 -6.8177e-4 0.1046022 0.01136052 -7.46045e-4 0.09892004 0.01207476 -8.94051e-4 0.1046565 0.01168507 -8.17969e-4 0.104668 0.01175361 -8.33152e-4 0.09899091 0.01248997 -0.001013696 0.1046885 0.01187199 -8.85736e-4 0.01108086 -4.638e-4 2.18396e-4 0.01093131 -7.93152e-4 4.19997e-4 0.0138486 -8.74206e-4 2.75653e-4 0.104155 0.008688271 -1.53891e-4 0.1043247 0.009702801 -3.78708e-4 0.09862154 0.01030075 -4.89405e-4 0.1041265 0.008517324 -1.22238e-4 0.06417208 0.01154088 -0.001860857 0.06538528 0.00436747 2.31527e-4 0.06992107 0.01155894 -0.001555562 0.06844288 0.004309296 2.90329e-4 0.08140653 0.01120173 -0.001048862 0.1033134 0.003629744 7.82746e-4 0.09753519 0.003747344 7.57675e-4 0.09172487 0.003865599 7.32465e-4 0.09288567 0.01063144 -6.51071e-4 0.09134888 0.003873229 7.30833e-4 0.08008897 0.004087567 5.14294e-4 0.02241867 -2.87815e-4 -6.4303e-4 0.01959055 -6.45687e-4 -3.77127e-4 0.01885569 -0.00227493 9.41604e-4 0.01808822 -0.002346336 9.74657e-4 0.01672828 -8.22505e-4 -4.55114e-5 0.01603287 -0.002329111 0.001071035 0.02164328 -0.002015531 8.21552e-4 0.02325618 -0.001865446 7.52089e-4 0.02519553 3.43026e-4 -7.67349e-4 0.02439594 -0.001639127 7.48668e-4 0.02803742 0.001143634 -7.63818e-4 0.02723437 -0.001075506 7.40151e-4 0.03278148 2.5942e-5 7.23506e-4 0.03390818 0.002754032 -8.27413e-4 0.033104 9.91365e-5 7.06737e-4 0.03978019 0.004495263 -0.001037776 0.03897476 0.001431465 4.01489e-4 0.04569375 0.006184697 -0.001257479 0.05599027 0.01330286 -0.003359973 0.0529747 0.01289379 -0.003541767 0.05901652 0.01372063 -0.003152668 0.04997628 0.01219838 -0.003682434 0.05296963 0.01288652 -0.003530621 0.04704284 0.01142609 -0.003854215 0.0529558 0.01287031 -0.003501594 0.04996246 0.01221776 -0.003661096 0.04993027 0.0121079 -0.003569245 0.0469684 0.01127982 -0.00369656 0.04700607 0.01139605 -0.003806591 0.04120612 0.009378492 -0.004063427 0.0268405 0.003676593 -0.004254341 0.02966058 0.004832983 -0.004240274 0.0411539 0.009253025 -0.003911674 0.03540503 0.007039964 -0.004088819 0.02398788 0.002754747 -0.004052281 0.01793462 0.001619517 -0.002458214 0.0208643 0.001912534 -0.003059089 0.01499879 0.001472532 -0.00181061 0.01226395 0.001921892 -0.001816272 0.01225823 0.001910984 -0.001805126 0.01201719 0.001453161 -0.001333713 0.1046878 0.01186859 -8.80268e-4 0.1046881 0.01187008 -8.82682e-4 0.1046883 0.01187092 -8.84006e-4 0.09900259 0.0125404 -0.001064419 0.1046856 0.01185649 -8.70684e-4 0.1046867 0.01186245 -8.75389e-4 0.1046745 0.01179283 -8.41852e-4 0.1046808 0.01182889 -8.58189e-4 0.1046835 0.01184481 -8.65379e-4 0.08187896 0.01370567 -0.001787781 0.09330362 0.01302492 -0.001286268 0.09616088 0.01284837 -0.001181185 0.09329909 0.01300668 -0.001264035 0.09330356 0.01302987 -0.001280367 0.0818789 0.01371109 -0.001781165 0.09328085 0.01290649 -0.001220941 0.0761649 0.01397162 -0.002084612 0.07044923 0.01410508 -0.00240314 0.07044935 0.01409679 -0.002407491 0.06472939 0.01405471 -0.002766788 0.06472867 0.01406329 -0.002763152 0.05901503 0.01372873 -0.003149986 0.08187395 0.01368725 -0.001761972 0.0704438 0.01408153 -0.002381205 0.06472295 0.01404035 -0.002740263 0.05900889 0.0137068 -0.00312674 0.08185362 0.01358318 -0.001711547 0.05292773 0.01276636 -0.003424465 0.05594515 0.01326066 -0.003258347 0.05898362 0.01360714 -0.003063976 0.06469911 0.01393741 -0.002679407 0.07042127 0.01397699 -0.002323329 0.09320497 0.01247537 -0.001090884 0.08176809 0.01313281 -0.001559913 0.07032585 0.01352113 -0.00214827 0.0645985 0.01348638 -0.002493798 0.05887752 0.01316845 -0.002870082 0.05584007 0.01282554 -0.003053426 0.05281925 0.01232838 -0.003196597 0.04981476 0.01166439 -0.003309071 0.04684281 0.01083093 -0.003397226 0.04099965 0.0088045 -0.003523349 0.03521728 0.006613969 -0.003614962 0.02943706 0.004456043 -0.00370872 0.02660977 0.003334641 -0.003710091 0.02377182 0.002438724 -0.003506898 0.01318794 -0.002305269 0.001204431 0.01213121 -0.002296388 0.001253962 0.01031249 -0.002155482 0.001253902 0.04395401 0.00256145 1.42596e-4 0.04488813 0.002723932 1.08691e-4 0.0486806 0.006896734 -0.001329481 0.05084222 0.003759682 -1.07422e-4 0.05168563 0.007465183 -0.001356184 0.05107909 0.003800868 -1.16017e-4 0.05469232 0.007880866 -0.001322925 0.05382794 0.004008173 -7.73496e-5 0.0567975 0.004232108 -3.55779e-5 0.01740044 5.98747e-4 -0.001293241 0.02029931 8.54927e-4 -0.001779794 0.02316826 0.001321434 -0.002156555 0.02597552 0.002114593 -0.002336859 0.02881407 0.003108918 -0.002346456 0.03465402 0.005061626 -0.002352654 0.04049432 0.007101714 -0.002429544 0.04638528 0.009032309 -0.002488136 0.04937118 0.009836673 -0.002483665 0.05238258 0.01047921 -0.002442181 0.05540257 0.01095598 -0.002352774 0.058429 0.01127183 -0.002200782 0.127301 0.00509876 -1.12772e-4 0.1246753 0.006482362 -2.19259e-4 0.1259892 0.005790054 -1.65976e-4 0.1105068 0.01052999 -6.70665e-4 0.1076027 0.01129508 -7.94702e-4 0.123362 0.007174491 -2.72526e-4 0.1220685 0.007728159 -3.08566e-4 0.1177737 0.009132862 -4.62362e-4 0.1163222 0.009446561 -5.09794e-4 0.1177173 0.009150862 -4.64213e-4 0.1212672 0.006399571 -1.6073e-4 0.1227788 0.001810848 2.86692e-4 0.1197593 0.006616413 -1.67396e-4 0.12106 0.001420378 3.75246e-4 0.1166622 0.007018923 -1.81989e-4 0.1243859 0.002175986 2.03902e-4 0.1227192 0.006170034 -1.55646e-4 0.1256383 0.002886116 9.02945e-5 0.1240602 0.005946516 -1.58082e-4 0.1163315 0.009434759 -5.03647e-4 0.1164072 0.008882462 -4.24234e-4 0.1193438 0.008250296 -3.4725e-4 0.1221945 0.007426679 -2.76372e-4 0.1248487 0.006372094 -2.11775e-4 0.1227063 0.00751996 -2.99116e-4 0.1224986 0.007629394 -3.07538e-4 0.1220169 0.007782697 -3.23324e-4 0.1206027 0.008232712 -3.69665e-4 0.1192439 0.008642256 -3.94406e-4 0.1191872 0.008683085 -4.16045e-4 0.1263098 0.005433917 -1.53476e-4 0.1252357 0.005714356 -1.62642e-4 0.1104037 0.007756054 -2.41931e-4 0.1104868 0.009993433 -5.83392e-4 0.1060914 0.01161545 -8.44081e-4 0.1105116 0.01065629 -6.93689e-4 0.1105093 0.01067888 -6.99731e-4 0.1134158 0.01006275 -6.04762e-4 0.116346 0.009329497 -4.86835e-4 0.1270681 0.004525125 -1.16847e-4 0.1269757 0.004404485 -1.02085e-4 0.1264106 0.003666162 -1.17528e-5 0.1259478 0.003061711 6.22091e-5 0.115354 9.59343e-4 6.41541e-4 0.1174682 0.001130163 5.42869e-4 0.1030377 0.001969933 0.001074373 0.1027694 3.5392e-4 0.001352608 0.1101418 6.87812e-4 0.001101672 0.1105117 0.01065862 -6.76881e-4 0.1174471 -0.007552564 0.001846015 0.118615 -0.007251143 0.001726806 0.1186151 -0.007229685 0.001745343 0.1097947 -0.008674323 0.002418935 0.1098781 -0.006425321 0.002146959 0.1014125 -0.007839322 0.002649247 0.1016464 -0.006421864 0.002455294 0.1275644 0.004252016 -8.75536e-5 0.127193 0.004763901 -1.00075e-4 0.1280632 -0.001006901 4.62034e-4 0.1281205 -8.58814e-4 4.41136e-4 0.1281238 -4.58027e-4 3.89399e-4 0.1248498 0.006374359 -1.8628e-4 0.1192446 0.008644998 -3.68077e-4 0.1008517 -0.01124686 0.003060638 0.100851 -0.01125138 0.003057837 0.109762 -0.009364485 0.002441942 0.1008508 -0.01125288 0.003056883 0.1163318 0.009436428 -4.89542e-4 0.1220689 0.007730126 -2.87308e-4 0.1221954 0.007430911 -2.30786e-4 0.1166651 0.007036089 -4.54313e-5 0.1197621 0.006629705 -4.50774e-5 0.1193451 0.008256256 -2.90791e-4 0.1276975 0.001542687 2.24064e-4 0.1269899 0.004396975 -5.51534e-5 0.1264685 0.00363332 8.13901e-5 0.1263105 0.005435526 -1.25119e-4 0.125238 0.005719363 -1.074e-4 0.1206084 -0.006736636 0.001523315 0.1208071 -0.006641328 0.001513719 0.1186009 -0.007121384 0.001749038 0.1207882 -0.006539106 0.001518368 0.1185402 -0.006668686 0.001725196 0.1229175 -0.005781948 0.001280307 0.1229324 -0.00586605 0.001263618 0.1208078 -0.006661951 0.001501023 0.1207077 -0.006111562 0.001500308 0.1228182 -0.005385458 0.00126785 0.1249276 -0.004750669 0.001052677 0.1248121 -0.004394292 0.001044869 0.1258955 -0.00421375 9.25828e-4 0.1258949 -0.004213094 9.25799e-4 0.1249262 -0.004802405 0.001036882 0.1239561 -0.005391597 0.001148104 0.1235651 -0.005629003 0.001192927 0.1182862 -0.004796504 0.001541256 0.1203708 -0.004342913 0.001344501 0.1224034 -0.00374484 0.001140296 0.1243306 -0.002919197 9.42979e-4 0.1260554 -0.001799881 7.44642e-4 0.1276689 0.003356873 -8.86293e-6 0.1240628 0.005954325 -7.8171e-5 0.125674 0.002846777 2.44687e-4 0.1261228 0.003238022 1.62117e-4 0.1272834 -2.67854e-4 5.00848e-4 0.1275754 6.28147e-4 3.60671e-4 0.1277896 -0.001251637 5.5342e-4 0.128032 -1.96275e-4 3.99275e-4 0.1267057 -0.003366053 8.27289e-4 0.1266791 -0.00340116 8.05273e-4 0.1274482 -0.002559781 6.93736e-4 0.1274538 -0.002579987 6.83993e-4 0.1274553 -0.002575814 6.8942e-4 0.1274468 -0.002597928 6.86526e-4 0.1270713 -0.002990841 7.44614e-4 0.1274183 -0.002494513 6.99344e-4 0.1272919 -0.002221226 6.96911e-4 0.1267646 -0.001090049 6.30826e-4 0.1250886 0.002491354 3.2028e-4 0.122721 0.006179511 -5.68782e-5 0.1276556 -0.002058744 6.1045e-4 0.1212691 0.006410777 -4.85354e-5 0.1278825 0.00302869 -4.2594e-6 0.1276815 0.004090726 -8.86936e-5 0.1281332 6.73593e-4 2.43322e-4 0.1281403 0.001534461 1.3219e-4 0.128084 8.82422e-4 2.49567e-4 0.1280959 0.001798987 1.08238e-4 0.1279075 0.002919197 6.80936e-6 0.1277097 0.004051923 -9.11234e-5 0.1278132 0.003480076 -4.39729e-5 0.1277164 0.004042685 -9.26885e-5 0.12772 0.004034519 -9.4173e-5 0.12786 -0.001531362 5.36036e-4 0.1281285 1.0744e-4 3.16405e-4 0.1259122 -0.004203557 9.23906e-4 0.1265798 -0.003061354 8.23147e-4 0.100855 -0.01122516 0.003066658 0.1008527 -0.01123929 0.003065407 0.1008523 -0.01124233 0.003063499 0.1097698 -0.009348988 0.002458691 0.1097746 -0.009218633 0.002460122 0.1008824 -0.01105517 0.003067016 0.1008693 -0.01113545 0.003071367 0.1008657 -0.01115739 0.003072559 0.1008582 -0.01120531 0.003068387 0.1009851 -0.01042914 0.003003597 0.1009297 -0.01076459 0.003049552 0.100922 -0.01081174 0.003053724 0.1111451 -0.009070813 0.002346813 0.1243887 0.002194106 3.85093e-4 0.1228004 0.001750886 4.94031e-4 0.1210837 0.001448452 5.98644e-4 0.1192979 0.001254498 7.04702e-4 0.1174767 0.001127541 8.0489e-4 0.110507 0.01053494 -6.35637e-4 0.1104874 0.0100041 -5.08287e-4 0.1164086 0.008890211 -3.61199e-4 0.1163466 0.009333074 -4.57438e-4 0.1104048 0.007779657 -7.92374e-5 0.127718 0.004039525 -9.4261e-5 0.1275097 0.004568755 -1.0351e-4 0.008014023 0.002546131 -0.001899242 0.007406651 0.002687275 -0.001830697 0.00738573 0.002683579 -0.00173068 0.001493036 -0.00565958 7.15594e-4 0.003685474 -0.006418168 0.001328229 0.003687381 -0.0063591 0.001431643 0.003705203 -0.006259977 0.001524209 -3.7609e-4 -0.004883587 3.92943e-4 -6.11365e-4 -0.004900634 2.33384e-4 -6.10009e-4 -0.004900634 2.35416e-4 0.001820027 -0.004220187 0.001236021 0.003793001 -0.005932688 0.001666784 0.001906394 -0.004155695 0.001244068 0.004185438 -0.004768252 0.0017277 0.002721726 -0.003547072 0.001319885 8.38801e-4 -0.004658997 9.81736e-4 2.20433e-4 -0.004796683 7.21453e-4 -6.94692e-5 -0.004861235 5.99431e-4 0.003361403 -0.002818822 0.001257538 0.004801034 -0.003128409 0.001461684 0.00337404 -0.002796411 0.001252889 0.00548011 -0.001425504 9.63154e-4 0.004113674 -0.001138269 8.45304e-4 0.003890693 -0.001884162 0.001063108 0.006167948 2.13698e-4 2.92928e-4 0.004290461 4.15125e-4 3.31873e-4 0.004226684 -7.60314e-4 7.34911e-4 0.006811141 0.001651823 -5.17518e-4 0.004097461 0.001463115 -4.92618e-5 0.004256129 6.01529e-4 2.64084e-4 0.004389703 0.002149403 -3.98071e-4 0.003772675 0.002287983 -3.45725e-4 0.00407505 0.001584768 -9.34899e-5 0.00366503 0.002538204 -4.35485e-4 0.004790723 0.003031373 -0.001066505 0.003006756 0.00345546 -7.56515e-4 0.002956807 0.003504872 -7.80712e-4 0.004891872 0.003208518 -0.001353025 0.002617061 0.003840923 -9.45312e-4 0.002524316 0.003921151 -0.001142859 0.002523601 0.00392419 -0.001108467 0.003912806 0.003499269 -0.001436591 0.004917919 0.003234386 -0.001478612 0.004942119 0.003260076 -0.0015527 0.002544343 0.003904283 -0.001018524 0.002535939 0.003911316 -0.001038551 0.002521514 0.003923535 -0.001073122 0.007147729 -0.003598272 0.001782298 0.009718716 -0.003549396 0.001880049 0.007873415 -0.001846909 0.001146733 0.01001965 -0.002836108 0.001576364 0.008315622 -0.007216572 0.002608716 0.006061732 -0.006521403 0.002180635 0.008296906 -0.007271647 0.002605915 0.005964457 -0.006873011 0.002051889 0.008259117 -0.007420361 0.002525389 0.008230745 -0.007531821 0.002465009 0.008372783 -0.00704813 0.002617418 0.008615851 -0.006331622 0.002654254 0.006486833 -0.005298435 0.002169013 0.008836865 -0.00577414 0.002499163 0.00911653 -0.0050686 0.002302825 0.009544849 -0.003987967 0.00200212 0.008229136 -0.007545232 0.002447426 0.005943715 -0.006982684 0.001960933 0.008227169 -0.007561445 0.002426147 0.005952358 -0.007022023 0.001834928 0.008219361 -0.007625877 0.002341628 0.0072456 0.002509236 -0.001285433 0.007356524 0.002667903 -0.00159794 0.009900629 0.002316951 -0.002136766 0.00988835 0.002285182 -0.001956045 0.009858965 0.002277135 -0.001815378 0.009744286 0.002130746 -0.001476109 0.009287416 0.001281559 -6.11996e-4 0.008605599 -1.73e-4 3.34635e-4 0.009896755 0.002186119 -0.002182006 0.003698527 -0.00644046 0.001212 5.60015e-4 -0.004740178 -3.64659e-4 0.001428186 -0.004414916 -5.62872e-4 0.002004563 -0.00463891 -4.43314e-4 0.004295766 3.20387e-4 -0.002023935 0.004190742 9.69087e-4 -0.002054154 0.004453778 0.001678764 -0.002098977 0.004926085 0.003174543 -0.001694798 0.002743363 0.00371474 -0.001401603 0.002658486 0.003804087 -0.001340568 0.002604663 0.003851175 -0.001267611 0.002533972 0.003913044 -0.001171767 0.003174066 0.003261685 -0.00171107 0.003145456 0.003291845 -0.001690506 0.004824101 0.002786397 -0.001951992 0.004908323 0.003087401 -0.001790761 0.004110097 0.001467347 -0.002077341 0.003970086 0.0018211 -0.00204122 0.003746032 0.002387225 -0.001983463 0.00689882 0.001011371 -0.002246379 0.006283223 -6.28489e-4 -0.001980364 0.004268944 -3.694e-5 -0.001964271 0.00327748 -0.00293231 -0.001213788 0.003888726 -0.001889586 -0.001561641 0.005604147 -0.002331316 -0.001481831 0.003914296 -0.001807332 -0.00158286 0.004206717 -8.65753e-4 -0.001825869 0.002914667 -0.003308355 -0.001062095 0.00491631 -0.003970563 -8.11608e-4 0.002474009 -0.003765046 -8.77864e-4 0.004273116 -0.005408763 -1.16089e-6 0.002326428 -0.003860712 -8.32237e-4 0.001531064 -0.004376351 -5.86369e-4 -4.07487e-4 -0.004892647 -1.56356e-4 -6.33597e-5 -0.004838407 -2.30448e-4 0.001603543 -0.005520939 2.25147e-4 0.001502394 -0.005698084 5.11676e-4 -5.57139e-4 -0.004897832 -8.75308e-5 0.001476347 -0.005723893 6.3727e-4 -6.97717e-4 -0.004904389 5.76489e-5 -6.47351e-4 -0.004900991 -4.60381e-5 -6.82756e-4 -0.004901111 -3.06452e-6 -6.94126e-4 -0.00490117 1.074e-5 0.009876012 0.002076447 -0.002272903 0.009778738 0.001724839 -0.002401709 0.009353637 5.01888e-4 -0.002390027 0.008692741 -0.001198172 -0.002003312 0.007396876 0.002602219 -0.001950323 0.007379055 0.002503037 -0.002042889 0.007291257 0.002175807 -0.002185463 0.003727734 -0.006424784 0.001079261 0.003838658 -0.006266117 7.66811e-4 0.008270561 -0.007642924 0.002011835 0.008240163 -0.007669568 0.002133846 0.008232295 -0.007653117 0.002212285 0.008229255 -0.007646739 0.002242624 0.007967114 -0.002949595 -0.001367747 0.01059901 -0.002792 -0.001680135 0.1025055 -0.001290798 0.001294136 0.01256054 -0.003786146 0.001989483 0.03240305 -0.00239408 0.001808047 0.02763932 -0.003124594 0.002006173 0.02655082 -0.003252089 0.002000212 0.02370041 -0.003585994 0.001984536 0.02106517 -0.003894746 0.001970112 0.02095371 -0.003894805 0.001971185 0.01817679 -0.003896355 0.00199896 0.05542755 4.8326e-4 0.001013934 0.05003625 1.0498e-4 0.001054108 0.04755407 -6.91842e-5 0.001072585 0.04414618 -5.92321e-4 0.001252412 0.03812664 -0.001516342 0.001570045 0.09110099 2.67808e-4 0.001385211 0.09695261 3.10993e-4 0.00136888 0.06177872 4.81646e-4 0.001149892 0.06400668 4.81081e-4 0.001197576 0.06764745 4.373e-4 0.001232445 0.08530133 2.25008e-4 0.001401424 0.07938003 2.96212e-4 0.00134474 0.01391273 -0.003898799 0.002041578 0.01537311 -0.003897964 0.002026975 0.05591577 4.83137e-4 0.001024365 0.01367104 -0.008870184 0.003109037 0.09953963 -0.01099246 0.003128528 0.09497296 -0.01152753 0.003302633 0.09491968 -0.01200783 0.003361642 0.02476155 -0.01040768 0.004602015 0.0247699 -0.01045173 0.004558861 0.03038078 -0.01098132 0.004760742 0.01924186 -0.009834825 0.003761529 0.04580122 -0.01244246 0.004455089 0.04720294 -0.01255697 0.004441618 0.04720509 -0.01254314 0.00444734 0.03599971 -0.01158076 0.004603385 0.03599768 -0.01157093 0.004620671 0.03039926 -0.01107525 0.004634261 0.07687962 -0.01330339 0.003773212 0.09788227 -0.01173907 0.003217697 0.09490454 -0.01210433 0.00335735 0.08891224 -0.0126776 0.003533124 0.07688528 -0.0132687 0.003786563 0.06484353 -0.01339447 0.00409305 0.07688075 -0.013296 0.003778457 0.05281752 -0.01297587 0.004358947 0.05281984 -0.01296365 0.004363715 0.05282312 -0.01294732 0.004367351 0.05283272 -0.01290172 0.004371106 0.05284637 -0.0128386 0.004370093 0.06486487 -0.01328414 0.004099011 0.07690399 -0.01316195 0.003792405 0.08892834 -0.01257687 0.003537714 0.03879868 -0.0117926 0.004585027 0.04160255 -0.01202517 0.004533886 0.04160571 -0.01200157 0.004540681 0.04721206 -0.01250338 0.004455149 0.04440075 -0.01231318 0.004476249 0.04720813 -0.01252532 0.004451811 0.04440265 -0.01229792 0.004483401 0.04160022 -0.01204496 0.004525899 0.03879809 -0.01180893 0.004573166 0.0304051 -0.01108074 0.004608511 0.03600257 -0.01158732 0.004584848 0.03879827 -0.01182174 0.004560053 0.03879928 -0.01183104 0.004545688 0.04159879 -0.01206099 0.004516661 0.0415982 -0.01207327 0.00450623 0.04439973 -0.01232457 0.004467964 0.04299867 -0.01220411 0.004480957 0.04159939 -0.0120868 0.004481911 0.04159837 -0.01208186 0.004494667 0.03880369 -0.01183915 0.004513561 0.03880113 -0.01183682 0.004530251 0.04580044 -0.01245123 0.004447042 0.04439955 -0.01233214 0.004458546 0.04439973 -0.01233452 0.00445342 0.04299908 -0.01221042 0.004469931 0.04720169 -0.0125668 0.004434704 0.04720139 -0.0125702 0.00443089 0.04720127 -0.0125727 0.004426717 0.04720163 -0.01256942 0.004423856 0.05281358 -0.01298356 0.004349589 0.05281507 -0.01298195 0.004352748 0.05281674 -0.0129804 0.004356145 0.04160022 -0.01208794 0.004475116 0.04160124 -0.01208817 0.004468023 0.04440021 -0.01233601 0.004447996 0.04160243 -0.01208752 0.004460692 0.04440081 -0.01233649 0.004442274 0.03042721 -0.01107972 0.004523515 0.03601056 -0.0115906 0.004544198 0.03041166 -0.0110833 0.004581451 0.03600621 -0.0115906 0.004565119 0.03043609 -0.01107358 0.00449264 0.02483481 -0.01053136 0.004328072 0.03601574 -0.01158732 0.004522144 0.0136981 -0.008871793 0.002965033 0.01920557 -0.009818255 0.0039047 0.024796 -0.01051127 0.004455089 0.03039419 -0.01106685 0.004658758 0.05038148 -0.01224386 0.004359483 0.04166454 -0.01165699 0.004581034 0.04162704 -0.01186841 0.004555046 0.03600221 -0.01144111 0.004698157 0.03880554 -0.01172184 0.00461322 0.03038382 -0.01102423 0.004724025 0.03319042 -0.01126676 0.004721581 0.03599745 -0.01149791 0.004677474 0.03394484 -0.0111373 0.004777312 0.03038692 -0.0108391 0.004739642 0.03038096 -0.01092702 0.004791975 0.0255956 -0.01043754 0.004688978 0.03602224 -0.01127713 0.004724502 0.02476239 -0.01033288 0.004605948 0.01918238 -0.00976926 0.004024207 0.01918619 -0.009632527 0.004049956 0.01678436 -0.009330928 0.003810465 0.01365649 -0.008840262 0.003232777 0.01367807 -0.00871253 0.003277778 0.02478134 -0.01048636 0.004509925 0.03038996 -0.01105558 0.004681825 0.03319269 -0.01130336 0.004687368 0.03599596 -0.01154112 0.004651606 0.09061902 -0.01203769 0.003468632 0.03599637 -0.01155769 0.004636764 0.03880012 -0.01177263 0.004595696 0.04161459 -0.0119428 0.004550457 0.0528863 -0.01265746 0.004352927 0.05294579 -0.01235085 0.004306852 0.08899486 -0.01212739 0.003502845 0.07979273 -0.01263564 0.003696382 0.0769822 -0.01267093 0.003764986 0.06495374 -0.01282197 0.00405848 0.0644021 -0.01282888 0.004071891 0.01136904 -0.006799042 0.003091394 0.09575003 -0.00696069 0.002663016 0.01190429 -0.005409359 0.002698779 0.04834836 -0.007296442 0.003241062 0.04256522 -0.007437348 0.003512203 0.04198223 -0.01010894 0.004251718 0.07733386 -0.01080518 0.003477692 0.07791644 -0.007638752 0.002918303 0.06534916 -0.01087272 0.003726303 0.06600397 -0.007640242 0.003070652 0.05337917 -0.01048898 0.003913462 0.0541014 -0.007347583 0.003140807 0.04769116 -0.01026242 0.004030466 0.08981561 -0.007323324 0.002777338 0.04178744 -0.01104003 0.00445646 0.05312198 -0.0116145 0.004163503 0.01366311 -0.008697569 0.003425717 0.01917505 -0.009572386 0.004195988 0.01368552 -0.008579254 0.003496944 0.0137726 -0.008242964 0.003577232 0.01927393 -0.008991003 0.004268586 0.01919245 -0.009417533 0.004247426 0.02485346 -0.009482026 0.004694163 0.024773 -0.01001375 0.004725754 0.03055781 -0.009794354 0.004768729 0.03043794 -0.01044237 0.004853785 0.03626942 -0.009981632 0.004549086 0.03611153 -0.01076722 0.004695713 0.02475714 -0.01020741 0.00469619 0.03040313 -0.01068001 0.00484997 0.0367816 -0.007670223 0.00389111 0.03099817 -0.007843196 0.004208683 0.02521741 -0.007859289 0.004235506 0.01963323 -0.007678747 0.00394237 0.01412498 -0.007169663 0.003445506 0.0491752 -0.003605961 0.002169549 0.04332643 -0.004051268 0.002434909 0.03748989 -0.004670381 0.00282979 0.03165572 -0.005251705 0.003186345 0.02581834 -0.005668163 0.003281354 0.02022576 -0.005885481 0.003130555 0.01468867 -0.005659699 0.002905368 0.05499774 -0.003467619 0.002117455 -0.09451276 0.01253479 0.003403484 -0.09212523 0.01273173 0.003463387 -0.09213346 0.01146745 0.003613054 -0.03614205 0.01166248 0.004503786 -0.03279221 0.01134741 0.004452347 -0.03279376 0.01124739 0.004334449 -0.015136 0.009039282 0.002802789 -0.01503735 0.009021759 0.002788603 -0.01505154 0.008762419 0.00214672 -0.01735174 0.004560649 -0.001631498 -0.01818305 0.004649877 -0.001654744 -0.01815795 0.00549519 -0.001295924 -0.09189093 0.003614008 0.001712083 -0.09231328 0.0036031 0.001712739 -0.09224891 0.005635678 0.002544522 -0.1025844 0.009419918 0.002714693 -0.1024982 0.009937644 0.00280714 -0.1010786 0.01027369 0.002977967 -0.1024348 0.01032233 0.002869904 -0.1022481 0.01145398 0.003054678 -0.1012237 0.003237962 0.001627385 -0.103632 0.003120243 0.001590371 -0.1026529 0.005954563 0.00210613 -0.1011665 0.005910575 0.002158403 -0.09819149 0.005800664 0.002355217 -0.09825241 0.003383159 0.001672983 -0.0953654 0.003524303 0.001717329 -0.06850612 0.005394995 0.002248108 -0.06856715 0.003772854 0.001607358 -0.07284498 0.003814876 0.00163865 -0.0803802 0.00547558 0.002397775 -0.08008086 0.003786742 0.001673936 -0.08044099 0.003785371 0.001675724 -0.08610922 0.003763318 0.001703381 -0.05668735 0.00365442 0.001508295 -0.05704474 0.003659665 0.001523077 -0.05662256 0.005351603 0.002127766 -0.06825876 0.003769814 0.001605093 -0.05073881 0.003571867 0.001204967 -0.05075573 0.003572106 0.001206576 -0.05068802 0.005316972 0.001838028 -0.05183541 0.00358355 0.001307904 -0.05645048 0.003650963 0.00149852 -0.0447691 0.005278885 0.001253724 -0.04515445 0.003536462 6.67843e-4 -0.04575556 0.003518819 7.37331e-4 -0.03426456 0.004095852 -5.98482e-4 -0.03968334 0.003710746 3.49758e-5 -0.04002296 0.003686606 7.46795e-5 -0.04483544 0.003545761 6.30968e-4 -0.02617037 0.004869222 -0.001463294 -0.02708619 0.004776 -0.001367807 -0.02705991 0.005484521 -0.001042366 -0.02886003 0.004595518 -0.001182794 -0.03296011 0.005315721 -2.44772e-4 -0.03262728 0.004212141 -7.89875e-4 -0.03300547 0.004185318 -7.45665e-4 -0.02313643 0.005002975 -0.001663863 -0.02410405 0.005578637 -0.001339912 -0.02115839 0.00491631 -0.001699566 -0.02113658 0.005591869 -0.001409411 -0.02032381 0.004879713 -0.001714646 -0.02317839 0.005001127 -0.001661062 -0.02412378 0.004959404 -0.001598596 -0.02610003 0.004872322 -0.001467943 -0.02023833 0.004870533 -0.001712203 -0.01218074 0.004947125 -8.04962e-4 -0.01118898 0.004822731 -7.2111e-4 -0.01126128 0.004664957 -8.24423e-4 -0.01684015 0.004505693 -0.001617193 -0.01517063 0.005277574 -0.001068234 -0.01519256 0.004232585 -0.001536011 -0.01218509 0.003733992 -0.001387774 -0.01171034 0.003655314 -0.001364409 -0.0105111 0.006303071 2.47928e-4 -0.01060545 0.006097018 1.13031e-4 -0.01215952 0.006291985 -1.71452e-5 -0.01093977 0.005366921 -3.6488e-4 -0.0121231 0.007542073 9.97412e-4 -0.01023811 0.006852269 7.40644e-4 -0.009982943 0.007365763 0.001201272 -0.01210397 0.008054316 0.001643896 -0.009716391 0.007789552 0.001839339 -0.009770929 0.007702887 0.001708805 -0.009703993 0.00780934 0.001869082 -0.01209372 0.008352994 0.002281308 -0.01265221 0.008480072 0.002377688 -0.01501697 0.009018123 0.002785623 -0.02419501 0.01045548 0.003967463 -0.02094459 0.01003932 0.003615438 -0.02095043 0.009943068 0.003324866 -0.02069127 0.0100069 0.00358802 -0.02028977 0.009955465 0.003544509 -0.02687305 0.01058673 0.003847718 -0.02686744 0.01075911 0.00418806 -0.02628684 0.01069962 0.004151642 -0.02392041 0.01009792 0.003174543 -0.0253567 0.0106042 0.004093289 -0.02688652 0.01018452 0.003133654 -0.03280824 0.01031351 0.003211736 -0.03184425 0.0112583 0.004437744 -0.03056436 0.0111379 0.004418075 -0.0305255 0.01113426 0.004417479 -0.03871554 0.01154053 0.004169106 -0.03871494 0.01189416 0.004485607 -0.04463523 0.01181298 0.004093945 -0.04463678 0.01242733 0.004443705 -0.043002 0.01228016 0.004455268 -0.0549364 0.01323026 0.004332423 -0.05421429 0.01317512 0.004340589 -0.05648571 0.01222223 0.004079937 -0.04860144 0.01274639 0.004403948 -0.04582548 0.01253437 0.0044353 -0.07921159 0.01347517 0.003745317 -0.07827693 0.01349312 0.003768503 -0.0802437 0.0126785 0.003763735 -0.07040911 0.01364433 0.003963828 -0.06623458 0.0136007 0.004069685 -0.06253463 0.01356202 0.004163503 -0.05648839 0.01329803 0.004297912 -0.08983898 0.01292032 0.003520786 -0.08807498 0.01306581 0.003565013 -0.0802415 0.01342761 0.003724336 -0.1005318 0.01173514 0.003149509 -0.0997703 0.01185989 0.00319159 -0.09807944 0.01164931 0.003320395 -0.09807556 0.01207745 0.003259897 -0.0962935 0.01230621 0.00333172 -0.1025947 0.008870005 0.002620697 -0.1011068 0.008823394 0.002708017 -0.09812605 0.008688747 0.003053605 -0.09217727 0.008512854 0.003374814 -0.08030098 0.008369565 0.00331062 -0.05653703 0.008271634 0.003067612 -0.05060398 0.008219301 0.002826392 -0.03290808 0.006729483 4.86922e-4 -0.03286534 0.008042275 0.001299381 -0.02700674 0.006874322 -2.30487e-4 -0.02695959 0.008133411 7.26848e-4 -0.02405244 0.006958007 -5.17484e-4 -0.0240035 0.008185744 5.03406e-4 -0.02108764 0.006956398 -5.84214e-4 -0.02103853 0.008161187 4.66193e-4 -0.01811403 0.00684601 -4.76615e-4 -0.018067 0.008039355 5.79773e-4 -0.0151357 0.006625294 -2.69117e-4 -0.01956319 0.009826302 0.003439962 -0.02099186 0.00916922 0.001763045 -0.02395892 0.009239792 0.001731634 -0.0269193 0.009243428 0.001843154 -0.03283202 0.00924164 0.002203285 -0.01799076 0.009546756 0.003213644 -0.01802122 0.009008288 0.001918494 -0.0150718 0.008339226 0.001411795 -0.01509338 0.007830262 7.72115e-4 -0.04468411 0.008145153 0.002368748 -0.03872412 0.01049214 0.003336489 -0.04465734 0.009454309 0.002933025 -0.101056 0.01164925 0.003120541 -0.09809881 0.01014775 0.003290057 -0.0921514 0.009976506 0.003584206 -0.08027356 0.009809076 0.003588259 -0.08025443 0.01124519 0.00374031 -0.05649262 0.01096314 0.003792166 -0.05056232 0.01083892 0.00369668 -0.04464107 0.01067805 0.003506183 -0.09030252 0.01288211 0.003509163 -0.1031586 0.005966722 0.002098381 -0.1026754 0.008872091 0.002616941 -0.04116117 -0.002357423 -0.00234884 -0.04669743 -0.003242373 -0.001649498 -0.04589504 3.597e-4 -4.67706e-4 -0.01369392 -0.001354932 -0.002744674 -0.0137062 -0.001399636 -0.002725601 -0.01666527 -0.001256704 -0.003397941 -0.05094057 -0.009938836 -0.003240704 -0.04804766 -0.00930643 -0.003528475 -0.04824334 -0.01023149 -0.003768384 -0.04254609 -0.008456647 -0.004291355 -0.05410856 -0.01147735 -0.003260076 -0.06011271 -0.01218885 -0.002815723 -0.05985623 -0.01106852 -0.002518773 -0.06804662 -0.01333099 -0.002515852 -0.07173544 -0.01326823 -0.002305209 -0.07068878 -0.008149266 -0.001141667 -0.1059517 -0.01086544 -7.41353e-4 -0.1055244 -0.008289158 -3.14278e-4 -0.09956139 -0.007299363 -1.7873e-4 -0.1052932 -0.006895244 -8.31988e-5 -0.1041673 -9.91719e-5 0.001004755 -0.06601178 -0.01323747 -0.002648234 -0.06490725 -0.008135199 -0.001403033 -0.06904107 -2.18274e-5 6.44467e-4 -0.07908946 -0.01314312 -0.001885294 -0.0822454 -0.007894873 -6.88597e-4 -0.08317625 -0.01291614 -0.001708269 -0.09379452 -0.007505714 -3.18953e-4 -0.1060089 -0.01120996 -7.98459e-4 -0.1003218 -0.01186311 -9.83956e-4 -0.09862506 -0.01205796 -0.001039266 -0.09461319 -0.01228082 -0.001213014 -0.06029099 -0.01295804 -0.003021657 -0.05427455 -0.01212751 -0.003453552 -0.05273973 -0.01191562 -0.003563702 -0.05131208 -0.01154142 -0.003674328 -0.04838955 -0.01077538 -0.003900825 -0.05115371 -0.01093053 -0.003508985 -0.05387854 -0.01042902 -0.002970993 -0.05913364 -0.007928848 -0.00168389 -0.02508324 -0.002456307 -0.004932343 -0.02565228 -0.002465248 -0.005073606 -0.02268511 -0.001974284 -0.004630386 -0.01495194 -0.001758098 -0.002692162 -0.01677262 -0.001810371 -0.003140747 -0.01676905 -0.001656711 -0.003220617 -0.0197317 -0.001895427 -0.003869771 -0.01972025 -0.001739025 -0.003975272 -0.02135896 -0.001942217 -0.004270613 -0.02269291 -0.002126336 -0.00450766 -0.02564394 -0.002626538 -0.004968106 -0.0285421 -0.003506302 -0.005153059 -0.02854621 -0.0033679 -0.005221247 -0.02863317 -0.003533959 -0.005158841 -0.03134179 -0.004519581 -0.005140364 -0.0137642 -0.001610994 -0.002635538 -0.01674801 -0.001554727 -0.003296792 -0.0196098 -0.001281678 -0.004125356 -0.01969772 -0.001620173 -0.004046201 -0.02257531 -0.001456081 -0.004742324 -0.02266347 -0.00183767 -0.004692196 -0.02555251 -0.001883268 -0.005140125 -0.0256347 -0.002310574 -0.005123198 -0.0284599 -0.002717316 -0.005242824 -0.02853357 -0.003194689 -0.005257725 -0.0312435 -0.003797352 -0.005124151 -0.03132539 -0.004327535 -0.005165159 -0.03680855 -0.005791246 -0.004674911 -0.03693002 -0.006435573 -0.004776835 -0.04238718 -0.007676422 -0.004118859 -0.03696554 -0.006670415 -0.004781961 -0.04633194 -0.01023608 -0.004060268 -0.04265832 -0.008906245 -0.004335522 -0.03723818 -0.006944239 -0.004741668 -0.03698641 -0.00684446 -0.004753887 -0.03135985 -0.004614591 -0.005026638 -0.01318407 5.03547e-5 -0.002626061 -0.01339143 -5.21109e-4 -0.002674281 -0.01632881 -2.78665e-4 -0.003353834 -0.01365262 -0.001241028 -0.002735078 -0.01925402 -2.00002e-4 -0.003988683 -0.02220994 -2.62044e-4 -0.004504799 -0.02518999 -5.64261e-4 -0.004803895 -0.02810847 -0.001251041 -0.004825055 -0.0308755 -0.002170681 -0.004648447 -0.03636401 -0.003839075 -0.004088163 -0.04187232 -0.005366563 -0.003423273 -0.04746186 -0.006637334 -0.002740144 -0.05322027 -0.007465839 -0.002123892 -0.04038321 8.75465e-4 -0.00110048 -0.03909343 9.96158e-4 -0.001248598 -0.03570204 -0.001237094 -0.003053307 -0.03494644 0.001636147 -0.001742243 -0.03026992 3.14182e-5 -0.003682672 -0.02953469 0.002471446 -0.00238645 -0.02751451 7.4209e-4 -0.003911852 -0.02861368 0.002613544 -0.002496123 -0.02162122 0.001390695 -0.003810465 -0.01937532 0.00314784 -0.002688109 -0.01868534 0.001321196 -0.003440678 -0.01800483 0.002982318 -0.002550721 -0.01578879 0.001122057 -0.00295484 -0.02676641 0.0028553 -0.002620518 -0.02387183 0.003234028 -0.002815425 -0.02459251 0.001240074 -0.003981769 -0.02386009 0.00323379 -0.002815127 -0.02090835 0.003177225 -0.002731502 -0.01229125 0.002292275 -0.001978158 -0.01247966 0.001827478 -0.002131402 -0.07516407 4.64264e-6 7.62908e-4 -0.09835577 -1.85268e-5 0.00102669 -0.09571981 1.80509e-5 0.001036643 -0.09250599 1.59545e-5 9.93849e-4 -0.08077859 8.30553e-6 8.37676e-4 -0.01380354 -0.00181508 -0.002452135 -0.01379382 -0.001746833 -0.002533555 -0.01379144 -0.001729965 -0.002553701 -0.01378571 -0.001689255 -0.002602159 -0.06047153 -0.01298296 -0.003008723 -0.01290255 7.84012e-4 -0.00247544 -0.01304906 4.22449e-4 -0.002594649 -0.05239117 -0.003767192 -0.001039147 -0.05823528 -0.004040658 -6.47306e-4 -0.06317323 -4.71938e-5 5.30962e-4 -0.05768013 -7.09416e-5 4.24706e-4 -0.05731576 -6.1892e-5 4.00038e-4 -0.05154061 8.15531e-5 9.04407e-6 -0.04790151 1.71942e-4 -2.37335e-4 -0.01379144 -0.001844644 -0.002322971 -0.01378571 -0.00185883 -0.002261281 -0.01676106 -0.001791954 -0.002911627 -0.0137239 -0.001809597 -0.002003312 -0.0137183 -0.001802802 -0.001984953 -0.01668876 -0.001813411 -0.002662599 -0.03698539 -0.00700438 -0.004679083 -0.03698831 -0.00696361 -0.004710912 -0.03132998 -0.004758775 -0.005012869 -0.01376539 -0.001842677 -0.002176642 -0.01375317 -0.001832962 -0.00212562 -0.01673543 -0.001785159 -0.00277704 -0.03694301 -0.007053196 -0.004501163 -0.03695815 -0.007058143 -0.004553079 -0.03126692 -0.004833817 -0.004795134 -0.03980547 -0.008161544 -0.004409492 -0.04829275 -0.01120662 -0.003898322 -0.0484277 -0.01123964 -0.003890693 -0.04842931 -0.0112459 -0.003901839 -0.04697465 -0.01078331 -0.004003822 -0.04843139 -0.01124244 -0.003918349 -0.04843139 -0.01123815 -0.003921151 -0.05587548 -0.01291197 -0.003458797 -0.05436891 -0.01269215 -0.003554642 -0.05460625 -0.0127502 -0.003541171 -0.1060819 -0.01164817 -8.80739e-4 -0.1004049 -0.01236319 -0.001083314 -0.1060842 -0.01166194 -8.84102e-4 -0.1060845 -0.01166367 -8.84622e-4 -0.106086 -0.01167201 -8.87304e-4 -0.1060863 -0.01167392 -8.88169e-4 -0.1060864 -0.01167458 -8.88985e-4 -0.1060858 -0.01167094 -8.86834e-4 -0.1060854 -0.01166826 -8.86022e-4 -0.08613318 -0.01331335 -0.001692771 -0.08898937 -0.01314264 -0.00156778 -0.08329552 -0.01346009 -0.001805245 -0.09470188 -0.01280134 -0.001317799 -0.09469664 -0.01277822 -0.00130397 -0.09882026 -0.0125553 -0.001137554 -0.08325433 -0.01338279 -0.001766324 -0.09468168 -0.01271343 -0.001264035 -0.1003915 -0.012299 -0.0010522 -0.106081 -0.01164245 -8.79344e-4 -0.06609982 -0.01372456 -0.002747654 -0.06875121 -0.01391869 -0.002612113 -0.07182186 -0.01376777 -0.002388715 -0.07184815 -0.01385146 -0.002433419 -0.08013713 -0.01367157 -0.001955211 -0.06034588 -0.01321673 -0.003086566 -0.05434483 -0.0125854 -0.003541171 -0.06038492 -0.01339226 -0.003132224 -0.05436223 -0.01267713 -0.003557443 -0.03981882 -0.008129656 -0.004479408 -0.04266333 -0.009227037 -0.004294812 -0.04266357 -0.009211599 -0.004305601 -0.04552888 -0.01025766 -0.004116952 -0.04552739 -0.01023894 -0.004122853 -0.04842412 -0.01117116 -0.00393331 -0.04842942 -0.01121205 -0.003929495 -0.04697453 -0.01075679 -0.004020571 -0.0455296 -0.01027292 -0.004109919 -0.0484308 -0.01122695 -0.003925859 -0.04697519 -0.01077008 -0.00401467 -0.04552948 -0.01028466 -0.004101693 -0.04266232 -0.009239256 -0.004282891 -0.03981661 -0.008142232 -0.004463732 -0.03697937 -0.007033765 -0.004642128 -0.05663061 -0.01300823 -0.003409802 -0.05700898 -0.01305651 -0.003385245 -0.05738818 -0.01310485 -0.003360629 -0.0499137 -0.01160323 -0.003807127 -0.04843014 -0.01124984 -0.003908276 -0.05139946 -0.01196616 -0.003722608 -0.04843115 -0.01124578 -0.00391525 -0.04697501 -0.01077979 -0.004007697 -0.04552787 -0.0102958 -0.004087269 -0.04552692 -0.01029777 -0.004081904 -0.04265469 -0.009256184 -0.004240095 -0.04265064 -0.009255409 -0.004223644 -0.04697406 -0.01078599 -0.00399959 -0.04552447 -0.01029926 -0.004070401 -0.04264581 -0.009251415 -0.004206061 -0.04991358 -0.01160293 -0.00380665 -0.0226407 -0.002193152 -0.004182517 -0.022601 -0.002219855 -0.003980755 -0.02364265 -0.002324521 -0.004210412 -0.02558642 -0.002723693 -0.00465089 -0.02552402 -0.002787113 -0.004434347 -0.02724426 -0.003210067 -0.004639089 -0.02845811 -0.003656744 -0.004836082 -0.02839106 -0.00367093 -0.004646122 -0.01971244 -0.001911282 -0.00366187 -0.0196858 -0.001913428 -0.003520131 -0.0226705 -0.002183079 -0.004325807 -0.02562218 -0.002707719 -0.004790067 -0.02849942 -0.003638684 -0.004966557 -0.03130471 -0.004815757 -0.004915118 -0.03697025 -0.007051706 -0.004600107 -0.03981363 -0.00815171 -0.004446804 -0.04266053 -0.009248137 -0.004269778 -0.04265803 -0.009253799 -0.004255533 -0.04552859 -0.01029294 -0.004092395 -0.03092795 -0.004690349 -0.004661738 -0.03121972 -0.004804193 -0.004650413 -0.03692662 -0.007030904 -0.004429221 -0.04012602 -0.008279263 -0.004305243 -0.04266017 -0.009187638 -0.004179 -0.04264831 -0.009049057 -0.00434488 -0.03698819 -0.006911575 -0.004737496 -0.04840338 -0.0110439 -0.003926634 -0.05133682 -0.01181674 -0.003716289 -0.0543124 -0.01242703 -0.003505587 -0.05288469 -0.01232933 -0.003638565 -0.05436253 -0.01268625 -0.003555774 -0.03981983 -0.008048534 -0.004529833 -0.0398209 -0.008095264 -0.004507124 -0.0426566 -0.00911653 -0.004336714 -0.04266166 -0.009170711 -0.004323601 -0.04552197 -0.01019078 -0.004131138 -0.04841548 -0.01111519 -0.003932356 -0.04988867 -0.01158672 -0.003836691 -0.03133803 -0.004716217 -0.005053281 -0.02564501 -0.002659857 -0.004906237 -0.02268773 -0.002143442 -0.004447162 -0.02852797 -0.003585457 -0.005073964 -0.01379436 -0.001837551 -0.002354145 -0.01677489 -0.001772582 -0.003029167 -0.01972681 -0.00188148 -0.003783822 -0.0313189 -0.004792034 -0.004966795 -0.1060787 -0.01162886 -8.76541e-4 -0.1060679 -0.01156431 -8.63167e-4 -0.1060544 -0.01148349 -8.48407e-4 -0.08327716 -0.01348394 -0.001817762 -0.01964884 -0.001923084 -0.003330051 -0.01862692 -0.001820385 -0.003104805 -0.05891323 -0.01329922 -0.003261685 -0.06042027 -0.01349133 -0.003163874 -0.06149011 -0.0136277 -0.003094434 -0.06613093 -0.01381367 -0.002786159 -0.01318204 -8.13079e-4 -8.78134e-4 -0.01293742 -3.4851e-4 -3.99795e-4 -0.01588636 -2.82782e-4 -7.90174e-4 -0.05909377 -0.007944166 -0.001211106 -0.05925327 -0.004114449 -2.07736e-5 -0.06401413 -0.004149556 1.38759e-4 -0.1059515 -0.01087284 -6.8177e-4 -0.106 -0.01116287 -7.46045e-4 -0.1003179 -0.01187711 -8.94051e-4 -0.1060543 -0.01148748 -8.17969e-4 -0.1060658 -0.01155596 -8.33152e-4 -0.1003888 -0.01229232 -0.001013696 -0.1060863 -0.01167434 -8.85736e-4 -0.0124787 6.61417e-4 2.18396e-4 -0.01232916 9.9077e-4 4.19997e-4 -0.01524645 0.00107181 2.75653e-4 -0.1055528 -0.008490681 -1.53891e-4 -0.1057226 -0.009505212 -3.78708e-4 -0.1000194 -0.0101031 -4.89405e-4 -0.1055244 -0.008319735 -1.22238e-4 -0.06556993 -0.01134324 -0.001860857 -0.06677943 -0.004169881 2.31422e-4 -0.07131892 -0.01136136 -0.001555562 -0.06984072 -0.004111647 2.90298e-4 -0.08280438 -0.01100414 -0.001048862 -0.1047112 -0.003432095 7.82746e-4 -0.09893304 -0.003549695 7.57673e-4 -0.09312272 -0.00366795 7.32461e-4 -0.09428352 -0.01043385 -6.51071e-4 -0.09274619 -0.003675639 7.30826e-4 -0.08148682 -0.003889977 5.14281e-4 -0.02381652 4.85432e-4 -6.4303e-4 -0.0209884 8.43304e-4 -3.77127e-4 -0.02025353 0.00247246 9.41613e-4 -0.01948511 0.002543985 9.74711e-4 -0.01812613 0.001020073 -4.55114e-5 -0.01743066 0.0025267 0.001070976 -0.02304112 0.00221318 8.21542e-4 -0.02465337 0.002063155 7.52097e-4 -0.02659338 -1.45408e-4 -7.67349e-4 -0.02579379 0.001836717 7.48675e-4 -0.02943527 -9.46063e-4 -7.63818e-4 -0.02863222 0.001273095 7.40159e-4 -0.03417903 1.7173e-4 7.23515e-4 -0.03530603 -0.002556383 -8.27413e-4 -0.03450179 9.84762e-5 7.06732e-4 -0.04117804 -0.004297673 -0.001037776 -0.04037261 -0.001233816 4.01487e-4 -0.0470916 -0.005987048 -0.001257479 -0.05738812 -0.01310527 -0.003359973 -0.05437254 -0.0126962 -0.003541767 -0.06041431 -0.01352304 -0.003152668 -0.05137413 -0.01200073 -0.003682434 -0.05436748 -0.01268893 -0.003530621 -0.04844069 -0.0112285 -0.003854215 -0.05435365 -0.01267266 -0.003501594 -0.0513603 -0.01202011 -0.003661096 -0.05132812 -0.01191031 -0.003569245 -0.04836624 -0.01108217 -0.00369656 -0.04840391 -0.0111984 -0.003806591 -0.04260396 -0.009180903 -0.004063427 -0.02823835 -0.003478944 -0.004254341 -0.03105843 -0.004635393 -0.004240274 -0.04255175 -0.009055435 -0.003911674 -0.03680288 -0.006842315 -0.004088819 -0.02538573 -0.002557098 -0.004052281 -0.01933246 -0.001421868 -0.002458214 -0.02226215 -0.001714885 -0.003059089 -0.01639664 -0.001274883 -0.00181061 -0.0136618 -0.001724302 -0.001816332 -0.01365607 -0.001713395 -0.001805126 -0.01341503 -0.001255571 -0.001333713 -0.1060857 -0.011671 -8.80268e-4 -0.106086 -0.01167249 -8.82682e-4 -0.1060861 -0.01167327 -8.84006e-4 -0.1004005 -0.01234281 -0.001064419 -0.1060834 -0.0116589 -8.70684e-4 -0.1060845 -0.0116648 -8.75389e-4 -0.1060724 -0.01159524 -8.41852e-4 -0.1060786 -0.0116313 -8.58189e-4 -0.1060814 -0.01164716 -8.65379e-4 -0.0832768 -0.01350802 -0.001787781 -0.09470146 -0.01282733 -0.001286268 -0.09755873 -0.01265078 -0.001181185 -0.09469693 -0.01280909 -0.001264035 -0.0947014 -0.01283228 -0.001280367 -0.08327674 -0.01351344 -0.001781165 -0.09467869 -0.0127089 -0.001220941 -0.07756274 -0.01377403 -0.002084612 -0.07184708 -0.01390743 -0.00240314 -0.0718472 -0.0138992 -0.002407491 -0.06612724 -0.01385712 -0.002766788 -0.06612652 -0.01386564 -0.002763152 -0.06041288 -0.01353114 -0.003149986 -0.0832718 -0.01348966 -0.001761972 -0.07184165 -0.01388394 -0.002381205 -0.0661208 -0.0138427 -0.002740263 -0.06040674 -0.01350921 -0.00312674 -0.08325147 -0.01338553 -0.001711547 -0.05432558 -0.01256871 -0.003424465 -0.057343 -0.01306307 -0.003258347 -0.06038147 -0.01340955 -0.003063976 -0.06609696 -0.01373976 -0.002679407 -0.07181912 -0.0137794 -0.002323329 -0.09460282 -0.01227772 -0.001090884 -0.08316594 -0.01293522 -0.001559913 -0.07172369 -0.01332348 -0.00214827 -0.06599634 -0.01328873 -0.002493798 -0.06027537 -0.01297086 -0.002870082 -0.05723792 -0.01262789 -0.003053426 -0.0542171 -0.01213079 -0.003196597 -0.0512126 -0.0114668 -0.003309071 -0.04824066 -0.01063334 -0.003397226 -0.04239749 -0.008606851 -0.003523349 -0.03661513 -0.00641632 -0.003614962 -0.03083491 -0.004258394 -0.00370872 -0.02800762 -0.003137052 -0.003710091 -0.02516967 -0.002241134 -0.003506898 -0.01458579 0.002502799 0.001204371 -0.01352816 0.002493917 0.001253962 -0.01171034 0.002353072 0.001253902 -0.04535174 -0.002363801 1.42601e-4 -0.04628598 -0.002526342 1.08692e-4 -0.05007845 -0.006699085 -0.001329481 -0.05224007 -0.003562033 -1.07422e-4 -0.05308347 -0.007267534 -0.001356184 -0.05247694 -0.003603219 -1.16017e-4 -0.05609017 -0.007683277 -0.001322925 -0.05522578 -0.003810644 -7.73808e-5 -0.05819535 -0.004034638 -3.56431e-5 -0.01879829 -4.0113e-4 -0.001293241 -0.0216971 -6.57309e-4 -0.001779794 -0.02456611 -0.001123785 -0.002156555 -0.02737337 -0.001916944 -0.002336859 -0.03021186 -0.002911329 -0.002346456 -0.03605186 -0.004863977 -0.002352654 -0.04189217 -0.006904065 -0.002429544 -0.04778313 -0.00883466 -0.002488136 -0.05076903 -0.009639084 -0.002483665 -0.05378043 -0.01028162 -0.002442181 -0.05680042 -0.01075839 -0.002352774 -0.05982685 -0.01107418 -0.002200782 -0.1286989 -0.00490117 -1.12772e-4 -0.1260732 -0.006284773 -2.19258e-4 -0.1273871 -0.005592465 -1.65975e-4 -0.1119046 -0.01033234 -6.70665e-4 -0.1090006 -0.01109749 -7.94702e-4 -0.1247598 -0.006976842 -2.72525e-4 -0.1234663 -0.00753057 -3.08566e-4 -0.1191716 -0.008935272 -4.62362e-4 -0.1177201 -0.009248971 -5.09794e-4 -0.1191151 -0.008953213 -4.64213e-4 -0.1226651 -0.006201922 -1.6073e-4 -0.1241767 -0.001613259 2.86692e-4 -0.1211571 -0.006418824 -1.67396e-4 -0.1224576 -0.001222729 3.75255e-4 -0.11806 -0.006821274 -1.81989e-4 -0.1257838 -0.001978337 2.03902e-4 -0.1241171 -0.005972445 -1.55646e-4 -0.1270361 -0.002688527 9.0295e-5 -0.1254581 -0.005748927 -1.58082e-4 -0.1177293 -0.00923711 -5.03647e-4 -0.1178051 -0.008684873 -4.24234e-4 -0.1207416 -0.008052647 -3.4725e-4 -0.1235924 -0.00722903 -2.76372e-4 -0.1262465 -0.006174504 -2.11775e-4 -0.1241042 -0.007322371 -2.99115e-4 -0.1238963 -0.007431864 -3.07544e-4 -0.1234148 -0.007585108 -3.23324e-4 -0.1220005 -0.008035123 -3.69665e-4 -0.1206418 -0.008444607 -3.94406e-4 -0.1205851 -0.008485496 -4.16045e-4 -0.1277077 -0.005236268 -1.53476e-4 -0.1266336 -0.005516707 -1.62642e-4 -0.1118016 -0.007558465 -2.41931e-4 -0.1118847 -0.009795784 -5.83392e-4 -0.1074893 -0.01141786 -8.44081e-4 -0.1119094 -0.01045864 -6.93689e-4 -0.1119071 -0.01048129 -6.99731e-4 -0.1148136 -0.009865105 -6.04762e-4 -0.1177438 -0.009131848 -4.86835e-4 -0.128466 -0.004327535 -1.16847e-4 -0.1283736 -0.004206836 -1.02085e-4 -0.1278085 -0.003468573 -1.17528e-5 -0.1273457 -0.002864062 6.221e-5 -0.1167513 -7.61691e-4 6.4156e-4 -0.1188661 -9.32559e-4 5.42866e-4 -0.1044356 -0.001772344 0.001074373 -0.1041673 -1.56303e-4 0.001352608 -0.1115396 -4.90195e-4 0.001101672 -0.1119095 -0.01046103 -6.76881e-4 -0.1188446 0.007750272 0.001846075 -0.1200129 0.007448732 0.001726806 -0.1200129 0.007427334 0.001745343 -0.1111926 0.008871912 0.002418935 -0.1112759 0.00662291 0.002146959 -0.1028103 0.008036911 0.002649247 -0.1030443 0.006619513 0.002455294 -0.1289623 -0.004054427 -8.75536e-5 -0.1285909 -0.004566311 -1.00075e-4 -0.129461 0.00120455 4.62035e-4 -0.1295183 0.001056551 4.41157e-4 -0.1295217 6.55644e-4 3.894e-4 -0.1262477 -0.006176769 -1.8628e-4 -0.1206424 -0.008447408 -3.68077e-4 -0.1022495 0.0114445 0.003060638 -0.1022489 0.01144897 0.003057837 -0.1111598 0.009562075 0.002441942 -0.1022487 0.01145046 0.003056883 -0.1177296 -0.009238839 -4.89542e-4 -0.1234667 -0.007532477 -2.87308e-4 -0.1235932 -0.007233321 -2.30786e-4 -0.1180629 -0.00683844 -4.54313e-5 -0.12116 -0.006432116 -4.50774e-5 -0.120743 -0.008058667 -2.90791e-4 -0.1290954 -0.001345098 2.24064e-4 -0.1283877 -0.004199326 -5.51534e-5 -0.1278664 -0.003435671 8.13901e-5 -0.1277083 -0.005237877 -1.25119e-4 -0.1266358 -0.005521714 -1.074e-4 -0.1220061 0.006934344 0.001523375 -0.1222049 0.006838917 0.001513719 -0.1199988 0.007319033 0.001749038 -0.1221861 0.006736755 0.001518368 -0.1199381 0.006866276 0.001725196 -0.1243154 0.005979537 0.001280307 -0.1243303 0.00606364 0.001263618 -0.1222057 0.00685954 0.001501023 -0.1221055 0.006309211 0.001500308 -0.124216 0.005583107 0.00126785 -0.1263254 0.004948258 0.001052677 -0.1262099 0.004591941 0.001044869 -0.1272933 0.004411339 9.25828e-4 -0.1272928 0.004410684 9.25799e-4 -0.126324 0.004999995 0.001036882 -0.1253539 0.005589187 0.001148104 -0.1249632 0.005826532 0.001192927 -0.1196841 0.004994153 0.001541256 -0.1217687 0.004540562 0.001344501 -0.1238012 0.003942489 0.001140296 -0.1257285 0.003116846 9.42979e-4 -0.1274532 0.00199747 7.44642e-4 -0.1290667 -0.003159224 -8.86293e-6 -0.1254606 -0.005756676 -7.8171e-5 -0.1270718 -0.002649128 2.44687e-4 -0.1275207 -0.003040432 1.62117e-4 -0.1286813 4.65471e-4 5.00848e-4 -0.1289733 -4.3053e-4 3.60671e-4 -0.1291874 0.001449286 5.5342e-4 -0.1294299 3.93893e-4 3.99275e-4 -0.1281035 0.003563702 8.27289e-4 -0.128077 0.003598809 8.05276e-4 -0.128846 0.00275737 6.93736e-4 -0.1288515 0.002777576 6.83991e-4 -0.1288532 0.002773404 6.8942e-4 -0.1288445 0.002795755 6.86556e-4 -0.1284691 0.00318849 7.44617e-4 -0.1288162 0.002692103 6.99344e-4 -0.1286897 0.002418875 6.96911e-4 -0.1281625 0.001287639 6.30826e-4 -0.1264865 -0.002293765 3.2028e-4 -0.1241189 -0.005981922 -5.68782e-5 -0.1290535 0.002256393 6.10448e-4 -0.122667 -0.006213188 -4.85354e-5 -0.1292804 -0.002831041 -4.2594e-6 -0.1290794 -0.003893077 -8.86936e-5 -0.1295311 -4.75977e-4 2.43321e-4 -0.1295382 -0.001336753 1.32202e-4 -0.1294818 -6.84803e-4 2.49567e-4 -0.1294937 -0.001601397 1.0824e-4 -0.1293054 -0.002721607 6.80983e-6 -0.1291075 -0.003854274 -9.11234e-5 -0.1292111 -0.003282487 -4.39733e-5 -0.1291142 -0.003845095 -9.26885e-5 -0.1291179 -0.00383687 -9.41711e-5 -0.1292578 0.001728951 5.36035e-4 -0.1295264 9.01762e-5 3.16405e-4 -0.1273103 0.004401028 9.23881e-4 -0.1279777 0.003258943 8.23147e-4 -0.1022529 0.01142275 0.003066658 -0.1022506 0.01143687 0.003065407 -0.1022502 0.01143997 0.003063499 -0.1111676 0.009546637 0.002458691 -0.1111724 0.009416222 0.002460122 -0.1022803 0.01125282 0.003067016 -0.1022672 0.01133304 0.003071367 -0.1022636 0.01135498 0.003072559 -0.102256 0.01140296 0.003068387 -0.102383 0.01062673 0.003003597 -0.1023276 0.01096218 0.003049552 -0.1023198 0.01100933 0.003053724 -0.1125435 0.009268343 0.002346754 -0.1257866 -0.001996517 3.85093e-4 -0.1241983 -0.001553297 4.94031e-4 -0.1224816 -0.001250863 5.98644e-4 -0.1206958 -0.001056849 7.04702e-4 -0.1188746 -9.2994e-4 8.0489e-4 -0.1119049 -0.01033729 -6.35637e-4 -0.1118852 -0.009806513 -5.08287e-4 -0.1178065 -0.008692622 -3.61199e-4 -0.1177445 -0.009135425 -4.57438e-4 -0.1118026 -0.007582068 -7.92374e-5 -0.1291159 -0.003841936 -9.42596e-5 -0.1289076 -0.004371106 -1.03509e-4 -0.009411633 -0.002348542 -0.001899242 -0.0088045 -0.002489686 -0.001830756 -0.008783578 -0.00248599 -0.00173068 -0.005561411 0.001264333 8.31623e-4 -0.005533814 0.001339375 8.52116e-4 -0.006877958 0.001623153 9.63154e-4 -0.002890884 0.005857229 7.15594e-4 -0.005083322 0.006615757 0.001328229 -0.005085229 0.006556689 0.001431643 -7.09951e-4 0.00509876 1.30846e-4 -6.98924e-4 0.00509876 1.03028e-4 -8.21963e-4 0.005095541 2.40158e-4 -0.005102992 0.006457567 0.001524209 -9.72882e-4 0.00509119 3.87446e-4 -0.003020226 0.004526615 0.001197338 -0.005190849 0.006130337 0.001666784 -0.003295004 0.004346191 0.001235604 -0.005583286 0.004965901 0.0017277 -0.003843843 0.003985762 0.001312077 -0.002459585 0.004778206 0.001053094 -0.001578807 0.005020737 7.21868e-4 -9.74134e-4 0.00509119 3.8867e-4 -0.006198883 0.003325998 0.001461684 -0.005161106 0.002354264 0.001129209 -0.00474435 0.002988755 0.001239895 -0.004540026 0.003299772 0.001294136 -0.005698919 9.88087e-5 4.44104e-4 -0.007565736 -1.60802e-5 2.92928e-4 -0.00568217 -3.13424e-4 2.97395e-4 -0.00820899 -0.001454234 -5.17518e-4 -0.00549364 -0.00126326 -4.84064e-5 -0.005664467 -4.02573e-4 2.64939e-4 -0.005787551 -0.001951754 -3.98071e-4 -0.005165398 -0.002088904 -3.44906e-4 -0.005462408 -0.001420617 -1.05701e-4 -0.005018711 -0.002418935 -4.6302e-4 -0.006188571 -0.002833783 -0.001066505 -0.004359483 -0.003306806 -7.7499e-4 -0.004349529 -0.003316521 -7.79745e-4 -0.00628972 -0.003010869 -0.001353025 -0.00403434 -0.003625094 -9.30345e-4 -0.003922164 -0.003723561 -0.001142859 -0.003921449 -0.003726541 -0.001108467 -0.005310356 -0.003301799 -0.001436531 -0.006315767 -0.003036737 -0.001478612 -0.006339967 -0.003062486 -0.0015527 -0.003942847 -0.003705978 -0.001017093 -0.003933846 -0.003713607 -0.001038551 -0.003919363 -0.003725886 -0.001073122 -0.008545577 0.003795921 0.001782298 -0.01111656 0.003746986 0.001880049 -0.009271204 0.002044558 0.001146733 -0.0114175 0.003033757 0.001576364 -0.00971347 0.007414162 0.002608716 -0.00745958 0.006719052 0.002180635 -0.009694755 0.007469296 0.002605915 -0.007362306 0.00707066 0.002051889 -0.009656965 0.00761795 0.002525389 -0.009628593 0.007729411 0.002465009 -0.009770631 0.007245719 0.002617418 -0.01001369 0.006529271 0.002654254 -0.007884681 0.005496025 0.002169013 -0.01023471 0.005971729 0.002499163 -0.01051437 0.005266249 0.002302825 -0.01094269 0.004185616 0.00200212 -0.009626984 0.007742822 0.002447426 -0.007341563 0.007180273 0.001960933 -0.009625017 0.007759094 0.002426147 -0.007350206 0.007219612 0.001834928 -0.009617209 0.007823526 0.002341628 -0.008643448 -0.002311587 -0.001285433 -0.008754372 -0.002470254 -0.00159794 -0.01129847 -0.002119362 -0.002136766 -0.01128619 -0.002087593 -0.001956045 -0.01125681 -0.002079486 -0.001815378 -0.01114207 -0.001933097 -0.001476109 -0.01068526 -0.00108391 -6.11996e-4 -0.01000344 3.70617e-4 3.34635e-4 -0.0112946 -0.00198847 -0.002182006 -0.005096375 0.006638109 0.001212 -0.004781246 -0.002788662 -0.001824021 -0.004542589 -0.003071427 -0.001678884 -0.00622195 -0.002588748 -0.001951992 -0.006323933 -0.002976953 -0.001694798 -0.001766502 0.004983365 -3.26844e-4 -0.002828717 0.004615128 -5.62299e-4 -0.003402411 0.004836559 -4.43314e-4 -0.004671812 0.00313431 -0.00121212 -0.00527209 0.002120077 -0.001551866 -0.007001936 0.002528905 -0.001481831 -0.005309879 0.002003967 -0.001582324 -0.007681012 8.26106e-4 -0.001980364 -0.005589723 0.00114417 -0.001807987 -0.005684077 2.40792e-4 -0.001971125 -0.004310846 0.00350517 -0.001062035 -0.006314158 0.004168212 -8.11608e-4 -0.003840923 0.003988027 -8.66697e-4 -0.005670964 0.005606353 -1.16089e-6 -0.003723144 0.00406295 -8.30708e-4 -0.002887845 0.004594624 -5.75407e-4 -9.77576e-4 0.005090951 -1.5241e-4 -0.001330852 0.005042791 -2.30521e-4 -0.003001391 0.005718529 2.25147e-4 -0.002900242 0.005895674 5.11676e-4 -8.39636e-4 0.005095541 -8.7847e-5 -0.002874195 0.005921542 6.3727e-4 -7.00131e-4 0.005101978 5.76489e-5 -7.50139e-4 0.005098521 -4.5964e-5 -7.15032e-4 0.0050987 -3.08175e-6 -7.03722e-4 0.00509876 1.074e-5 -0.003971695 -0.003681182 -0.001243114 -0.003995895 -0.003658652 -0.001266002 -0.006306171 -0.002889811 -0.001790761 -0.00414294 -0.003521919 -0.001405179 -0.004233539 -0.003437638 -0.00149095 -0.005612373 -8.13575e-4 -0.002073228 -0.005608737 -8.51456e-4 -0.002076447 -0.005851626 -0.001481175 -0.002098977 -0.005365431 -0.001626133 -0.002040326 -0.005271971 -0.001923799 -0.002026438 -0.01127386 -0.001878857 -0.002272903 -0.01117658 -0.001527249 -0.002401709 -0.01075148 -3.04271e-4 -0.002390027 -0.01009058 0.001395821 -0.002003312 -0.008794724 -0.00240457 -0.001950323 -0.008776903 -0.002305448 -0.002042889 -0.008689105 -0.001978218 -0.002185463 -0.008296668 -8.1377e-4 -0.002246379 -0.005698919 9.88087e-5 -0.001996755 -0.005125582 0.006622374 0.001079261 -0.005236506 0.006463766 7.66811e-4 -0.009668409 0.007840514 0.002011835 -0.009637951 0.007867217 0.002133846 -0.009630143 0.007850706 0.002212285 -0.009627103 0.007844328 0.002242624 -0.009364962 0.003147184 -0.001367747 -0.01199686 0.00298959 -0.001680135 -0.1039033 0.001488387 0.001294136 -0.01395839 0.003983736 0.001989483 -0.03380089 0.002591669 0.001807987 -0.02903211 0.003322899 0.002006173 -0.02794867 0.003449738 0.002000212 -0.02509826 0.003783524 0.001984596 -0.02245837 0.004092633 0.001970171 -0.02235156 0.004092693 0.001971244 -0.01957464 0.004094183 0.00199896 -0.05682194 -2.8556e-4 0.001013875 -0.05143415 9.27048e-5 0.001054108 -0.0489481 2.67241e-4 0.001072704 -0.04554396 7.89887e-4 0.001252412 -0.03951829 0.001715004 0.001570463 -0.09249883 -7.01994e-5 0.001385211 -0.09835046 -1.1338e-4 0.00136888 -0.06317657 -2.84036e-4 0.001149892 -0.06540071 -2.83501e-4 0.001197516 -0.0690453 -2.39675e-4 0.001232385 -0.08669829 -2.73958e-5 0.001401424 -0.08077788 -9.85889e-5 0.00134474 -0.01531147 0.004096448 0.002041578 -0.01677095 0.004095673 0.002026975 -0.05731362 -2.85443e-4 0.001024425 -0.100938 0.01118999 0.003128468 -0.09637081 0.01172518 0.003302633 -0.09631752 0.01220542 0.003361642 -0.0261594 0.01060533 0.004602015 -0.02616775 0.01064938 0.004558861 -0.03177863 0.01117891 0.004760742 -0.02063971 0.01003241 0.003761529 -0.04859942 0.01276719 0.004423737 -0.03739756 0.01177841 0.004603385 -0.03739553 0.01176851 0.004620671 -0.03179711 0.0112729 0.004634261 -0.05423057 0.01309937 0.004371106 -0.05422097 0.01314491 0.004367351 -0.06624138 0.01359212 0.00409305 -0.0782786 0.01349365 0.003778457 -0.07828313 0.01346635 0.003786563 -0.09928011 0.01193672 0.003217697 -0.09630239 0.01230192 0.00335735 -0.09031009 0.01287525 0.003533124 -0.04859954 0.01276439 0.004434704 -0.05421459 0.01317799 0.004356145 -0.05421537 0.01317346 0.004358947 -0.05421769 0.0131613 0.004363715 -0.05424422 0.01303619 0.004370093 -0.06626272 0.01348179 0.004099011 -0.07830184 0.0133596 0.003792405 -0.09032618 0.01277446 0.003537714 -0.04019653 0.01199018 0.004585027 -0.0430004 0.01222282 0.004533886 -0.04300355 0.01219922 0.004540681 -0.04860991 0.01270103 0.004455149 -0.04019594 0.01200658 0.004573166 -0.04019612 0.01201939 0.004560053 -0.04299807 0.01224261 0.004525899 -0.04299664 0.01225858 0.004516661 -0.0458005 0.01249557 0.004483401 -0.02060341 0.01001584 0.0039047 -0.01506888 0.009067773 0.003109037 -0.01509594 0.009069383 0.002965033 -0.02619385 0.01070892 0.004455089 -0.02623265 0.01072901 0.004328072 -0.03179204 0.0112645 0.004658758 -0.03180295 0.01127839 0.004608511 -0.03740042 0.01178497 0.004584848 -0.04019713 0.01202863 0.004545688 -0.04299604 0.01227086 0.00450623 -0.04579859 0.01251083 0.004476249 -0.04860079 0.01275455 0.004441618 -0.04860293 0.01274079 0.00444734 -0.04860597 0.0127229 0.004451811 -0.04299724 0.01228439 0.004481911 -0.04299622 0.01227945 0.004494667 -0.04020154 0.0120368 0.004513561 -0.04019898 0.01203441 0.004530251 -0.04579758 0.01253217 0.00445342 -0.0457974 0.01252979 0.004458546 -0.04439693 0.01240801 0.004469931 -0.04579758 0.01252222 0.004467964 -0.04439651 0.01240175 0.004480957 -0.04859912 0.01277035 0.004426717 -0.0542109 0.01317971 0.004350066 -0.04299807 0.01228553 0.004475116 -0.04299908 0.01228576 0.004468023 -0.045798 0.0125336 0.004447996 -0.04579865 0.01253414 0.004442274 -0.04300028 0.01228511 0.004460692 -0.031825 0.01127731 0.004523515 -0.03740841 0.01178818 0.004544198 -0.0318095 0.01128095 0.004581451 -0.037404 0.01178818 0.004565119 -0.03183394 0.01127117 0.00449264 -0.03741359 0.01178497 0.004522144 -0.05177789 0.01244139 0.004359483 -0.04306238 0.01185464 0.004581034 -0.04302489 0.012066 0.004555046 -0.03740006 0.0116387 0.004698157 -0.04020339 0.01191949 0.00461322 -0.03178167 0.01122182 0.004724025 -0.03458827 0.01146435 0.004721581 -0.03739529 0.0116955 0.004677474 -0.03534042 0.01133471 0.004777312 -0.03178477 0.01103675 0.004739701 -0.03177875 0.01112461 0.004791975 -0.02699416 0.01063525 0.004689037 -0.03742009 0.01147472 0.004724442 -0.02616024 0.01053053 0.004605889 -0.02058023 0.00996685 0.004024207 -0.02058404 0.009830176 0.004049956 -0.01818257 0.009528577 0.003810524 -0.01505434 0.009037911 0.003232777 -0.01507592 0.008910179 0.003277778 -0.02617919 0.01068401 0.004509925 -0.03178781 0.01125317 0.004681825 -0.03459054 0.01150101 0.004687368 -0.0373938 0.01173877 0.004651606 -0.09201705 0.01223534 0.003468632 -0.04719907 0.01264005 0.004455089 -0.04719829 0.01264882 0.004447042 -0.04859924 0.01276785 0.00443089 -0.05421274 0.01317876 0.004353106 -0.03739422 0.01175534 0.004636764 -0.04019796 0.01197022 0.004595696 -0.04301244 0.01214045 0.004550457 -0.05428415 0.01285511 0.004352927 -0.05434364 0.01254844 0.004306852 -0.0903927 0.01232504 0.003502845 -0.0811904 0.01283329 0.003696382 -0.07838004 0.01286858 0.003764986 -0.06635159 0.01301956 0.00405848 -0.06579911 0.01302653 0.00407195 -0.01276689 0.006996631 0.003091394 -0.09714788 0.007158339 0.002663016 -0.01330214 0.005606949 0.002698779 -0.04974621 0.007494091 0.003241062 -0.04396307 0.007634997 0.003512203 -0.04338008 0.01030653 0.004251718 -0.07873171 0.01100277 0.003477692 -0.07931429 0.007836341 0.002918303 -0.066747 0.01107031 0.003726303 -0.06740182 0.007837831 0.003070652 -0.05477702 0.01068663 0.003913462 -0.05549925 0.007545232 0.003140807 -0.04908901 0.01046007 0.004030466 -0.09121346 0.007520914 0.002777338 -0.04318529 0.01123762 0.00445646 -0.05451983 0.01181215 0.004163503 -0.0150609 0.008895158 0.003425717 -0.02057284 0.009770035 0.004195988 -0.01508331 0.008776843 0.003496944 -0.01517045 0.008440554 0.003577232 -0.02067178 0.009188652 0.004268586 -0.0205903 0.009615123 0.004247426 -0.02625131 0.009679675 0.004694163 -0.02617084 0.0102114 0.004725754 -0.03195565 0.009992003 0.004768729 -0.03183579 0.01063996 0.004853785 -0.03766727 0.01017922 0.004549086 -0.03750938 0.01096481 0.004695713 -0.02615499 0.010405 0.00469619 -0.03180098 0.0108776 0.00484997 -0.03817945 0.007867872 0.00389111 -0.03239601 0.008040845 0.004208683 -0.02661526 0.008056879 0.004235506 -0.02103108 0.007876336 0.00394237 -0.01552283 0.007367312 0.003445506 -0.05057305 0.003803551 0.002169549 -0.04472428 0.004248917 0.002434909 -0.03888773 0.00486803 0.00282979 -0.03305357 0.005449354 0.003186345 -0.02721619 0.005865752 0.003281354 -0.02162361 0.00608313 0.003130555 -0.01608651 0.005857348 0.002905368 -0.05639559 0.003665268 0.002117455 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.9965841 -0.08258438 0 -0.9965841 0.08258438 0 -0.9965841 0.08258438 0 -0.9458234 0.3246817 0 -0.9458234 0.3246817 0 -0.7891305 0.6142256 0 -0.7891305 0.6142256 0 -0.546954 0.8371627 0 -0.546954 0.8371627 0 -0.2454884 0.9693995 0 -0.2454884 0.9693995 0 0.08258092 0.9965845 0 0.08258092 0.9965845 0 0.4016861 0.9157774 0 0.4016861 0.9157774 0 0.6772947 0.7357119 0 0.6772947 0.7357119 0 0.8794687 0.4759566 0 0.8794687 0.4759566 0 0.9863623 0.1645883 0 0.9863623 0.1645883 0 0.9863623 -0.1645883 0 0.9863623 -0.1645883 0 0.8794683 -0.4759573 0 0.8794683 -0.4759573 0 0.6772947 -0.7357119 0 0.6772947 -0.7357119 0 0.4016878 -0.9157767 0 0.4016878 -0.9157767 0 0.08258092 -0.9965845 0 0.08258092 -0.9965845 0 -0.2454884 -0.9693995 0 -0.2454884 -0.9693995 0 -0.546954 -0.8371627 0 -0.546954 -0.8371627 0 -0.7891312 -0.6142247 0 -0.7891312 -0.6142247 0 -0.9458231 -0.3246823 0 -0.9458231 -0.3246823 0 -0.9965841 -0.08258438 0 0.9989943 -0.04483824 0 0.9989943 0.04483824 0 0.9989943 0.04483824 0 0.9839274 0.1785689 0 0.9839274 0.1785689 0 0.9362366 0.3513705 0 0.9362366 0.3513705 0 0.8584481 0.5129004 0 0.8584481 0.5129004 0 0.753071 0.6579392 0 0.753071 0.6579392 0 0.6234884 0.7818326 0 0.6234884 0.7818326 0 0.4738689 0.8805955 0 0.4738689 0.8805955 0 0.3090192 0.9510558 0 0.3090192 0.9510558 0 0.1342313 0.9909501 0 0.1342313 0.9909501 0 -0.0448628 0.9989932 0 -0.0448628 0.9989932 0 -0.2225205 0.974928 0 -0.2225205 0.974928 0 -0.3930248 0.9195279 0 -0.3930248 0.9195279 0 -0.5509014 0.8345704 0 -0.5509014 0.8345704 0 -0.6910575 0.7227998 0 -0.6910575 0.7227998 0 -0.8090196 0.5877817 0 -0.8090196 0.5877817 0 -0.9009664 0.4338888 0 -0.9009664 0.4338888 0 -0.9639638 0.2660337 0 -0.9639638 0.2660337 0 -0.9959741 0.08964198 0 -0.9959741 0.08964198 0 -0.9959741 -0.08964198 0 -0.9959741 -0.08964198 0 -0.9639637 -0.266034 0 -0.9639637 -0.266034 0 -0.9009668 -0.433888 0 -0.9009668 -0.433888 0 -0.8090192 -0.5877822 0 -0.8090192 -0.5877822 0 -0.6910575 -0.7227998 0 -0.6910575 -0.7227998 0 -0.5509014 -0.8345704 0 -0.5509014 -0.8345704 0 -0.3930248 -0.9195279 0 -0.3930248 -0.9195279 0 -0.2225195 -0.9749282 0 -0.2225195 -0.9749282 0 -0.04486489 -0.9989931 0 -0.04486489 -0.9989931 0 0.1342323 -0.9909499 0 0.1342323 -0.9909499 0 0.3090201 -0.9510555 0 0.3090201 -0.9510555 0 0.4738689 -0.8805955 0 0.4738689 -0.8805955 0 0.6234877 -0.7818331 0 0.6234877 -0.7818331 0 0.753071 -0.6579392 0 0.753071 -0.6579392 0 0.8584481 -0.5129004 0 0.8584481 -0.5129004 0 0.9362366 -0.3513705 0 0.9362366 -0.3513705 0 0.9839274 -0.1785689 0 0.9839274 -0.1785689 0 0.9989943 -0.04483824 0 -0.4999995 -0.8660258 0 -0.4999995 -0.8660258 0 0.4999995 -0.8660258 0 0.4999995 -0.8660258 0 1 0 0 1 0 0 0.4999997 0.8660256 0 0.4999997 0.8660256 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 -1 0 0 -1 0 0 -0.8315983 0 -0.5553776 -0.9807735 0 -0.1951498 -0.9807735 0 -0.1951498 -0.8968206 -0.001491665 -0.442392 -0.7074394 9.97705e-4 -0.7067734 -0.5550361 9.7822e-4 -0.8318256 -0.7068079 -0.001220107 -0.7074044 -0.2590129 7.38622e-4 -0.9658735 -0.2592328 7.38624e-4 -0.9658146 -0.1951038 0 -0.9807826 -0.4895182 -0.8498637 -0.1952022 -0.4508891 -0.7749888 -0.442822 -0.490391 -0.8493832 -0.1951017 -0.4484265 -0.776697 -0.4423295 -0.353557 -0.6123784 -0.7070999 -0.3535583 -0.6123806 -0.7070973 -0.3535615 -0.6123862 -0.7070908 -0.3535633 -0.612389 -0.7070875 -0.1293887 -0.2241076 -0.965937 -0.1293556 -0.2240509 -0.9659546 -0.1294133 -0.2241508 -0.9659236 -0.129415 -0.2241538 -0.9659228 0.490391 -0.8493832 -0.1951017 0.4153774 -0.7204593 -0.5553378 0.4484257 -0.7766973 -0.4423297 0.4903917 -0.8493847 -0.1950936 0.1260669 -0.2242044 -0.9663538 0.3545689 -0.6121364 -0.7068025 0.3545644 -0.6121287 -0.7068116 0.2782167 -0.4804821 -0.8317044 0.09798151 -0.1682361 -0.980865 0.1294134 -0.2241508 -0.9659237 0.9807735 0 -0.1951498 0.9807735 0 -0.1951498 0.8315983 0 -0.5553776 0.8315984 0 -0.5553777 0.5554269 0 -0.8315653 0.5554269 0 -0.8315654 0.1951038 0 -0.9807825 0.1951038 0 -0.9807826 0.490392 0.8493847 -0.1950935 0.490389 0.84938 -0.1951211 0.4157315 0.7200692 -0.5555786 0.4157686 0.7201306 -0.5554713 0.2777905 0.481146 -0.8314631 0.2777487 0.4810758 -0.8315177 0.09754443 0.1689523 -0.9807855 0.09754836 0.168959 -0.9807841 -0.4999997 0.8660256 0 -0.4999997 0.8660256 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.4903892 0.8493798 -0.1951216 -0.4903916 0.8493846 -0.1950947 -0.4157676 0.7201317 -0.5554708 -0.4157332 0.7200692 -0.5555775 -0.2777497 0.4810753 -0.8315178 -0.2777892 0.481146 -0.8314636 -0.09754818 0.1689587 -0.980784 -0.09754455 0.1689523 -0.9807855 0.9380454 0.3430646 -0.04875952 0.9409648 0.3349634 -0.04883366 0.9403008 0.3368203 -0.04885131 0.93853 0.3417016 -0.04900509 0.9422903 0.3312187 -0.04881608 0.9415481 0.3333531 -0.04861205 0.9380727 0.3429123 -0.04930436 0.9428136 0.3297684 -0.04853159 0.9527161 0.3005969 -0.04442471 0.9373074 0.3449735 -0.04947817 0.9336611 0.3545888 -0.05043691 0.947466 0.3161603 -0.04848611 0.9450699 0.3232786 -0.04831117 0.9403218 0.3367503 -0.0489304 0.9392864 0.3396136 -0.04902738 0.942059 0.3319129 -0.04856538 0.9350586 0.3509337 -0.05010902 0.9414962 0.3334573 -0.04889941 0.9788835 0.2017417 -0.03297644 0.9217047 0.3840562 -0.05441743 0.9535511 0.297795 -0.04537087 -0.1311252 -0.5000443 -0.8560151 -0.0688709 -0.4042395 -0.9120566 -0.001876413 -0.4185613 -0.9081866 0.1162558 -0.4212833 -0.899447 -1.02014e-4 -0.296878 -0.9549154 -1.02205e-4 -0.296878 -0.9549154 -0.08186966 -0.1619176 -0.9834023 -0.08583837 -0.1467799 -0.9854376 -0.08583825 -0.1467751 -0.9854384 -0.02561122 -0.1715323 -0.9848455 0.01218891 -0.4196318 -0.9076126 0.01218926 -0.4196316 -0.9076127 0.01218873 -0.4196316 -0.9076128 8.01087e-4 -0.4764463 -0.8792032 0.006049335 -0.4578118 -0.8890287 0.006049931 -0.4578116 -0.8890287 0.02466833 -0.5837358 -0.8115689 0.02466678 -0.5837358 -0.8115689 0.001665353 -0.4781582 -0.8782721 0.001665651 -0.4781582 -0.8782721 0.001665294 -0.4781582 -0.8782722 0.02466726 -0.5837368 -0.8115682 0.0400893 -0.3973282 -0.9168006 0.07103389 -0.5656813 -0.8215587 0.1164069 -0.06388795 -0.9911447 0.07103347 -0.5656828 -0.8215578 0.0710566 -0.5656813 -0.8215568 0.1349163 -0.4309611 -0.8922276 0.12598 -0.4229915 -0.8973335 0.1340265 -0.3818452 -0.9144567 0.1340258 -0.381847 -0.914456 0.1372376 -0.4377768 -0.8885479 0.1372385 -0.4377768 -0.8885477 0.1356312 -0.4348004 -0.8902543 0.1368671 -0.4303781 -0.8922119 0.1349198 -0.4309611 -0.8922272 -0.001875996 -0.4185613 -0.9081866 0.07891064 -0.6325629 -0.7704785 0.06039518 -0.585294 -0.8085687 0.07915318 -0.5024366 -0.8609832 0.07915198 -0.5024381 -0.8609826 -0.04691398 -0.405321 -0.9129699 -0.07657581 -0.4869766 -0.8700518 -0.07657372 -0.4869746 -0.870053 -0.1328992 -0.4993215 -0.8561635 -0.1328994 -0.4993232 -0.8561624 -0.06886994 -0.4042388 -0.9120571 -0.09809774 -0.4371743 -0.8940109 -0.1128863 -0.4122359 -0.9040566 -0.1223078 -0.4116028 -0.903119 -0.1155956 -0.4313455 -0.8947506 -0.1109182 -0.4315911 -0.8952242 -0.1151349 -0.4280922 -0.8963711 -0.1196589 -0.8030235 -0.5838108 -0.1225029 -0.6281058 -0.7684245 -0.08677548 -0.8125397 -0.5764107 -0.1331525 -0.892162 -0.4316451 -0.1304385 -0.8925052 -0.431764 -0.1169155 -0.8903505 -0.4400076 -0.06644421 -0.9154826 -0.3968335 -0.1095567 -0.9116168 -0.3961718 -0.1016619 -0.9234326 -0.3700502 -0.115778 -0.9226696 -0.3677991 -0.1157803 -0.9226694 -0.3677991 -0.09175717 -0.9475699 -0.3060912 -0.0917533 -0.9475714 -0.3060875 -0.05960422 -0.8811451 -0.4690744 -0.05960422 -0.881145 -0.4690744 -0.06087249 -0.870874 -0.4877222 -0.05529886 -0.731957 -0.6791031 -0.05529886 -0.7319569 -0.6791032 -0.05589699 -0.8643876 -0.4997096 -0.07867997 -0.915652 -0.3941967 -0.05960458 -0.8811451 -0.4690744 -0.05529826 -0.731957 -0.679103 -0.05101662 -0.7108609 -0.7014799 -0.06018793 -0.6089349 -0.7909334 -0.06018805 -0.6089349 -0.7909334 -0.02208614 -0.4258161 -0.9045401 -0.03985726 -0.3742344 -0.9264772 0.01082181 -0.1712258 -0.9851723 -0.03886187 -0.3737384 -0.9267197 -0.03985929 -0.3742344 -0.9264771 0.01868367 0.02934634 -0.9993947 -0.01746702 -0.09026008 -0.995765 -0.01746672 -0.09026008 -0.995765 -0.01670682 0.110915 -0.9936895 -0.01670676 0.110915 -0.9936895 -0.003880858 0.08398526 -0.9964594 -0.02423828 0.07883024 -0.9965934 -0.03069788 0.06903153 -0.9971421 -0.02734607 0.1471633 -0.9887341 -0.02686202 0.1463497 -0.9888682 -0.02734661 0.1471646 -0.9887339 -0.02379977 0.1082229 -0.9938417 -0.01972085 0.05536258 -0.9982716 -0.03639823 0.1434888 -0.9889824 -0.03639757 0.1434888 -0.9889824 -0.03639972 0.1434916 -0.9889819 -0.06759685 0.07744729 -0.9947023 -0.05830138 0.1464604 -0.9874969 -0.04939919 0.1464515 -0.9879836 -0.05358636 0.1079321 -0.992713 -0.05358642 0.1079319 -0.992713 -0.07574576 -0.8082292 -0.583976 -0.1353151 -0.7981218 -0.5871042 -0.1325113 -0.7735462 -0.6197314 -0.1195143 -0.7750259 -0.6205251 -0.1182417 -0.7722589 -0.6242076 -0.09042978 -0.7749918 -0.625468 -0.05064237 -0.7521716 -0.6570184 0.003038644 -0.754163 -0.6566804 0.01748538 -0.7899345 -0.6129419 0.066549 -0.6823608 -0.7279801 0.08416944 -0.6817949 -0.7266852 -0.1400623 -0.9073861 -0.396274 -0.1436218 -0.8523633 -0.5028416 -0.1060163 -0.8569001 -0.5044628 -0.07586771 -0.796727 -0.5995584 -0.06966233 -0.8101553 -0.5820615 0.01641279 -0.8133866 -0.581492 -0.1007203 -0.8947705 -0.4350185 -0.09987878 -0.9052579 -0.4129555 -0.0240429 -0.9102374 -0.4133882 -0.02176392 -0.7776618 -0.628306 0.04125481 -0.7780388 -0.6268602 -0.104348 -0.9018427 -0.4192748 -0.1222233 -0.8581126 -0.4987025 -0.002711057 -0.8660871 -0.4998857 0.001810729 -0.7310308 -0.6823421 0.04488533 -0.7310075 -0.6808915 0.07587075 -0.6001139 -0.7963083 0.05062854 -0.6006283 -0.7979238 0.08964669 -0.4943887 -0.8646059 -0.02424007 0.07883024 -0.9965933 -0.02422416 0.07882833 -0.9965938 -0.005174994 -0.01957845 -0.9997949 0.01723879 -0.01956796 -0.99966 0.04359602 -0.1678888 -0.9848414 0.01096385 -0.1680603 -0.9857157 0.04472452 -0.3775762 -0.9248979 -0.0197913 -0.3777983 -0.9256764 0.0175327 -0.5815984 -0.8132871 -0.04701298 -0.5807902 -0.8126947 -0.002527117 -0.7520821 -0.6590647 -0.03023898 -0.7515741 -0.6589552 -0.009804546 -0.8629055 -0.5052705 -0.06110936 -0.8609207 -0.5050558 -0.0301119 -0.2285598 -0.9730641 -0.03242826 -0.2379524 -0.9707352 0.001413762 -0.2387192 -0.9710876 -0.00210911 -0.2524928 -0.9675965 0.07250469 -0.2531747 -0.9646998 0.06045323 -0.2965191 -0.9531117 0.1053479 -0.2962033 -0.9492973 0.07772636 -0.3856083 -0.9193828 0.06822878 -0.3857122 -0.9200929 -0.03257793 -0.1176062 -0.9925258 -0.03239113 -0.1168122 -0.9926257 -9.95556e-4 -0.117223 -0.9931051 -0.006886899 -0.1419777 -0.9898459 0.06465864 -0.142371 -0.9876993 0.04169571 -0.2340631 -0.9713269 0.08592301 -0.2338195 -0.9684759 0.04456734 -0.3803453 -0.9237701 0.0685817 -0.3800679 -0.9224125 0.02113944 -0.5291374 -0.8482728 0.05569148 -0.5288138 -0.8469088 0.002515017 -0.6749839 -0.7378281 0.0286017 -0.675015 -0.7372493 -0.007751584 -0.8225014 -0.5687102 -0.04882901 -0.8211048 -0.568685 -0.04838275 -0.8819656 -0.4688239 -0.09175282 -0.9475703 -0.3060913 -0.06032317 -0.1321178 -0.9893968 -0.06592416 -0.1529336 -0.9860352 -0.1116858 -0.1514757 -0.9821311 -0.1244434 -0.1756855 -0.9765492 -0.07263606 -0.1775785 -0.9814224 -0.06793016 -0.1658967 -0.9838007 -0.05721205 -0.1662046 -0.9844301 -0.05423992 -0.001174747 -0.9985273 -0.05769979 -0.01363468 -0.998241 -0.07088923 -0.01345336 -0.9973935 -0.1095229 -0.07365304 -0.9912517 -0.03844475 -0.1003425 -0.9942098 -0.03844439 -0.1003425 -0.99421 -0.02285265 -0.4384536 -0.8984633 -0.01110947 -0.3320993 -0.943179 -0.01232504 -0.3859761 -0.9224264 0.01523506 -0.3866919 -0.922083 -0.02561122 -0.1715323 -0.9848456 -0.05729997 -0.1715476 -0.983508 -0.04463446 -0.1719042 -0.9841019 -0.06824851 -0.1828023 -0.9807779 -0.0748561 -0.1825842 -0.9803365 -0.1253906 -0.2297077 -0.9651485 -0.06548309 -0.232334 -0.9704292 -0.06714779 -0.2384826 -0.9688226 -0.01278388 -0.240171 -0.9706465 -0.0120272 -0.1331825 -0.9910185 -0.01710569 -0.1713117 -0.9850683 -0.0154547 -0.001627206 -0.9998793 -0.02323275 -0.0590372 -0.9979854 -0.02026629 0.118122 -0.9927922 -0.0311501 0.05541044 -0.9979777 -0.03073811 0.07164406 -0.9969566 -0.02686172 0.1463497 -0.9888681 -0.006346523 -0.1780343 -0.9840039 -0.04517441 -0.1976134 -0.9792385 -0.03993606 -0.1977658 -0.9794354 -0.07642227 -0.2644421 -0.9613688 -0.04260909 -0.2657607 -0.963097 -0.04342579 -0.3215308 -0.9459028 -0.008475244 -0.3226774 -0.9464711 -0.008122444 -0.2780221 -0.9605403 -0.00949347 -0.2779872 -0.9605379 -0.009209036 -0.171472 -0.9851459 -0.0165829 -0.228893 -0.9733104 -0.01583713 -0.05913531 -0.9981243 -0.02320671 -0.1177538 -0.9927716 -0.0213418 0.06362217 -0.9977458 -0.02445626 0.06361973 -0.9976745 -0.04845893 -0.5301549 -0.8465148 -0.04545497 -0.5256147 -0.8495075 -0.1007234 -0.5221536 -0.8468828 -0.09296977 -0.5106179 -0.8547666 -0.1284492 -0.5078989 -0.851786 -0.1240711 -0.5015995 -0.8561567 -0.132039 -0.5009838 -0.8553251 -0.1311249 -0.5000397 -0.8560178 0.002507209 -0.439309 -0.8983325 0.002090334 -0.4406009 -0.8977007 0.05757206 -0.4414934 -0.8954156 0.06778573 -0.4123452 -0.9085024 0.1063402 -0.4120686 -0.9049261 0.1092366 -0.4040786 -0.9081783 0.1271749 -0.4037289 -0.9059964 0.1112837 -0.4768969 -0.871886 0.1338776 -0.4762215 -0.8690741 0.1190496 -0.5180151 -0.8470464 0.06191956 -0.5190708 -0.8524855 0.09910082 -0.4022516 -0.9101498 0.01842349 -0.5324613 -0.8462539 0.1162564 -0.4212833 -0.899447 0.09140008 -0.4177559 -0.9039503 0.1030432 -0.4616239 -0.8810706 0.03818398 -0.4616364 -0.886247 0.05443936 -0.5143285 -0.8558636 -0.007098555 -0.5130882 -0.8583065 0.00204432 -0.5151891 -0.8570742 -0.01298576 -0.5488218 -0.8358386 -0.01359635 -0.4079802 -0.9128895 0.001430451 -0.4084483 -0.9127804 -0.1225029 -0.6281057 -0.7684246 -0.1171903 -0.6238232 -0.7727296 -0.1148021 -0.6240411 -0.7729122 -0.1315574 -0.6454012 -0.7524294 -0.0895912 -0.6492995 -0.7552374 -0.09658443 -0.6584424 -0.7464081 -0.05008375 -0.6617404 -0.7480583 -0.04705774 -0.6577203 -0.7517909 0.005111336 -0.6596504 -0.7515552 0.01652228 -0.644231 -0.7646526 0.06846654 -0.6440308 -0.7619296 0.09292185 -0.6101011 -0.7868559 0.08934247 -0.6102164 -0.7871811 0.1182146 -0.5334475 -0.8375315 0.08645761 -0.5344466 -0.8407686 0.116984 -0.3935669 -0.9118223 0.09957832 -0.3939061 -0.9137406 0.1122337 -0.3562548 -0.9276239 0.06909608 -0.3566194 -0.9316912 0.07005381 -0.3535532 -0.9327876 8.06863e-4 -0.3527192 -0.9357289 0.002531766 -0.3466466 -0.9379925 -0.02922338 -0.3457061 -0.9378877 -0.02389836 -0.325904 -0.9451007 -0.003136277 -0.3265077 -0.9451894 -0.003335177 -0.3744457 -0.9272429 -0.001819252 -0.3744878 -0.9272301 -0.002938985 -0.4575482 -0.8891801 0.005989074 -0.4119517 -0.911186 0.005249261 -0.1589227 -0.9872771 0.1713078 -0.3413809 -0.9241822 -0.1806587 0.4271861 -0.8859314 0.1551823 -0.2786565 -0.9477706 0.1743429 -0.2816169 -0.9435552 0.103515 -0.2768854 -0.9553111 0.05153852 -0.2313669 -0.9715005 0.004853844 -0.1643218 -0.9863948 0.01313954 -0.1656469 -0.9860976 0.07433468 -0.2515988 -0.9649727 0.04447025 -0.2348407 -0.9710161 0.04456681 -0.2230411 -0.9737898 0.05269891 -0.1917768 -0.9800227 0.03101176 -0.2044363 -0.9783885 0.02447783 -0.2033103 -0.9788084 0.01313954 -0.1656469 -0.9860976 0.006638646 -0.1748253 -0.9845771 0.01193201 -0.1756718 -0.9843765 0.01769137 -0.1745591 -0.9844878 0.03198641 -0.1892422 -0.9814093 0.03198641 -0.1892421 -0.9814093 0.1071584 -0.2802643 -0.9539231 0.1065084 -0.3084192 -0.9452691 0.1104816 -0.3092198 -0.9445512 0.136972 -0.2383518 -0.9614713 0.1503064 -0.2944689 -0.9437669 0.1336659 -0.2911129 -0.947305 0.1335875 -0.2906152 -0.9474689 0.102607 -0.2853215 -0.9529236 0.1019505 -0.2775055 -0.9552993 -0.2109562 0.5383392 -0.8158974 -0.2253972 0.4548352 -0.8615806 -0.2253986 0.4548351 -0.8615802 -0.2203192 0.5568488 -0.8008614 -0.2137507 0.5573391 -0.802299 -0.2118314 0.6583672 -0.7222741 -0.2194362 0.6194701 -0.7537271 -0.2194361 0.6194701 -0.7537271 -0.212511 0.5271258 -0.8227864 -0.2125061 0.5271265 -0.8227871 -0.1795245 0.4309205 -0.884352 -0.1868844 0.4301338 -0.8832095 -0.1441177 0.412985 -0.8992628 -0.1806662 0.4271367 -0.8859537 -0.1950497 0.3633117 -0.9110216 -0.2258724 0.3686948 -0.9016905 -0.2422187 0.2800385 -0.9289287 -0.2113133 0.2741737 -0.9381767 -0.2218448 0.1771885 -0.9588479 -0.1536583 0.1634902 -0.9745051 -0.1538971 0.06859683 -0.9857029 -0.04929339 0.04894638 -0.9975843 -0.03867596 -0.02519959 -0.9989341 0.05808264 -0.04008138 -0.9975069 0.06843149 -0.0874325 -0.9938173 0.1135398 -0.09403204 -0.9890736 0.1350755 -0.1796137 -0.9744195 0.1586702 -0.1833881 -0.9701509 0.1702793 -0.245686 -0.9542763 0.1709277 -0.2457867 -0.9541345 0.09921211 -0.03683811 -0.9943842 0.08190357 -0.03425896 -0.9960512 0.01468235 0.1268725 -0.9918103 -0.01978337 0.1297596 -0.9913482 -0.05818837 0.2098007 -0.9760112 -0.1098756 0.2125083 -0.9709622 -0.1466751 0.3169896 -0.9370187 -0.1855828 0.3189758 -0.9294157 -0.2025965 0.4302205 -0.879696 -0.2221053 0.4309979 -0.8745915 -0.2228091 0.5305508 -0.8178459 -0.2197698 0.5304881 -0.8187084 -0.2117864 0.6127168 -0.7613965 0.1472211 -0.20647 -0.9673138 0.1304727 -0.129175 -0.9830008 0.1196265 -0.1266359 -0.9847095 0.05973583 0.08651673 -0.9944579 -0.01621317 0.1616851 -0.9867092 0.001874566 0.1595896 -0.9871817 -0.2721973 0.7591984 -0.5912075 -0.272198 0.7591984 -0.5912073 -0.2254248 -4.65875e-4 -0.9742605 -0.2254245 -4.63141e-4 -0.9742605 -0.2254316 -4.8393e-4 -0.9742588 -0.2137086 0.0294581 -0.9764533 -0.2112612 0.02859097 -0.9770114 -0.2392392 -0.04388636 -0.9699683 -0.1702244 -0.068237 -0.9830398 -0.1943068 -0.1338438 -0.9717668 -0.08125901 -0.1704745 -0.9820058 -0.09802973 -0.2204393 -0.9704622 0.05433428 -0.2606481 -0.9639037 0.04771035 -0.2842652 -0.9575579 0.1616045 -0.3060481 -0.9381996 0.1603514 -0.3103001 -0.9370173 0.1906663 -0.3150279 -0.929733 0.1902542 -0.3220362 -0.9274137 0.2013624 -0.3236865 -0.9244892 0.2014201 -0.3233295 -0.9246015 0.1864913 -0.3211691 -0.928478 0.1879719 -0.3159272 -0.9299767 0.1450846 -0.3094143 -0.9397942 0.1560709 -0.2834333 -0.9462069 0.140791 -0.3859225 -0.9117245 0.140792 -0.3859226 -0.9117243 0.1996271 -0.4143944 -0.8879337 0.1733824 -0.4462011 -0.8779767 0.2058569 -0.4505137 -0.8687119 0.1783043 -0.5029844 -0.8457034 0.2002874 -0.5060184 -0.8389459 0.1799775 -0.5240288 -0.8324674 -0.1232838 -0.4174719 -0.9002879 -0.1407303 -0.4221088 -0.8955551 -0.1782436 -0.4069268 -0.8959017 0.1275022 -0.5496439 -0.8256118 0.1275029 -0.5496441 -0.8256115 0.1106559 -0.5313091 -0.8399202 -0.03407436 -0.4953835 -0.8680058 -0.02472221 -0.4980958 -0.8667696 -0.03412371 -0.5066555 -0.8614731 -0.03412359 -0.5066555 -0.861473 -0.1276484 -0.2635011 -0.9561764 0.03313148 -0.227968 -0.9731047 0.0336917 -0.2097631 -0.9771716 0.01793354 -0.2180761 -0.975767 -0.001448631 -0.1630975 -0.9866089 -0.00144875 -0.1630975 -0.9866089 0.01775789 -0.1728991 -0.9847795 0.01300132 -0.1740866 -0.9846446 0.02556085 -0.1761317 -0.9840347 0.01294523 -0.191918 -0.9813256 0.01294529 -0.191918 -0.9813256 -0.09429967 0.7683993 -0.6329851 -0.06235629 0.9185007 -0.3904715 -0.1220315 0.7676753 -0.6291129 -0.1585274 0.611826 -0.7749439 -0.1129512 0.7679843 -0.6304301 -0.1878217 0.4282394 -0.8839309 0.1071542 -0.2802634 -0.9539237 0.07477629 -0.2672275 -0.9607279 0.07551223 -0.2715715 -0.9594514 0.06792026 -0.2504016 -0.9657567 0.05637794 -0.2686865 -0.9615764 -0.1478201 -0.3748794 -0.9152129 -0.1862615 -0.238717 -0.9530587 -0.1862612 -0.2387132 -0.9530597 -0.138624 -0.03327184 -0.9897861 -0.2016395 -0.1956439 -0.9597213 -0.1756435 -0.2064744 -0.9625579 -0.2114503 -0.2603262 -0.9420823 -0.1262971 -0.2940738 -0.9474015 -0.1552389 -0.3351153 -0.9293 -0.03427278 -0.3766916 -0.9257045 -0.05127149 -0.3999599 -0.9150974 0.09618228 -0.4388877 -0.8933792 0.09663873 -0.4382542 -0.893641 0.1897471 -0.4551512 -0.8699618 0.2019135 -0.4394042 -0.8753027 0.204022 -0.4397036 -0.8746632 0.2145075 -0.4076069 -0.8876052 0.198351 -0.4053899 -0.8923653 0.212405 -0.3727276 -0.9033041 0.1741288 -0.3673689 -0.9136297 0.1896438 -0.3387524 -0.9215651 0.1306232 -0.3297729 -0.9349799 0.1449594 -0.3082438 -0.9401981 0.07770311 -0.2965819 -0.951841 0.01752454 -0.2629478 -0.9646509 0.07171607 -0.2693796 -0.9603601 0.07700294 -0.2704169 -0.959659 0.07175666 -0.2768362 -0.9582342 0.1282107 -0.286891 -0.9493448 0.07192379 -0.3594455 -0.9303902 0.1384292 -0.3364484 -0.931472 0.0177741 -0.2361293 -0.971559 0.03739273 -0.2399765 -0.9700583 0.05639231 -0.2693367 -0.9613935 0.09282809 -0.2764587 -0.956532 0.09374022 -0.2928358 -0.9515566 0.1367661 -0.3002367 -0.944009 0.1347706 -0.285632 -0.9488157 0.1535634 -0.2886505 -0.9450393 0.1500012 -0.271753 -0.9506051 0.1446703 -0.2706013 -0.9517591 -0.02748084 0.9737832 -0.2258123 0.08057141 0.9263958 0.36783 -0.190285 0.5952562 -0.7806802 0.05951899 0.9778378 0.2007261 -0.3633603 0.9315009 -0.01659464 -0.360602 0.9325879 -0.01568603 -0.2361642 0.8623613 0.4478386 -0.122901 0.5444264 -0.8297562 0.07359427 -0.07085251 -0.9947682 0.004723668 -0.2377229 -0.9713216 -0.002138316 -0.2893069 -0.957234 -0.01800447 -0.4070066 -0.9132478 -0.07193559 -0.7718223 -0.6317561 -0.01799517 -0.4069343 -0.9132801 -0.002158939 -0.2894448 -0.9571923 -0.002187371 -0.2896587 -0.9571275 0.01157206 -0.4575403 -0.8891136 0.01157277 -0.4575308 -0.8891185 0.00699687 -0.5136919 -0.8579462 0.00685507 -0.5136688 -0.8579612 0.04507207 0.09107285 -0.9948236 0.01250183 -0.454811 -0.8905003 0.005950629 -0.5257813 -0.8505989 -0.006407618 -0.5237161 -0.8518687 0.003013908 -0.436806 -0.8995506 -0.02250444 -0.4323514 -0.9014243 0.004726231 -0.2377009 -0.971327 0.06296092 -0.1737681 -0.9827719 0.04010784 -0.4805353 -0.8760576 0.04010802 -0.4805353 -0.8760577 0.1010716 -0.2715135 -0.9571129 0.09167397 -0.1909227 -0.9773148 -0.1641982 0.5619711 -0.8106955 -0.1521459 0.5631996 -0.8121932 -0.04802304 0.3031606 -0.9517287 -0.03497928 0.3023804 -0.9525453 0.03481352 0.08780914 -0.9955288 0.02865499 0.1089559 -0.9936336 -0.08557564 0.4221835 -0.9024621 -0.09588819 0.4221783 -0.9014272 -0.01544606 0.2379826 -0.9711467 -0.06987196 0.4055483 -0.9113993 -0.08142018 0.4056712 -0.9103855 -0.1393586 0.5661499 -0.8124368 -0.1546891 0.5647402 -0.8106417 -0.2015532 0.6774619 -0.7074049 -0.2152798 0.6748235 -0.7058809 -0.2445905 0.7394838 -0.6271676 -0.2490219 0.7382909 -0.6268292 0.063488 0.01004391 -0.997932 0.0635038 0.00993365 -0.9979321 -0.2337284 0.8421232 0.4860037 -0.2351374 0.8546471 0.4629133 -0.1705195 0.840239 -0.5147053 -0.1869013 0.7200522 -0.6682759 -0.2031003 0.716915 -0.6669207 -0.2758538 0.8834525 -0.3787037 -0.2968365 0.8762072 -0.3796697 -0.3387915 0.9400762 -0.03843367 -0.2229451 0.8087235 -0.5442994 -0.2403393 0.8041153 -0.5437239 -0.3047416 0.9344242 -0.1843471 -0.3264524 0.9263468 -0.1879107 -0.3445532 0.9315909 0.1158521 -0.236165 0.8623611 0.4478384 -0.2358154 0.8597651 0.4529846 -0.2358238 0.8597765 0.4529587 -0.1327971 0.9788153 -0.1558384 -0.1122726 0.9307117 0.3480957 -0.2625882 0.9029895 -0.3400843 -0.2625864 0.9029901 -0.3400839 -0.2619487 0.8833761 0.388625 -0.366628 0.9092555 -0.1970744 -0.376205 0.9046672 -0.2001171 0.06614339 0.9771131 0.2021757 0.0307604 0.9979269 0.05653119 -0.02888089 0.9985597 0.04521685 -0.04948598 0.9984836 -0.02411526 -0.09884929 0.9945439 -0.0333386 -0.1146385 0.9889788 -0.0936957 -0.1905049 0.9756655 -0.1085582 -0.1998463 0.9662845 -0.1623439 -0.31277 0.9311745 -0.1873206 -0.3141399 0.9218161 -0.2270925 -0.371665 0.8963307 -0.2417778 -0.3709644 0.893948 -0.2514804 -0.3441089 0.9064256 -0.2449116 -0.3475441 0.9126436 -0.2151622 -0.3423848 0.9148324 -0.2141363 -0.3304105 0.8925706 -0.3068332 -0.3254703 0.8945752 -0.3062747 -0.3093305 0.8638948 -0.3974925 -0.2923954 0.8700435 -0.3968996 -0.3721666 0.9267867 0.05058056 -0.364948 0.9283593 0.07044142 -0.3664029 0.9278302 0.06985825 -0.3629081 0.9103789 0.1987665 -0.3629091 0.9103782 0.1987674 -0.2494956 0.8284264 -0.5014595 -0.2692732 0.8225071 -0.5009732 -0.3222597 0.9221277 -0.2140774 -0.3388735 0.9155553 -0.2166175 -0.3560732 0.9334677 -0.04301291 -0.3621553 0.9289643 0.07660859 -0.3624384 0.9255416 0.1095954 -0.3607096 0.9323253 0.02565407 -0.1718832 0.3516023 0.9202347 0.0955584 -0.0582779 -0.9937164 0.09555804 -0.0582779 -0.9937165 -0.05873996 0.3286855 -0.942611 0.1123422 -0.1595012 -0.9807847 0.0863232 -0.07797271 -0.9932112 0.1228757 -0.2693179 -0.9551803 0.11785 -0.1598879 -0.9800751 0.0981726 -0.2372085 -0.9664856 0.1097055 -0.2391793 -0.964758 0.1005748 -0.1924103 -0.976147 0.01169997 0.1797295 -0.9836465 0.01171582 0.1796652 -0.983658 0.01171654 0.1796637 -0.9836583 0.01171445 0.1796657 -0.983658 0.03808182 0.1682919 -0.9850013 0.06348758 0.01004689 -0.997932 -0.1787852 0.5971062 -0.7819846 -0.1138643 0.4366634 -0.8923901 -0.1036788 0.4369677 -0.8934819 -0.02725183 0.2376846 -0.97096 -0.01917141 0.2370132 -0.9713172 0.0678786 0.00986433 -0.9976448 0.09891432 -0.09669971 -0.9903863 0.09640032 -0.09629607 -0.9906736 0.09989738 -0.1114557 -0.9887356 0.09545701 -0.08175045 -0.992071 -0.04682123 0.2369161 -0.9704013 -0.04681658 0.2369161 -0.9704015 0.1400937 -0.2217401 -0.9649897 0.1030022 -0.1004186 -0.9895992 0.1030018 -0.1004186 -0.9895992 0.1117981 -0.1235619 -0.9860191 0.03941386 0.1156626 -0.9925063 0.02328771 0.1176757 -0.992779 0.006434798 0.1641437 -0.9864155 -0.116795 0.4523753 -0.8841467 -0.1262128 0.4518698 -0.8831105 -0.2149045 0.6512019 -0.7278407 -0.285433 0.8447529 -0.4526815 -0.2274654 0.7129287 -0.6633191 -0.285426 0.8447546 -0.4526826 -0.2532875 0.6608857 -0.7064527 -0.2463421 0.6627926 -0.7071219 0.001586675 0.9747444 -0.2233175 -0.1134955 0.8075388 -0.5787919 -0.1803175 0.9422334 -0.2822797 -0.1803175 0.9422334 -0.2822797 -0.1962372 0.8068009 -0.5572821 0.01137751 0.9867649 0.1617583 0.004857361 0.9868764 0.161404 0.05097675 0.946786 0.3178014 0.05097627 0.946786 0.3178014 0.1351757 -0.22291 -0.9654214 -0.2568745 0.6514168 -0.7139129 -0.2526389 0.641088 -0.7246929 -0.2962955 0.7391082 -0.6049198 -0.2625594 0.7512471 -0.6055497 -0.2555018 0.7359561 -0.6269668 -0.2461075 0.7386388 -0.6275697 -0.190759 0.6086225 -0.7701881 -0.1811422 0.6101183 -0.7713255 -0.09822201 0.404339 -0.9093198 -0.08289915 0.4042969 -0.9108632 0.002371966 0.1687154 -0.9856619 0.01422697 0.1674003 -0.9857864 0.07422804 -0.02795332 -0.9968494 0.07367265 -0.02786833 -0.996893 0.04097831 0.08699661 -0.9953654 -0.2511831 0.8765996 0.4104635 0.007790207 0.2359401 -0.9717364 0.006240189 -0.2036868 -0.9790162 0.00623387 -0.2037376 -0.9790056 0.009305417 -0.1811404 -0.9834132 0.03573274 -0.1292566 -0.9909671 0.04314148 -0.2726754 -0.9611384 0.05058276 -0.1037126 -0.9933203 0.01184594 -0.4545369 -0.8906491 0.01157432 -0.4575142 -0.889127 0.01157397 -0.4575141 -0.889127 0.03573256 -0.1292566 -0.9909672 0.03640651 -0.1227149 -0.9917739 0.03613388 -0.1226736 -0.9917891 0.02120351 -0.2077573 -0.9779505 0.01419109 -0.1568927 -0.9875138 0.01297348 -0.1567055 -0.9875602 0.01123547 -0.1814417 -0.9833375 -0.1327983 0.9788151 -0.1558386 -0.1098366 0.9913924 -0.07125425 -0.1155883 0.9906599 -0.0723356 0.03440344 0.9529741 0.3010928 -0.06400448 0.9620527 -0.2652506 -0.04056525 0.9656728 -0.2565749 0.04250609 0.9794852 0.1969826 0.06348836 0.01004314 -0.9979321 0.06349176 0.0100187 -0.9979321 0.1060345 -0.3366414 -0.9356437 0.1035798 -0.3359352 -0.9361723 0.07772034 -0.2082184 -0.9749895 0.07687181 -0.418085 -0.9051495 0.07687181 -0.418085 -0.9051495 -0.02997696 0.9736621 -0.2260164 -0.01507633 0.986286 -0.1643552 -0.080006 0.9819681 -0.1712825 -0.1019306 0.9634497 -0.2477391 -0.1409485 0.9576869 -0.2509368 -0.1588996 0.9316993 -0.3266304 -0.2118914 0.9198061 -0.3302406 -0.221631 0.8855321 -0.4083047 -0.3000879 0.8598104 -0.4131262 -0.2959113 0.8225008 -0.4857252 -0.3305718 0.8079862 -0.4877301 -0.3347461 0.8181954 -0.4674412 -0.3028046 0.8319358 -0.4649648 -0.3108344 0.8480697 -0.4291384 -0.3052136 0.8502514 -0.4288557 -0.2870093 0.8125517 -0.5073314 -0.2816833 0.814362 -0.5074142 -0.265416 0.7805708 -0.5659185 -0.2503627 0.7848827 -0.5668136 -0.2210576 0.7187479 -0.6591926 -0.2028539 0.7225832 -0.6608508 -0.1467351 0.5758056 -0.8043113 -0.1319879 0.5771814 -0.805879 -0.06887644 0.3921012 -0.91734 -0.03446412 0.3912883 -0.9196226 -0.07842433 0.5470057 -0.8334472 -0.1139095 0.6663984 -0.7368432 -0.165741 0.659696 -0.7330288 -0.2307209 0.8255993 -0.5149307 -0.2416273 0.6098766 0.7547627 -0.2979579 0.8305279 0.4705789 -0.1439022 0.2721803 0.9514252 -0.2400407 0.7834835 -0.573179 -0.1718844 0.3516021 0.9202345 0.05320155 -0.1735382 -0.9833891 0.05320155 -0.1735381 -0.9833891 0.06241887 -0.2588545 -0.9638975 0.07313925 -0.2120463 -0.9745188 0.07791918 -0.2128013 -0.9739837 0.07495123 -0.2735999 -0.9589189 0.09187871 -0.2698331 -0.9585136 0.1051189 -0.2628245 -0.9591003 0.1009629 -0.2621039 -0.9597437 0.0953924 -0.1821702 -0.9786288 0.0953918 -0.18217 -0.9786289 0.1106883 0.6840591 0.7209793 -0.03416138 0.2953475 0.954779 0.001726865 0.2160686 0.9763767 -0.002934396 0.2168056 0.9762104 0.1173499 0.9900606 0.07751685 0.05664753 0.5023909 0.862783 0.003668129 0.2157607 0.9764394 -0.006261408 0.1830678 0.9830804 -0.05189275 0.2715483 0.9610248 -0.01387429 0.2493786 0.9683067 -0.03477406 0.2532503 0.9667755 -5.58595e-4 0.1821541 0.9832699 -0.004706025 0.187691 0.9822168 -4.55708e-4 0.1870131 0.9823573 -0.01589393 0.2029332 0.9790636 -1.73138e-4 0.2003703 0.9797202 -0.02369946 0.2054463 0.9783814 -0.0146358 0.2171702 0.976024 -0.0146358 0.2171702 0.976024 -0.006912171 0.6310112 0.7757429 -0.02596259 0.6359813 0.7712675 0.05686956 0.5899608 0.8054268 0.04295754 0.5819875 0.8120624 -0.02826136 0.6537162 0.7562119 -0.0282613 0.6537162 0.756212 -0.1076158 0.6259253 0.7724224 -0.1235661 0.6338233 0.763544 -0.1819752 0.6426298 0.7442526 -0.1138045 0.5852578 0.8028213 -0.1138039 0.5852576 0.8028214 -0.1367828 0.5316621 0.8358384 -0.07256937 0.5153951 0.8538745 -0.1253858 0.5245776 0.8420788 -0.0521878 0.4358146 0.8985222 -0.09354251 0.4433627 0.891448 -0.0671882 0.8180081 -0.5712691 -0.06719404 0.8180075 -0.5712693 -0.1203908 0.5112428 0.8509624 -0.1204087 0.5114179 0.8508546 -0.1204127 0.5114552 0.8508316 -0.2184019 0.9474106 -0.2339096 -0.1345193 0.6652936 0.7343629 -0.1125875 0.953794 -0.2785699 0.01632839 0.3470485 -0.937705 -0.1719146 0.855529 -0.4883804 -0.1338991 0.7080954 -0.6933052 -0.1339005 0.7080947 -0.6933055 -0.2240537 0.9215766 -0.3170117 -0.2406538 0.9006083 0.361926 -0.1830052 0.6618102 0.7269913 -0.2161766 0.6629755 0.7167504 -0.3109142 0.8363183 0.4515572 -0.3308342 0.9377092 -0.1060669 -0.330832 0.9377101 -0.1060659 -0.3700447 0.8995828 0.2319865 -0.2294853 0.7072777 0.6686514 -0.2746269 0.7064391 0.6523219 -0.2934947 0.7839261 0.5471022 -0.3352712 0.7795239 0.5290894 -0.3376641 0.8437368 0.4172423 -0.3519797 0.8670954 0.3524998 -0.3432208 0.868895 0.3566802 -0.3614675 0.9035923 0.2299179 -0.3614658 0.9035927 0.2299188 -0.3546441 0.8869006 0.2960315 -0.3546454 0.8869004 0.2960309 -0.2986605 0.9480959 0.1091611 -0.1585565 0.870166 0.4665522 -0.1585581 0.870166 0.4665516 0.01170057 0.8750931 0.4838132 0.02444702 0.8628985 0.5047855 0.02444678 0.8628986 0.5047854 0.06076776 0.8780203 0.4747501 0.1249011 0.8187417 0.5604122 0.1249015 0.8187416 0.5604123 0.1432939 0.8778851 0.4569298 0.1108752 0.6839223 0.7210804 0.1108862 0.683992 0.7210128 0.08415251 0.8453643 0.5275202 0.08414447 0.8453196 0.5275931 0.084185 0.8455463 0.5272234 0.05567532 0.6718641 0.738579 0.04665982 0.6140646 0.7878753 0.04666042 0.6140688 0.7878721 0.01825141 0.4099986 0.9119036 0.01825463 0.4100214 0.9118933 0.01825869 0.4100506 0.9118799 0.07379454 0.7786639 -0.6230865 0.0737254 0.774368 -0.6284257 0.07374632 0.7702518 -0.6334616 0.07090139 0.7703946 -0.6336128 -0.001503109 0.5758407 0.8175605 -0.002930939 0.2168307 0.9762048 0.06430238 0.6997316 0.7115061 0.02575427 0.7054328 0.7083088 0.0737949 0.7786782 -0.6230685 0.07379549 0.7786782 -0.6230685 -0.03914719 0.2411808 0.9696903 0.07076752 0.7627708 -0.642785 0.07364946 0.7626294 -0.6426291 0.07369184 0.7699385 -0.6338487 0.06879401 0.7701868 -0.6340976 -0.05798298 -0.1169545 0.9914432 0.06093496 0.4775697 -0.8764783 -0.0626707 0.2327649 0.9705117 0.04406493 0.4103468 -0.9108643 0.04406493 0.4103468 -0.9108643 -0.0826295 0.3245416 0.9422553 0.01844871 0.3349464 -0.9420565 0.01844882 0.3349465 -0.9420566 0.06149888 0.3789626 -0.9233663 0.05997747 0.4775829 -0.8765372 0.06006348 0.467373 -0.8820175 0.05198919 0.4674592 -0.8824846 0.05481183 0.3953286 -0.916903 0.038944 0.3945211 -0.9180614 0.04534077 0.3200139 -0.9463274 0.01787984 0.3157959 -0.9486586 -0.1504732 0.8586736 0.4899361 -0.791997 0.6095243 0.03494173 -0.242087 0.9632242 0.1165883 0.003363728 0.6266527 0.7792914 -0.02056664 0.6295357 0.7766993 -0.01593369 0.6837949 0.7295004 -0.0506215 0.6872424 0.7246623 -0.04911267 0.711547 0.70092 -0.0888195 0.7145281 0.6939457 -0.08835488 0.7361363 0.6710414 -0.1443547 0.7385619 0.65855 -0.1496825 0.89144 0.427703 -0.2249505 0.8919659 0.3921657 -0.1143462 0.6974073 -0.7074943 -0.1389656 0.6866071 -0.7136241 -0.2663169 0.8946807 0.3586387 -0.2568532 0.8945264 0.3658536 -0.2402613 0.8967511 0.3716343 -0.03337895 0.4409663 0.8969027 -0.0126636 0.4379047 0.8989322 -0.01630973 0.3974782 0.9174667 1.36555e-4 0.3950075 0.9186779 0.01818472 0.5731891 0.8192214 0.03011673 0.6756603 0.7365977 -0.03523725 -0.008643388 0.9993416 -0.03524494 -0.00871998 0.9993407 0.06755906 0.4970599 -0.8650822 -0.172544 0.6166478 0.7680978 -0.1433736 0.6144762 0.7757984 -0.1495623 0.9207156 0.3604356 -0.1156243 0.5500046 0.8271191 -0.08822786 0.5466001 0.8327331 -0.08725345 0.5218696 0.848551 -0.05729603 0.5178847 0.8535295 -0.05742865 0.4931991 0.8680188 -0.02978724 0.4892463 0.8716368 0.001727461 0.2160732 0.9763756 0.006004095 0.2760552 0.9611231 -0.01351153 0.279111 0.9601638 -0.01349443 0.2909651 0.9566385 -0.02240163 0.2923546 0.9560475 -0.02151668 0.3227068 0.9462544 -0.03754311 0.3252846 0.9448705 -0.03720331 0.3650211 0.9302556 -0.05821585 0.3684809 0.9278107 -0.05985468 0.391219 0.9183492 -0.08212256 0.3948385 0.9150729 -0.08506709 0.4199946 0.903531 -0.1020882 0.4227606 0.9004729 -0.1075888 0.4447304 0.8891792 -0.1154409 0.4458888 0.8876129 -0.1267444 0.4824067 0.8667292 -0.1393245 0.4840409 0.8638826 -0.1566073 0.5296947 0.8336052 -0.173631 0.5314779 0.8290859 -0.1965137 0.5814686 0.7894787 -0.2190915 0.5830324 0.7823505 -0.262841 0.681568 0.6829201 -0.2689869 0.6815881 0.6805025 -0.3117557 0.7646936 0.5639611 -0.2951329 0.7657163 0.5714676 -0.3306612 0.829833 0.449489 -0.3294197 0.8299853 0.450119 -0.3515439 0.8525839 0.3866753 -0.2413488 0.86451 0.4408777 -0.2545941 0.8770822 0.4073189 -0.08562827 0.8764208 0.4738717 -0.1534893 0.9375151 0.3122603 0.01917928 0.8738226 0.4858665 0.04295742 0.5819875 0.8120623 0.08594262 0.5141741 0.8533691 0.04416364 0.5294512 0.84719 0.05662089 0.5185308 0.8531823 0.03936994 0.5085997 0.8601025 -0.03710353 0.3756486 0.9260191 -0.03128224 0.3733028 0.9271821 -0.06835919 0.3800591 0.9224327 -0.0263434 0.3470564 0.9374741 -0.05403739 0.3299165 0.9424623 -0.02198749 0.3237735 0.9458791 -0.05583012 0.3283667 0.9428989 -0.03698688 0.3134499 0.9488842 -0.06286513 0.3182701 0.9459134 -0.03569871 0.2952721 0.9547461 -0.03569781 0.2952719 0.9547461 0.1258444 0.4757183 0.870549 0.07176661 0.5956019 0.8000676 0.1157628 0.5798462 0.8064598 0.07403534 0.6379313 0.7665262 0.0721749 0.6385296 0.7662054 0.04430717 0.6709479 0.7401797 -0.01626896 0.686866 0.726602 -0.01922339 0.689722 0.7238191 -0.158129 0.7145764 0.6814514 -0.1243144 0.6880926 0.7148948 -0.2433053 0.7010205 0.6703527 -0.1868197 0.6598981 0.7277588 -0.2209846 0.6631911 0.7150829 -0.1499887 0.5784616 0.8018015 -0.1935374 0.5837599 0.7885224 -0.1150569 0.4922509 0.8628157 -0.1547197 0.4980129 0.8532555 -0.08413279 0.4124582 0.9070832 -0.1137685 0.4172948 0.9016218 -0.067941 0.3783778 0.9231545 -0.09437453 0.3829334 0.9189425 -0.05794918 0.3502389 0.9348661 -0.0835849 0.35484 0.9311832 -0.05586737 0.3286436 0.9428002 -0.08196318 0.3334629 0.9391936 -0.06256157 0.3141813 0.9472994 -0.07079428 0.3157601 0.9461944 -0.04931396 0.2773771 0.9594947 -0.03421586 0.2745223 0.9609718 0.1108866 0.6839891 0.7210154 0.11075 0.6843296 0.7207131 0.125507 0.6792201 0.7231237 0.08766734 0.728961 0.6789185 0.06470614 0.735657 0.6742565 0.04141539 0.7610019 0.6474263 -0.04487425 0.7795889 0.6246817 -0.04466831 0.7794046 0.6249266 -0.2112393 0.7973577 0.5653305 -0.1801313 0.7751849 0.6055088 -0.3086037 0.7773826 0.5481241 -0.258328 0.7433882 0.6169607 -0.2873727 0.7435243 0.6038116 -0.2206847 0.662297 0.7160034 -0.2627542 0.664331 0.6997318 -0.188501 0.5697703 0.7998932 -0.2155422 0.5722445 0.7912508 -0.1472823 0.4757404 0.8671671 -0.1594805 0.4773134 0.86414 -0.1178059 0.4323244 0.8939896 -0.1293078 0.4340243 0.891573 -0.09698158 0.3955149 0.913325 -0.1085774 0.3973881 0.9112046 -0.08537745 0.3671199 0.9262472 -0.09747403 0.3691937 0.9242266 -0.08330053 0.3490741 0.9333854 -0.08078432 0.3486173 0.9337772 -0.07097804 0.3226326 0.9438593 -0.05898648 0.320508 0.9454074 -0.05155211 0.2985092 0.9530134 -0.039011 0.2963092 0.954295 -0.03441172 0.2617173 0.964531 -0.02463507 0.260083 0.9652719 -0.02196758 0.2355806 0.9716066 -0.01702231 0.2347934 0.9718962 -0.01450634 0.2246825 0.974324 0.00282222 0.2219342 0.9750576 0.003668069 0.2157604 0.9764394 -0.01511693 -0.1049788 -0.9943595 -0.005286514 -0.1787887 -0.9838733 -0.05017513 -0.4019071 -0.9143047 -0.02684146 -0.1272469 -0.9915078 0.0324735 -8.66999e-4 -0.9994722 -0.01002687 -0.1003115 -0.9949056 -0.02612668 -0.1103003 -0.9935549 -0.009105443 -0.1061186 -0.9943118 -0.03189158 -0.1028053 -0.9941901 -0.01671469 -0.08943927 -0.9958521 -0.0819118 -0.508592 -0.8571025 -0.01229411 -0.1305489 -0.9913657 0.002647817 -0.1087519 -0.9940654 -0.01176619 -0.1123663 -0.9935972 -0.006045877 -0.1064914 -0.9942952 -0.01478272 -0.09815919 -0.9950609 -0.01905477 -0.1034952 -0.9944474 -0.01244693 -0.1007729 -0.9948316 -0.01143479 -0.09438419 -0.9954702 -0.027157 -0.1058672 -0.9940093 -0.02684551 -0.1272563 -0.9915065 0.02086985 -0.03729426 -0.9990864 -0.09918141 -0.3462207 -0.9328957 -0.07198107 -0.3233728 -0.94353 -0.1278915 -0.4768514 -0.8696302 -0.180674 -0.6443279 -0.7431005 0.04232364 0.003831088 -0.9990966 -0.01291662 -0.08204019 -0.9965454 -0.02100133 -0.0867573 -0.996008 -0.007523775 -0.1623207 -0.9867093 -8.75049e-4 -0.1508387 -0.988558 0.01977568 -0.06053149 -0.9979704 -0.04476803 -0.4026833 -0.9142439 -0.1196024 -0.7643703 -0.6335875 -0.009659767 -0.201183 -0.979506 -0.009649395 -0.201133 -0.9795164 -0.01672428 -0.2342773 -0.9720259 -0.02748084 -0.2851516 -0.9580883 0.0107693 -0.1025079 -0.9946739 -0.02595919 -0.2858368 -0.9579267 -0.02591025 -0.2855985 -0.9579991 -0.02359908 -0.2600986 -0.9652936 -0.02204883 -0.259964 -0.9653665 -0.01671719 -0.2342431 -0.9720343 -0.00528723 -0.1787921 -0.9838726 -0.005363523 -0.1791436 -0.9838083 -0.005474448 -0.1791394 -0.9838085 -0.04188895 -0.3454306 -0.9375088 -0.07949423 -0.5072428 -0.858129 0.02064353 -0.03800565 -0.9990643 -0.01163768 -0.1592683 -0.9871668 -0.001376569 -0.1579023 -0.9874537 -0.001918256 -0.1604734 -0.9870383 -0.002488553 -0.1604525 -0.9870405 -0.003125548 -0.1630345 -0.9866154 0.03819108 -0.008408725 -0.9992352 -0.0510419 -0.08270347 -0.9952662 -0.005407869 -0.05334872 -0.9985613 -0.0361697 -0.09404313 -0.9949108 -0.02070695 -0.0852642 -0.9961432 -0.03222328 -0.09704518 -0.9947583 -0.03439211 -0.09844821 -0.9945478 3.31883e-4 -0.1193615 -0.9928508 -0.009240806 -0.1217596 -0.9925166 -0.006768345 -0.1089684 -0.9940221 -0.02081161 -0.1147486 -0.9931765 -0.0069682 -0.07860243 -0.9968817 0.0279051 -0.02395558 -0.9993235 -0.02036297 -0.1547543 -0.9877431 -0.008438706 -0.1328735 -0.9910971 -0.03600436 -0.1269444 -0.9912562 -0.03600448 -0.1269444 -0.9912561 -0.1124479 -0.5824547 -0.8050479 -0.001347005 -0.1388716 -0.9903094 6.13926e-4 -0.138608 -0.9903472 0.002535045 -0.1285635 -0.991698 -0.008266389 -0.1505655 -0.9885655 -0.008531808 -0.1527908 -0.9882218 -0.007523775 -0.1623208 -0.9867093 0.02606695 0.1654223 0.9858782 0.137338 0.7479302 0.6494141 0.2389397 -0.6353443 0.7343333 0.03906983 0.1185597 0.992178 0.0371747 0.1294481 0.9908891 0.01283138 0.03375405 0.9993477 0.03142994 0.1277039 0.9913142 0.3919788 0.7812483 0.485802 0.2689847 0.8845757 0.3810158 0.1713337 -0.5401923 0.8239156 0.1715319 -0.5414012 0.8230805 0.1714293 -0.5407762 0.8235126 0.008293867 0.1281892 0.991715 0.008312106 0.1282748 0.9917039 0.1809879 0.9108878 0.3708461 -0.02087998 0.0372678 0.9990871 0.304243 0.7244952 0.6185006 0.1116159 0.285081 0.9519826 0.07847249 0.2169924 0.9730141 0.2253768 0.5985932 0.7686947 0.02014392 0.1543857 0.9878053 0.02420532 0.1553893 0.9875567 0.03860998 0.2044484 0.9781156 0.03697538 0.2005733 0.9789807 0.2436903 0.8006139 0.5473869 0.1920456 0.6767207 0.7107514 0.08608311 0.1181181 0.9892613 0.08246386 0.1205905 0.9892713 0.02044814 0.09664016 0.9951093 0.0566312 0.1523866 0.9866971 0.04757189 0.1178306 0.9918936 0.2389421 -0.6353444 0.7343326 0.1696067 -0.2573275 0.9513233 0.1102927 -0.0196731 0.9937044 0.111353 -0.02465778 0.993475 0.08777654 0.06413972 0.994073 0.1667194 -0.1631214 0.9724175 0.1247733 -0.02211064 0.9919389 0.2773767 -0.4947493 0.8235808 0.2773414 -0.4947555 0.8235889 0.08812677 0.05856412 0.9943863 0.09018737 0.05894345 0.994179 0.09095156 0.05396264 0.9943922 0.08565396 0.05265229 0.9949328 0.08653247 0.04975783 0.9950057 0.05828583 0.09166735 0.9940824 0.279539 -0.2867047 0.9163287 0.2791922 -0.2867251 0.9164282 0.1626394 -0.1003501 0.9815693 0.1459813 -0.05391609 0.9878171 0.1695098 -0.1625503 0.9720308 0.07032859 0.1069763 0.9917711 0.07670485 0.1019667 0.9918262 0.07008039 0.1007589 0.9924396 0.07612639 0.09642487 0.9924248 0.06193172 0.09293872 0.9937438 0.06623703 0.09029388 0.9937101 0.05756562 0.08751821 0.9944983 0.1031371 0.09903663 0.9897245 0.06359255 0.1356916 0.9887081 0.07659858 0.1209787 0.9896953 0.08998882 0.1252511 0.9880356 0.1208713 0.1148691 0.9859996 0.1247856 0.1152603 0.9854661 0.7394894 -0.6556726 0.1524757 0.9326366 -0.360628 0.01167553 0.4216971 -0.2753003 0.8639337 0.140679 0.07390028 0.9872933 0.09115934 0.09984147 0.9908187 0.09001791 0.09984695 0.9909225 0.06549298 0.1153606 0.9911623 0.0590865 0.1136447 0.9917629 0.04977035 0.1287046 0.9904333 0.03670656 0.1249554 0.9914831 0.9329603 -0.3598125 0.01095533 0.4512249 -0.03865724 0.8915726 0.2788701 -0.1315288 0.9512789 0.3375982 -0.1862471 0.9226806 0.02464973 0.1540846 0.9877502 0.02953261 0.1497461 0.9882833 0.04566997 0.1562977 0.9866535 0.04423356 0.1704739 0.9843688 0.05480462 0.1513359 0.9869619 0.04970663 0.1253514 0.9908665 0.07671529 0.1346626 0.9879174 0.08849185 0.124436 0.9882737 0.1107569 0.1323322 0.984998 0.1463364 0.1269901 0.98105 0.1362006 0.1025104 0.9853633 0.1583418 0.1080026 0.9814597 0.08833664 0.05709493 0.994453 0.5425376 0.1031288 0.8336771 0.3281381 0.1397787 0.9342309 0.3282244 0.139773 0.9342015 0.2541254 0.1243604 0.9591427 0.2395023 0.1134294 0.9642471 0.1822216 0.1323227 0.974313 0.1257255 0.1281387 0.9837549 -0.2653799 0.03694981 0.9634357 0.5230605 0.1636738 0.8364321 0.4138423 0.1489818 0.8980752 0.6953345 0.1799121 0.6958028 0.3101219 0.01897132 0.9505075 0.303028 0.01704168 0.9528293 0.2471009 0.08421778 0.965323 0.3446699 0.08560049 0.934813 0.418697 0.1128327 0.9010891 0.05825769 0.09164428 0.9940862 0.0586732 0.09089857 0.9941302 0.1044284 0.04660421 0.9934398 0.594802 -0.6992968 0.3964774 0.08721262 0.04997676 0.9949353 0.08740532 0.04962205 0.9949362 0.05945706 0.08660817 0.9944667 0.09062993 -0.1012052 0.9907289 0.1714718 -0.5410384 0.8233316 0.1714569 -0.5409468 0.823395 0.07085728 -0.01347982 0.9973953 0.05966204 0.04477059 0.9972141 0.05966269 0.04476761 0.9972143 0.08883464 -0.1010071 0.9909117 0.04006946 0.1289635 0.9908396 0.04006916 0.1289651 0.9908393 0.05355572 0.07328623 0.9958719 0.05243211 0.07955378 0.9954508 0.05878585 0.04492157 0.9972593 0.204388 -0.764908 0.6108528 0.2011746 -0.7647095 0.6121668 0.09066396 -0.1013751 0.9907084 0.05129283 0.1045336 0.9931977 0.05159771 0.1180338 0.9916681 0.06497901 0.06118613 0.9960091 0.06286317 0.07290273 0.9953559 0.08570086 -0.02297514 0.996056 0.08369642 -0.01394426 0.9963937 0.04399406 0.1488917 0.9878744 0.09062433 -0.04805356 0.9947252 0.04421442 0.1078567 0.9931827 0.03801268 0.1079539 0.993429 0.0532518 0.1128277 0.9921866 0.04044038 0.1138113 0.992679 0.06434053 0.1196807 0.9907253 0.04562371 0.1220806 0.991471 0.06604951 0.1258107 0.9898531 0.04547387 0.129348 0.9905561 0.04627209 0.1294509 0.9905056 0.03137779 0.1441775 0.9890542 0.03710579 0.1439411 0.9888904 0.0265311 0.1562845 0.9873557 0.177003 0.9810315 0.07903766 -0.0109359 0.101733 0.9947517 0.1488083 0.8352794 0.5293058 0.1487922 0.8352147 0.5294123 0.003137648 0.1667699 0.9859908 0.1540318 0.8340891 0.5296882 0.09931498 0.6057632 0.7894222 0.09928381 0.605626 0.7895316 0.1322019 0.7481916 0.6501784 0.05281007 0.4045686 0.9129816 0.05279433 0.4044965 0.9130144 0.052796 0.4045043 0.9130108 0.01400083 0.2141144 0.9767082 0.03364884 0.3149492 0.948512 0.01003569 0.2147321 0.9766215 0.01436293 0.2327718 0.9724254 0.01172393 0.2144633 0.9766617 0.01172161 0.214452 0.9766641 0.01959502 0.2325672 0.9723829 0.01429319 0.2142587 0.9766724 0.0358572 0.3148511 0.9484636 0.03244841 0.3006284 0.9531891 0.1562337 0.8268196 0.5403337 0.1809869 0.9108877 0.370847 0.2196333 0.8746515 0.4321412 0.04228705 0.3018041 0.9524316 0.01708608 0.199217 0.9798064 0.02309495 0.2153999 0.9762528 0.01299113 0.1696173 0.9854243 0.007282018 0.1688597 0.9856132 0.01711785 0.1887495 0.981876 0.005291879 0.1891977 0.9819248 0.01932984 0.213222 0.9768126 0.01932996 0.2132223 0.9768124 0.01437985 0.1797313 0.9836106 0.01437997 0.179732 0.9836105 0.9065937 0.3586048 0.2224645 0.9067527 0.3607462 0.2183157 0.4825158 0.207083 0.8510553 0.6638891 0.2735415 0.6960073 0.4186856 0.1128376 0.9010938 0.5081868 0.09435093 0.8560631 0.1549227 0.128489 0.9795354 0.1544601 0.1282225 0.9796433 0.1294803 0.1282901 0.9832479 0.06419873 0.08615964 0.9942108 0.04531341 0.09662634 0.9942887 3.82549e-4 0.03776699 0.9992865 0.6762845 -0.1605666 0.718928 0.2686622 0.03999823 0.9624036 0.179656 -0.002491116 0.9837264 0.1068872 0.0583074 0.99256 0.107607 0.05793255 0.9925042 0.06945705 0.09041273 0.9934793 0.06888723 0.09046953 0.9935139 0.04982244 0.1093951 0.9927489 0.04586356 0.1085315 0.9930344 0.03830176 0.1259602 0.9912956 0.03342682 0.1239677 0.991723 0.0254296 0.1238556 0.9919744 0.03787106 0.127839 0.9910717 0.02094537 0.1285253 0.9914849 0.04420983 0.1342697 0.9899582 0.01781255 0.1366197 0.9904634 0.04401546 0.148229 0.9879731 0.01176351 0.1440193 0.989505 0.03012615 0.1630948 0.9861504 0.02430152 0.163331 0.986272 0.02666139 0.1687037 0.9853062 0.2346409 0.968361 0.08497363 -0.4023805 -0.791728 0.4596267 -0.3941177 -0.5882837 0.7061116 -0.3796245 -0.8882293 0.2587165 -0.3887066 -0.8461805 0.364535 -0.3733141 -0.892573 0.2528833 -0.3995153 -0.6343141 0.6618409 -0.1488285 0.07652324 0.9858977 -0.2031183 0.01724368 0.9790024 -0.1766064 0.114754 0.9775694 -0.2381089 -0.03014159 0.9707706 -0.3240351 -0.2627585 0.908823 -0.33212 -0.3004238 0.8941151 -0.3221043 -0.269153 0.9076373 -0.397871 -0.6375194 0.6597482 -0.1166329 0.1859831 0.975606 -0.09657567 0.1945853 0.9761197 -0.08352285 0.2480475 0.9651406 -0.021811 0.2889178 0.9571054 -0.02628505 0.2874725 0.9574282 -0.08351838 0.2480646 0.9651365 0.05764192 0.3570039 0.9323228 -1.03867e-4 0.3243514 0.9459366 -0.02239716 0.2864304 0.9578392 0.1220993 0.4452584 0.8870382 0.05699211 0.3504629 0.934841 0.05699259 0.3504654 0.93484 0.1654155 0.3952335 0.9035642 0.1654155 0.3952332 0.9035643 0.2349171 0.5170237 0.8231041 0.2596908 0.4796952 0.8381249 0.2761961 0.6333483 0.7229009 0.2873992 0.7660158 0.574997 0.3054105 0.6497533 0.6960928 0.2746267 0.9583619 -0.07824748 0.2413213 0.9482842 -0.2062069 0.2499625 0.886536 0.3893233 0.3123639 0.8497217 0.4247374 0.3078702 0.9172353 0.2527757 0.302091 0.9316317 0.2019988 0.2922233 0.9484422 0.1227315 0.5728276 0.8182022 0.04912841 -0.04226988 0.3562566 0.9334316 -0.003012239 0.3928495 0.9195979 -0.1831368 0.01156109 0.9830195 -0.2655633 -0.2659368 0.9266897 -0.2760989 -0.4024786 0.8728003 -0.2760957 -0.4024545 0.8728124 -0.1831426 0.01154196 0.9830186 -0.1831412 0.01154774 0.9830188 -0.18716 0.07439887 0.9795081 -0.07422399 0.2945445 0.9527509 -0.07422453 0.2945424 0.9527516 -0.07078909 0.2473118 0.9663466 -0.04181957 0.2832001 0.9581486 -0.04181975 0.283199 0.958149 -0.3225728 -0.7380561 0.5926381 -0.3031775 -0.5737257 0.7608693 -0.3092503 -0.7421526 0.5946207 -0.2875866 -0.919662 0.2674242 -0.3283769 -0.7361629 0.5918048 0.2144508 0.3684534 0.9045734 0.1279742 0.4055353 0.9050766 0.1537617 0.5514873 0.8198898 0.1963762 0.5971245 0.7777395 0.2193915 0.7933319 0.5678837 0.2325283 0.831437 0.5046219 0.2307745 0.9424431 0.2419587 0.2308257 0.959018 0.1643285 0.2383292 0.8907513 0.3869903 0.2346431 0.9683604 0.08497405 0.09112966 0.9724771 -0.214438 0.1258416 0.9755634 0.1801112 0.1002898 0.9919064 0.07786947 0.06258833 0.9740612 -0.2174566 0.06258565 0.9740579 -0.2174726 0.1223279 0.9691154 0.2141285 0.1223263 0.9691192 0.214113 0.122325 0.9691219 0.2141016 0.1536675 0.6683067 0.7278409 0.1320888 0.8931074 0.4300135 0.1303567 0.8813166 0.4541895 0.1291102 0.916426 0.3788061 0.1536643 0.6684067 0.7277499 0.1519417 0.6636212 0.7324756 0.1501785 0.6697311 0.7272597 0.01374691 0.4232637 0.9059022 0.02718418 0.5128696 0.8580361 0.07549244 0.4083265 0.909709 0.09795397 0.4868187 0.8679934 0.099981 0.5093808 0.8547134 0.07967805 0.4938383 0.8658956 0.1501785 0.6697324 0.7272586 -0.3240205 -0.8189211 0.4736864 -0.3138723 -0.9122256 0.2633031 -0.3367925 -0.6094269 0.7177533 -0.3299422 -0.5648976 0.7563259 -0.2958611 -0.3137002 0.9022518 -0.2773341 -0.261844 0.9244045 -0.2155364 0.02157217 0.9762576 -0.1724516 0.06931567 0.9825761 -0.1375935 0.2087075 0.9682506 -0.0815069 0.2510657 0.9645324 -0.06860148 0.3054217 0.9497428 -0.01121312 0.3452126 0.9384576 -0.004072427 0.3799098 0.9250146 0.05076807 0.4178697 0.9070873 0.05944919 0.4697583 0.8807911 0.1083254 0.5060827 0.8556553 0.1230856 0.6267952 0.7694009 0.1562029 0.6619526 0.7330889 0.1669571 0.8539769 0.492797 0.1757314 0.8808873 0.4394952 0.1653518 0.9744891 0.1517555 0.1645275 0.9821915 0.09072285 0.121535 0.9414165 -0.3145857 0.1409934 0.9733697 0.1807548 -0.07873541 0.3276502 -0.9415127 -0.2856124 -0.9465803 0.1497043 -0.01254504 -0.4957121 -0.8683964 -0.03122097 -0.05154973 -0.9981823 0.1367595 0.8418587 -0.5220831 0.03672027 0.5872229 -0.808592 0.1760293 0.8810843 -0.4389809 0.1960608 0.9073829 -0.3717746 0.1808767 0.8816788 -0.435805 0.250164 0.9507568 -0.1829741 0.05585592 0.5988258 -0.798929 0.05585217 0.5988169 -0.7989361 -0.01996707 0.4763638 -0.8790215 0.089284 0.7290617 -0.6785997 -0.0312215 -0.05154949 -0.9981823 -0.1004721 0.06154882 -0.9930343 -0.07208067 0.1549034 -0.9852966 -0.007409572 0.09859526 -0.9951 -0.0668354 0.2566605 -0.964188 -0.04954415 -0.1417645 -0.9886598 -0.03262323 -0.2990335 -0.9536848 -0.01787841 -0.2446265 -0.9694526 -0.02653044 -0.2711251 -0.9621784 -0.04520446 -0.2364373 -0.9705947 -0.05499964 -0.1604266 -0.9855142 -0.005863845 -0.3692452 -0.9293134 -0.0171017 -0.4850511 -0.8743186 0.01909661 -0.4541732 -0.8907088 0.01978355 -0.4534884 -0.8910426 0.01810705 -0.4529497 -0.8913521 -0.01254749 -0.4957169 -0.8683935 -0.06012207 -0.6516028 -0.756174 -0.06011843 -0.6515973 -0.756179 -0.1919419 -0.8549084 -0.4819647 -0.4052518 -0.6621164 0.6303752 -0.3652127 -0.9292403 0.05596572 -0.1919564 -0.8549226 -0.4819337 -0.2792619 -0.9273796 -0.2489575 -0.2838216 -0.929148 -0.2369162 -0.3194757 -0.9387655 -0.1290531 -0.08670026 -0.9934356 -0.07462453 -0.08794748 0.4108607 -0.9074463 -0.05158448 0.6432945 -0.7638792 -0.01602303 0.7671561 -0.6412603 -0.0879476 0.41086 -0.9074465 -0.08794063 0.4108852 -0.9074358 -0.1009183 0.3666424 -0.9248724 -0.1031743 -0.04645085 -0.9935781 -0.1093344 0.02852362 -0.9935957 -0.1371999 -0.0337994 -0.9899666 -0.1372014 -0.03381347 -0.9899659 -0.1008458 -0.2744076 -0.9563109 -0.1263348 -0.1730533 -0.9767764 -0.1636036 -0.248447 -0.9547292 -0.1031745 -0.04645299 -0.993578 -0.01602011 0.767167 -0.6412474 -0.1004807 0.3275836 -0.939464 0.01201099 0.7655698 -0.6432407 0.1367586 0.8418588 -0.5220831 0.125942 0.8034744 -0.5818656 0.09832215 0.7275882 -0.6789317 0.08378732 0.6718058 -0.7359733 0.02040952 0.4675775 -0.8837165 0.01135158 0.3968372 -0.9178187 -0.05632424 0.1498748 -0.9870994 -0.04198265 0.06629312 -0.9969167 -0.07276242 -0.04661041 -0.9962596 -0.04137939 -0.1615313 -0.9859997 -0.2442545 -0.938517 -0.2439782 -0.2622734 -0.9498657 -0.170199 -0.3809777 -0.6729198 0.6340624 -0.3579054 -0.9236276 0.1371703 -0.1005671 -0.8086743 -0.5795965 -0.1493492 -0.8165984 -0.5575498 -0.138635 -0.8197365 -0.5557087 -0.1549782 -0.8576129 -0.4903897 -0.1386002 -0.8623455 -0.4869806 -0.1087352 -0.8062929 -0.5814365 -0.2008294 -0.9454126 -0.2566368 -0.2008349 -0.9454172 -0.2566158 -0.2266414 -0.9601445 -0.1635731 -0.2892991 -0.942192 0.1690571 -0.2878263 -0.9442394 0.1598992 -0.2888372 -0.9422984 0.1692535 -0.2888248 -0.9423208 0.1691499 -0.05524873 -0.5288344 -0.8469249 -0.05524951 -0.5288357 -0.846924 -0.02447515 -0.4824615 -0.8755753 -0.0547589 -0.6513468 -0.7568017 -0.0547589 -0.6513468 -0.7568018 -0.001100718 -0.6037074 -0.7972052 -0.04346871 -0.5908263 -0.8056269 -0.03628641 -0.6564967 -0.7534556 -0.05438572 -0.6507817 -0.7573146 -0.1005688 -0.8086774 -0.579592 0.1212359 0.8041365 -0.5819503 0.1154136 0.912236 -0.3930716 0.04468882 0.6773002 -0.7343483 0.03709417 0.6337738 -0.7726284 -0.01548349 0.4028667 -0.9151276 -0.01832699 0.348312 -0.9371995 -0.07258284 0.0764752 -0.9944262 -0.05634045 0.01005864 -0.9983609 -0.0845074 -0.1285475 -0.9880961 -0.05671274 -0.2004125 -0.9780688 -0.06942164 -0.2547072 -0.9645231 -0.0397824 -0.326256 -0.944444 -0.005863904 -0.3692454 -0.9293134 -0.00996989 -0.3748438 -0.9270343 -0.0078336 -0.37562 -0.9267407 -0.0762183 -0.4549608 -0.8872438 -0.1486809 -0.4928498 -0.8573173 -0.1486827 -0.4928513 -0.8573162 -0.1008459 -0.2744081 -0.9563108 -0.1291337 -0.3431237 -0.9303712 -0.09422349 -0.3048866 -0.9477162 -0.08469462 -0.3970002 -0.9139025 -0.09335923 -0.4368674 -0.8946681 0.005589842 -0.2170767 -0.9761386 0.0348584 -0.2904797 -0.956246 0.07193368 -0.3414698 -0.9371361 0.1397867 -0.3639894 -0.9208536 0.08423733 -0.3402264 -0.936563 0.08425158 -0.3402289 -0.9365608 0.07193297 -0.338024 -0.9383844 0.08475756 -0.3283256 -0.9407542 0.1395104 -0.3581938 -0.9231653 0.1175037 -0.3584037 -0.9261423 0.1175034 -0.3584036 -0.9261424 0.1761105 -0.4768464 -0.8611636 0.1408562 -0.521591 -0.8414882 0.1802572 -0.5276584 -0.8301109 0.1413158 -0.5345728 -0.8332237 0.1255624 -0.5272002 -0.840413 0.1409525 -0.5242501 -0.839818 0.0792101 -0.5142256 -0.8539894 -0.006802797 -0.5110167 -0.8595439 -0.03417718 -0.535342 -0.8439436 0.07928311 -0.5662572 -0.8204067 -0.0757727 -0.4782181 -0.8749662 -0.1447041 -0.4802821 -0.8650953 -0.07968527 -0.5212628 -0.8496678 -0.03412067 -0.5054984 -0.8621526 -0.07700252 -0.491672 -0.8673692 -0.006803333 -0.5110168 -0.8595439 0.07928866 -0.5662581 -0.8204054 -0.03387677 -0.6620255 -0.7487153 0.1252063 -0.5231419 -0.8429982 0.1168316 -0.3957942 -0.9108772 0.1343357 -0.3968055 -0.9080195 0.1413111 -0.3979093 -0.9064764 0.13439 -0.3995664 -0.9067998 0.1741389 -0.4545167 -0.8735504 0.1351409 -0.4483662 -0.883575 0.1351445 -0.4483683 -0.8835733 -0.001215815 -0.1791184 -0.9838268 -0.001215934 -0.1791189 -0.9838268 -0.001089036 -0.1784338 -0.9839514 -0.005733311 -0.1899054 -0.9817857 -0.005733549 -0.1899057 -0.9817856 0.01285403 -0.2183407 -0.9757879 0.005616009 -0.2272831 -0.9738126 0.01778501 -0.2349205 -0.9718518 -0.005733311 -0.1899056 -0.9817856 0.006452798 -0.191284 -0.9815136 0.01292788 -0.1971881 -0.9802804 0.006594896 -0.1968733 -0.9804067 0.01292544 -0.1979014 -0.9801367 0.007056057 -0.2151216 -0.9765618 0.005589783 -0.2170767 -0.9761385 -0.1092953 -0.3871743 -0.9155057 -0.1092965 -0.3871745 -0.9155054 -0.09669351 -0.3563736 -0.9293268 -0.1401771 -0.4145247 -0.8991772 -0.1184204 -0.4514666 -0.884395 -0.0757718 -0.4782184 -0.8749662 0.004607498 -0.2465388 -0.969122 0.004607737 -0.2465388 -0.9691221 0.01765596 -0.2490307 -0.9683346 0.01765596 -0.2490307 -0.9683346 0.004171967 -0.2833017 -0.9590218 0.07182586 -0.2914498 -0.9538857 0.03485804 -0.2904797 -0.956246 0.03485929 -0.2904798 -0.956246 -0.0026986 0.3927378 0.9196465 -7.48222e-4 0.1731834 0.9848893 -0.02533209 0.4121428 0.910767 -0.09848552 0.5089044 0.8551708 -0.0650379 0.5151716 0.8546158 -0.06503772 0.5151717 0.8546158 -0.1087673 0.560168 0.8212074 -0.1087674 0.560168 0.8212074 -0.07111144 0.5686613 0.8194922 -0.01210272 0.5241762 0.8515238 0.008246779 0.5196406 0.8543453 0.008244037 0.5196414 0.8543447 -0.01434296 0.3054834 0.9520894 -0.01879072 0.3066001 0.951653 -0.0143612 0.3057361 0.952008 -0.01935034 0.3096076 0.9506675 -1.6938e-4 0.3260775 0.9453431 -0.02326297 0.3306028 0.9434832 -0.001168549 0.3318906 0.9433172 -0.03758728 0.3775944 0.9252079 -0.01864361 0.3730949 0.9276058 -0.04684394 0.4146197 0.9087883 -0.04684364 0.4146196 0.9087884 0.001461863 0.1748825 0.9845882 0.001461982 0.1748825 0.9845883 -0.001816093 0.1699765 0.9854464 -0.02066725 0.2480809 0.9685189 -0.01395827 0.2458709 0.9692021 -0.006441652 0.2376639 0.9713261 -0.01411885 0.2391335 0.970884 -6.32997e-4 0.1786349 0.9839152 -6.33637e-4 0.178635 0.9839152 0.001433491 0.1784972 0.9839394 -0.01492583 0.2046561 0.97872 -0.006762146 0.2151746 0.9765523 -0.006762146 0.2151746 0.9765522 0.03223598 0.4165576 0.9085376 0.02203953 0.4477089 0.8939076 0.04554975 0.4527804 0.8904579 0.004830479 0.4667952 0.8843522 0.04509514 0.4806041 0.8757774 0.008256077 0.5177999 0.8554618 0.04463148 0.5060795 0.8613313 0.008022785 0.5516348 0.8340472 -0.01529622 0.5506608 0.834589 -0.01529657 0.5506609 0.834589 -0.03424435 0.2598596 0.965039 -0.03424429 0.2598596 0.965039 -0.02051752 0.2729218 0.9618175 -0.03457075 0.2794324 0.9595428 -0.02049523 0.2764781 0.9608017 -0.0346955 0.2811713 0.9590302 -0.03469526 0.2811713 0.9590302 -0.2425396 -0.9540025 0.1762206 0.02387332 0.1192612 0.9925759 -0.09185737 -0.7052872 0.7029453 -0.1035744 -0.9684629 -0.2266096 -0.02207511 -0.3793386 0.9249946 -0.07586491 -0.8702627 0.4867107 0.0166471 0.1005042 0.9947974 0.1343311 -0.5400339 0.8308541 0.1344003 -0.5405583 0.8305019 0.01800137 -0.4247205 -0.9051455 0.01800215 -0.4247264 -0.9051427 0.01709342 0.2240132 0.9744363 0.06288534 -0.09717464 0.9932787 0.1193856 -0.539654 0.833379 0.1193922 -0.5397129 0.8333399 0.06286579 -0.09703725 0.9932934 0.07568514 -0.1353176 0.9879073 0.1335299 -0.5404993 0.8306806 -0.009181261 0.3615323 0.9323143 0.08472204 -0.9725915 0.2165359 0.06991404 -0.4592365 0.8855585 0.03400546 -0.04937106 0.9982014 0.05637001 -0.05282658 0.9970113 0.1157367 -0.5389825 0.8343278 0.1453672 -0.9875741 0.0597139 0.1290895 -0.9894645 0.06554448 0.02299869 0.02402591 0.9994468 0.02737087 -0.2882179 0.9571737 0.0166049 -0.9398165 0.3412756 0.009428203 -0.3650145 0.9309541 -0.02560359 -0.9356865 0.3519023 0.0141136 -0.2190746 0.975606 0.01950943 -0.086573 0.9960544 0.02515226 -0.01213204 0.9996101 -0.006726741 -0.7477499 -0.6639465 0.02296763 0.01127254 0.9996726 0.0207355 -0.05784529 0.9981102 0.0260089 -0.05885553 0.9979276 0.02601712 -0.05931746 0.9979001 0.02400875 -0.05896908 0.9979711 0.01445633 0.1264498 0.9918677 0.03314131 -0.2375478 0.9708103 0.04207402 -0.5476186 0.8356696 -0.002913832 -0.7475903 -0.6641538 -0.005300343 -0.2752268 0.9613647 -0.009915351 -0.2746489 0.9614934 0.01478582 -0.005214631 0.9998772 -0.02380377 -0.4195964 0.9073987 -9.82145e-4 -0.1492921 0.9887927 -0.01130026 -0.2861791 0.9581096 -0.01881021 -0.3733901 0.9274836 -0.01583987 -0.3737075 0.9274114 -0.03392326 -0.5867474 0.8090592 -0.03612524 -0.5866481 0.8090359 -0.08725488 -0.9782048 0.1884201 -0.08403509 -0.9435409 0.3204191 -0.07628005 -0.9437696 0.3216835 -0.06557983 -0.839232 0.5398046 -0.06333583 -0.839283 0.5399933 -0.04508537 -0.645236 0.7626519 -0.04178565 -0.5853846 0.8096782 -0.02521616 -0.4216948 0.9063871 -0.01001948 -0.2443234 0.9696421 -0.06569254 -0.8703773 0.4879835 -0.05074435 -0.7147923 0.6974933 -0.04845207 -0.7148571 0.6975899 -0.02903908 -0.4971253 0.8671926 -0.03170067 -0.4969043 0.8672261 -0.04547572 -0.645213 0.7626482 -0.02619874 -0.4193265 0.9074574 -0.05089277 -0.6851775 0.726596 -0.04284572 -0.5852942 0.8096882 0.01585686 0.01280969 0.9997922 0.004137516 -0.1501956 0.9886477 0.008657276 -0.08432328 0.9964008 -0.003848195 -0.2453227 0.9694339 -0.001645147 -0.216073 0.9763759 -0.01471924 -0.3803681 0.924718 -0.01322847 -0.3612461 0.9323767 -0.07848149 -0.9314581 0.3552838 -0.08498877 -0.9884485 0.125486 -0.07365465 -0.9067636 0.4151565 -0.07545477 -0.9066709 0.4150356 -0.0553652 -0.74254 0.6675096 -0.07982003 -0.9705548 0.227271 -0.06781458 -0.8552345 0.5137851 -0.05829912 -0.6548977 -0.7534655 -0.05768334 -0.8773922 0.4762935 -0.05562508 -0.8559766 0.5140135 -0.05985742 -0.8986184 0.4346288 -0.0454151 -0.7432953 0.6674201 -0.08548378 -0.984574 0.1526643 -0.08831071 -0.9958844 0.02038264 -0.08803141 -0.9959083 0.02042251 -0.08810275 -0.9751666 -0.2031947 -0.08980679 -0.9955807 0.02745503 -0.06340694 -0.7199379 -0.691136 -0.09046334 -0.9921864 -0.08592087 -0.0903415 -0.9957189 -0.01955127 -0.0870915 -0.9686955 -0.232474 -0.08807009 -0.9758221 -0.2000373 -0.08807015 -0.975822 -0.2000375 -0.08875477 -0.9795824 -0.1803907 -0.08942514 -0.9805679 -0.1746129 -0.1039 -0.9905603 -0.08941513 -0.08841019 -0.9716724 -0.2191719 -0.08809715 -0.971719 -0.2190911 -0.08955454 -0.9821062 -0.1656734 -0.1342496 -0.9511207 -0.2781125 -0.1342509 -0.9511203 -0.2781127 -0.1525933 -0.9805466 -0.1234651 -0.1876757 -0.9811257 0.0465855 -0.1876807 -0.9811238 0.04660415 -0.1035794 -0.9684621 -0.2266109 -0.1035755 -0.9684643 -0.2266033 -0.114456 -0.989627 -0.08682286 -0.137921 -0.9891099 0.05137395 -0.08806985 -0.9758221 -0.2000372 -0.08780717 -0.9928395 0.08099132 -0.08845937 -0.9908298 -0.1021338 -0.08982461 -0.9906852 -0.1023449 -0.08982264 -0.9910278 -0.09897387 -0.08922463 -0.9821481 -0.1656026 -0.08658993 -0.988343 0.1252209 -0.08798193 -0.9959398 -0.01905721 -0.0870918 -0.9686954 -0.2324741 -0.08709156 -0.968698 -0.2324636 -0.07368278 -0.8318041 -0.550157 -0.08869373 -0.9629739 -0.2545872 -0.08881717 -0.9588921 -0.2695133 -0.08257752 -0.8799341 -0.467864 -0.08257645 -0.8799339 -0.4678647 -0.1660264 -0.9539558 -0.2498068 -0.2158048 -0.9759925 -0.02944648 -0.1660188 -0.98592 -0.01998519 -0.1802073 -0.9812863 0.06784319 -0.1304979 -0.988114 0.08124673 -0.1341949 -0.9843106 0.1145614 -0.1024758 -0.9868919 0.1246714 0.01679837 -0.1250476 0.9920085 0.01575714 -0.1248677 0.9920482 0.01001936 -0.1965172 0.9804492 -0.08859223 -0.6514023 0.7535427 -0.0556432 -0.6516222 0.7565 -4.96941e-4 -0.1408705 0.9900279 -0.01332825 -0.3410751 0.9399416 -0.005747377 -0.3416603 0.9398059 0.03359496 0.5093635 0.8598954 0.03359502 0.5093635 0.8598954 0.01430672 -0.1601626 0.986987 0.01430648 -0.1601625 0.9869869 -0.02104067 -0.3829828 0.9235159 -0.02581083 -0.4980046 0.8667901 -0.07513064 -0.4966607 0.8646869 -0.09281724 -0.776269 0.6235314 -0.1054207 -0.05097949 0.9931201 -0.1200028 -0.1804839 0.9762299 -0.2419986 -0.9541223 0.176316 -0.1958939 -0.946375 0.2569046 -0.2177259 -0.2912127 0.9315527 -0.2177257 -0.2912128 0.9315528 -0.1054217 -0.05097961 0.99312 -0.121723 -0.1803994 0.9760326 -0.1524132 -0.7058048 0.6918162 -0.1528669 -0.8235401 0.5462723 -0.1003949 -0.8234267 0.5584708 -0.09965866 -0.8055722 0.5840563 -0.06909286 -0.8055438 0.5884941 -0.0618236 -0.6829515 0.7278428 -0.0447973 -0.6830176 0.729027 -0.03248983 -0.5121191 0.8582998 -0.02124029 -0.5125628 0.858387 0.04328101 0.08108043 0.9957674 0.06215691 -0.09699171 0.9933424 0.04168319 0.04773879 0.9979898 0.04536038 0.02289897 0.9987082 0.04788064 0.04671901 0.9977599 0.04788082 0.04672372 0.9977596 0.02387362 0.1192612 0.9925758 0.02449256 0.05108791 0.9983938 0.0341584 -0.05076205 0.9981265 0.0234512 -0.04906666 0.9985201 0.05257636 -0.9725333 0.2267482 0.03615349 -0.2894808 0.9565008 0.0478999 -0.584466 0.8100032 0.02482342 -0.582617 0.8123676 0.02487641 -0.0331164 0.9991419 -0.1755074 -0.9517561 -0.2517094 -0.175515 -0.9517669 -0.2516632 -0.1885547 -0.9667574 -0.1727054 -0.2056807 -0.9728021 -0.1065436 -0.1342532 -0.9511206 -0.2781113 -0.06110316 -0.7005128 -0.7110193 -0.07822346 -0.9955658 -0.05224722 0.4807446 -0.8528701 0.2037087 -0.07498377 -0.9832862 0.1659082 -0.00419116 -0.5065867 0.8621789 -0.07004088 -0.8674891 0.4925007 -0.06256544 -0.7780253 0.6251097 -0.05969685 -0.7781891 0.6251863 -0.05115956 -0.673206 0.7376831 -0.04790163 -0.6734659 0.7376646 -0.03970479 -0.5690418 0.8213495 -0.03044372 -0.5700221 0.8210651 -0.02633047 -0.5196493 0.8539739 0.001897513 -0.5234636 0.8520458 -0.02187323 -0.9070311 0.4204952 0.02621483 0.07867115 0.9965558 0.004749 -0.3613981 0.9323996 0.02646654 0.1030977 0.9943191 -0.2420103 -0.9541032 0.1764034 -0.2452817 -0.9485428 0.2002587 -0.1911789 -0.9590141 0.209147 -0.205801 -0.918864 0.3366528 -0.1488209 -0.9248072 0.3501197 -0.1503584 -0.9144604 0.3757054 -0.1048182 -0.9155269 0.3883602 -0.1047247 -0.900737 0.4215514 -0.0805146 -0.9010528 0.4261706 -0.08444601 -0.9733628 0.2131515 -0.04711532 -0.6672732 0.7433215 -0.04025715 -0.6673673 0.74364 -0.008040189 -0.3258152 0.9453994 -0.004519641 -0.3261557 0.9453052 0.01723057 -0.06454044 0.9977663 0.01343172 -0.06391143 0.9978652 0.02888041 0.1593551 0.9867988 0.02627903 0.1435613 0.9892925 0.01683622 0.0749244 0.9970471 0.0168367 0.07492434 0.997047 0.01671874 0.08990544 0.99581 0.02370589 0.05202054 0.9983646 0.02489608 0.05182993 0.9983456 0.02326768 0.08288693 0.9962873 0.02326768 0.08288693 0.9962872 0.0239169 0.08354276 0.9962172 0.02846252 0.1431378 0.9892935 0.02574497 0.08858251 0.9957361 0.02310049 0.08916723 0.9957488 0.002741336 -0.1642255 0.986419 0.005903542 -0.1646905 0.9863276 -0.02104812 -0.469959 0.8824373 -0.02308124 -0.4698244 0.8824581 -0.05321192 -0.7739365 0.6310235 -0.06533217 -0.773846 0.6299953 -0.08314555 -0.9476085 0.3084235 -0.1092045 -0.9467905 0.3027575 -0.1056476 -0.9772207 0.1840604 -0.1013699 -0.9924328 0.06929099 -0.08959388 -0.9933543 0.07225018 -0.0889095 -0.9852693 0.1460801 -0.08382362 -0.9855684 0.147066 -0.07827824 -0.9367837 0.3410409 -0.07626748 -0.9368537 0.3413041 -0.06275659 -0.8025882 0.5932232 -0.06426817 -0.8025238 0.5931485 -0.0778563 -0.931487 0.3553454 -0.07238769 -0.8673817 0.4923505 -0.08564287 -0.9845636 0.1526428 -0.08601707 -0.9878545 0.1294001 -0.08303987 -0.964669 0.2500363 -0.07964342 -0.9648715 0.2503598 -0.08331698 -0.9931836 0.08151543 -0.05941075 -0.6547937 -0.7534691 -0.05947214 -0.6555868 -0.7527742 -0.05903387 -0.6556276 -0.7527731 -0.09904873 0.303014 0.9478248 0.02040064 0.1572981 0.9873405 -0.0976786 0.3025498 0.9481152 0.03894066 0.2586853 0.9651765 0.02195298 0.1350101 0.990601 0.02285748 0.1318271 0.9910091 0.0350176 0.1298097 0.9909204 0.02285748 0.1318273 0.9910091 0.02468478 0.1345452 0.9905999 0.01711398 0.174333 0.9845379 0.01947683 0.1704497 0.9851739 0.01251572 0.1963229 0.9804594 0.02156794 0.1945297 0.9806595 0.01153647 0.2363085 0.9716095 0.02926272 0.2323747 0.972186 0.007793605 0.148014 0.9889545 0.01724904 0.1708546 0.9851453 0.01331359 0.1362512 0.9905849 0.02226507 0.1480537 0.9887287 0.03776443 0.1905412 0.9809526 0.03776437 0.1905412 0.9809525 0.03363651 0.1606314 0.9864412 0.02784967 0.1845794 0.982423 0.02784991 0.1845793 0.982423 -0.2074584 -0.9751461 0.07778769 -0.1832404 -0.3435192 0.9210958 -0.1955628 -0.4783794 0.8561007 -0.2452117 -0.4127312 0.8772252 -0.1732575 0.008114755 0.9848431 -0.2023128 -0.1774136 0.9631168 -0.1481476 -0.1930735 0.9699355 -0.1383754 -0.02261543 0.9901217 -0.0790072 -0.03426283 0.9962851 -0.07766407 0.07088571 0.9944565 -0.009722948 0.06082242 0.9981012 -0.01238471 0.1323763 0.9911222 0.04214632 0.1223495 0.9915918 0.0374872 0.1760739 0.9836629 0.05503588 0.1725104 0.983469 -0.1518283 -0.9179698 0.3664419 -0.1518285 -0.9179698 0.3664418 -0.1380284 -0.5822144 0.8012331 -0.1526974 -0.5813594 0.7991902 -0.04218643 -0.1845064 0.9819254 -0.05606293 -0.5650836 0.8231267 -0.05606293 -0.5650836 0.8231267 -0.1727444 -0.2929173 0.9404036 -0.1190178 -0.3008904 0.9462027 -0.09960007 -0.1421527 0.984821 -0.03927159 -0.1476224 0.9882637 -0.02354842 -0.01263409 0.9996429 0.01809859 -0.01873689 0.9996606 0.03027451 0.042822 0.9986239 0.05593013 0.2550166 0.9653179 0.0525546 0.2626158 0.9634682 0.04570955 0.2641153 0.9634075 0.0448997 0.26626 0.9628549 0.002505779 0.2753899 0.9613295 0.003716588 0.2712015 0.9625154 -0.04830455 0.2816755 0.958293 -0.04260253 0.2519792 0.9667944 -0.0851413 0.2622441 0.9612383 -0.07550233 0.1458212 0.9864257 -0.1053504 0.1551093 0.9822639 -0.1396093 0.09908163 0.9852371 -0.1732597 0.008101284 0.9848428 -0.1732609 0.00809592 0.9848427 0.02001333 0.3045393 0.9522895 2.87088e-4 0.3234177 0.9462563 0.03052413 0.3168438 0.9479864 -0.008177578 0.3723098 0.9280725 0.02023482 0.3672971 0.9298835 -0.03026545 0.4406292 0.8971788 -0.01660639 0.4378781 0.8988809 -0.03502005 0.4678225 0.8831284 0.008365571 0.500946 0.8654382 -0.01597315 0.4819223 0.8760684 -0.06126266 0.4820368 0.8740066 -0.06126242 0.4820367 0.8740065 -0.04267686 0.4965518 0.8669574 -0.06594097 0.5231097 0.8497105 0.008368909 0.500945 0.8654386 -0.01427251 0.2733021 0.9618223 -0.0235114 0.4082458 0.9125694 -0.001869857 0.4010245 0.9160654 -0.02828001 0.4301551 0.9023119 0.008705794 0.4434759 0.896244 0.008705675 0.4434759 0.8962441 0.001461267 0.1749771 0.9845713 0.008350014 0.1738667 0.9847338 0.01009047 0.1467638 0.9891201 0.01267611 0.1471908 0.9890269 -0.2539309 -0.7576122 0.6012843 -0.2174481 -0.9730644 0.07656377 -0.2678766 -0.7539691 0.5998106 -0.2513127 -0.4638543 0.8495182 -0.2588917 -0.7563704 0.6007319 -0.2452092 -0.4127101 0.877236 0.02226507 0.1480537 0.9887287 0.019535 0.1640987 0.9862505 0.02201002 0.1636018 0.9862809 0.0206834 0.1642307 0.9862051 0.03056001 0.2101475 0.977192 0.02849799 0.2106103 0.9771546 0.03749704 0.245911 0.9685669 -0.09767866 0.3025493 0.9481154 -0.09795194 0.3053553 0.9471873 -0.04512423 0.2876847 0.9566617 -0.07121473 0.3594244 0.9304529 -0.02410447 0.3446835 0.9384094 -0.04246389 0.4236666 0.9048224 -0.04085618 0.4232558 0.9050885 -0.03475463 0.4070089 0.9127628 -0.01380693 0.4023957 0.9153617 0.003303945 0.3662434 0.9305132 0.02085053 0.3623086 0.931825 0.04218006 0.324386 0.9449839 0.0291801 0.3272764 0.944478 0.0507974 0.2923946 0.9549477 0.02052164 0.2989177 0.9540582 0.03849554 0.270659 0.9619054 0.001980841 0.2784198 0.9604574 0.001420378 0.1801431 0.9836394 0.001420557 0.180143 0.9836395 0.006789624 0.1832454 0.9830437 -0.007034599 0.1957615 0.9806263 0.01252645 0.1922793 0.9812602 -0.0066486 0.2231821 0.9747541 -0.006648659 0.2231821 0.974754 -0.02052944 0.2710266 0.9623529 -0.02053004 0.2710267 0.9623528 0.00223422 0.2687862 0.9631973 -0.01326847 0.2906627 0.9567336 -0.01326835 0.2906627 0.9567336 -0.02081996 0.2198266 0.9753167 0.00369811 0.2319669 0.9727166 0.01190906 0.2524425 0.9675385 0.01909661 0.2508603 0.9678349 0.01910674 0.2531958 0.9672264 0.04416823 0.247797 0.9678047 0.0434215 0.2058854 0.9776122 0.05102747 0.2042872 0.9775802 0.0443924 0.04847908 0.9978373 0.02882528 0.05122923 0.9982708 0.03461092 -0.1177147 -0.9924441 0.06159973 0.7605643 -0.6463339 0.1097859 0.9207312 -0.3744345 0.06737661 0.3881694 -0.9191219 -0.01118713 0.3790213 -0.9253203 0.07996845 0.1622342 -0.9835065 0.08380138 0.1470892 -0.9855669 0.08380132 0.1470863 -0.9855673 0.006476104 0.1768665 -0.9842135 0.04022383 0.1939127 -0.9801938 0.07185202 0.1929162 -0.978581 0.001513659 0.2715517 -0.9624226 0.03995335 0.3773552 -0.9252063 -0.008182108 0.2603693 -0.9654744 0.001513838 0.2715517 -0.9624227 -0.003192842 0.367478 -0.9300267 -0.009062588 0.3814103 -0.9243614 -0.006014466 0.3930224 -0.9195093 -0.006015002 0.3930222 -0.9195093 -0.006069242 0.3930238 -0.9195083 -0.006015002 0.3933123 -0.9193853 -0.01118612 0.3790214 -0.9253203 -0.03374087 0.3438082 -0.9384335 -0.003572046 0.3373327 -0.9413787 -0.08418214 0.3419722 -0.9359318 -0.08419597 0.3419723 -0.9359306 -0.04435986 0.3189108 -0.946746 -0.03374075 0.3438083 -0.9384335 -0.03374141 0.3438082 -0.9384334 -0.1178076 0.339802 -0.9330894 -0.131934 0.3051213 -0.9431301 -0.1319362 0.3051155 -0.9431316 -0.1178048 0.3398017 -0.93309 -0.1178053 0.3398017 -0.9330899 -0.1361972 0.417651 -0.8983418 -0.136198 0.4176509 -0.8983417 -0.13361 0.4128239 -0.9009578 -0.1355561 0.4056206 -0.9039339 -0.1345193 0.4059392 -0.9039458 0.006178617 0.4982489 -0.867012 -0.02327787 0.3951208 -0.9183342 6.9877e-4 0.3945732 -0.9188643 -0.0777741 0.3864213 -0.9190374 -0.07777863 0.3864153 -0.9190396 -0.1045446 0.386197 -0.9164727 -0.07892835 0.4826111 -0.872271 -0.0789262 0.4826137 -0.8722699 0.04768747 0.3891089 -0.9199566 0.07444208 0.4633796 -0.8830276 0.07443195 0.4633696 -0.8830338 0.1349263 0.4986885 -0.8562154 0.06737625 0.3881691 -0.919122 0.09952872 0.4247266 -0.8998341 0.1117278 0.4040632 -0.907882 0.1244016 0.4032252 -0.9066056 0.1153907 0.4298437 -0.8954994 0.1129997 0.4299697 -0.8957438 0.1151568 0.4281812 -0.8963258 0.1343094 0.4989438 -0.8561636 0.1343091 0.4989414 -0.856165 0.1249145 0.6274482 -0.7685734 0.1249148 0.6274489 -0.7685728 0.1365421 0.7979311 -0.5870794 0.08564698 0.8130796 -0.5758179 0.1339816 0.89653 -0.4222357 0.1311898 0.8968855 -0.4223573 0.1455299 0.8990697 -0.4129101 0.1438204 0.9160462 -0.3743998 0.1098474 0.9207244 -0.3744331 0.08691585 0.9451674 -0.3148085 0.08691799 0.9451673 -0.3148085 0.08691585 0.945168 -0.3148065 0.06290417 0.8898563 -0.4518837 0.06763684 0.9180911 -0.3905559 0.06250745 0.9177609 -0.3921834 0.06392472 0.8866787 -0.457946 0.06290704 0.8898538 -0.4518883 0.03218168 0.8705953 -0.4909461 0.01249927 0.8711376 -0.49088 0.03315508 0.7681593 -0.6393997 0.06159955 0.7605643 -0.6463339 0.06159961 0.7605641 -0.6463342 0.06078463 0.8849105 -0.4617776 0.08147656 0.926305 -0.3678596 0.06290596 0.8898562 -0.4518837 0.06517392 0.6654125 -0.7436252 0.05063658 0.4941896 -0.8678782 0.02664309 0.2041767 -0.9785714 0.02664256 0.204178 -0.9785711 0.01379042 0.3674373 -0.929946 0.04724222 0.4898433 -0.8705295 0.05063688 0.4941896 -0.8678781 0.02586489 -0.05661171 -0.9980612 0.02586454 -0.05661076 -0.9980613 0.02683013 0.1824367 -0.9828515 0.03045153 0.1985841 -0.9796108 0.03045117 0.1985842 -0.9796107 0.02526021 -0.002147018 -0.9996786 0.02273327 -0.05256181 -0.9983589 0.02273362 -0.05256181 -0.9983589 0.06682497 -0.07233917 -0.9951389 0.05785131 -0.1402823 -0.98842 0.04439365 -0.1402596 -0.989119 0.05069977 -0.08241397 -0.9953078 0.0507 -0.08241289 -0.9953078 0.03974092 0.1729133 -0.984135 0.06330704 0.1837847 -0.9809259 0.07162517 0.1835158 -0.9804039 0.1223304 0.2306583 -0.9653145 0.03745037 0.2340761 -0.9714968 0.05995512 0.2753905 -0.959461 -0.008137345 0.2774454 -0.960707 -0.001523315 0.3008697 -0.9536641 -0.00997579 0.3010655 -0.9535512 -0.008472502 0.3064217 -0.9518582 -0.03559595 0.323086 -0.9456999 -0.04461503 0.3072624 -0.9505785 -0.008518874 0.3065983 -0.9518009 -0.00808078 0.3668246 -0.930255 -0.003193855 0.367478 -0.9300267 -0.1153739 0.5254535 -0.8429635 -0.08607465 0.6050452 -0.7915248 -0.09395009 0.6048008 -0.7908157 -0.06919431 0.6394518 -0.7657111 -0.01695352 0.6396628 -0.7684687 -0.004015445 0.6572503 -0.7536616 0.05159747 0.6550922 -0.7537851 0.05569571 0.660562 -0.7487028 0.1007337 0.6572232 -0.7469341 -0.1318888 0.4594486 -0.8783577 -0.1163958 0.5043176 -0.8556377 -0.102353 0.504697 -0.8572076 -0.09739518 0.5123853 -0.8532148 -0.02239352 0.5126244 -0.858321 -0.0189715 0.5179077 -0.8552261 0.04933118 0.5155773 -0.8554219 0.05011188 0.5167698 -0.8546566 0.1023465 0.513454 -0.8519919 0.09719175 0.505742 -0.8571925 0.1308324 0.5031265 -0.8542521 0.1087993 0.9189216 -0.3791381 0.1116487 0.8892593 -0.4435679 0.06906151 0.8931736 -0.4443776 0.02583152 0.8588885 -0.5115109 0.03211694 0.858658 -0.5115416 -0.0211749 0.8080571 -0.5887234 0.009822607 0.8078241 -0.5893418 -0.04449343 0.6850893 -0.7270991 0.1077983 0.9170929 -0.3838229 0.1050973 0.9209883 -0.3751467 0.1095159 0.8600776 -0.4982697 0.1213557 0.8587433 -0.4978279 0.122861 0.7760668 -0.6185674 0.1339131 0.7747855 -0.6178792 0.1217608 0.8025811 -0.5839845 0.1200249 0.6234968 -0.772558 0.1191086 0.6235826 -0.7726306 0.1222247 0.7746804 -0.6204285 0.07233619 0.7793189 -0.6224384 0.07464396 0.7899359 -0.6086294 0.07087332 0.9067452 -0.4156804 0.1077966 0.9170931 -0.3838229 -0.1345168 0.4059392 -0.9039461 -0.1171126 0.3900464 -0.9133172 -0.1131905 0.4599683 -0.8806912 -0.1042824 0.3632668 -0.9258307 -0.07206189 0.5265812 -0.8470651 -0.06678009 0.6017085 -0.7959192 -0.08629924 0.6011518 -0.7944613 -0.04307311 0.7092304 -0.7036597 -0.06563425 0.7087659 -0.7023839 -0.02356535 0.7590909 -0.6505579 -0.001887381 0.7589114 -0.6511912 0.02525132 0.7888438 -0.6140749 0.05574381 0.7873353 -0.6139999 0.09403538 0.8257957 -0.5560745 0.09446424 0.6490061 -0.7548957 0.1359093 0.6450276 -0.7519761 0.1284947 0.4997546 -0.856583 0.1346281 0.4992708 -0.8559228 0.1349266 0.4986924 -0.856213 0.05504423 0.724365 -0.6872157 0.05581843 0.7672399 -0.6389266 0.002272129 0.6219239 -0.7830744 0.005335688 0.6851709 -0.7283628 -0.04113805 0.5575205 -0.8291432 -0.04945188 0.3961596 -0.9168491 -0.06584006 0.3960671 -0.915858 -0.06727761 0.3634697 -0.9291736 -0.09090256 0.3233899 -0.9418894 -0.09076255 0.3268769 -0.9406985 -0.08419567 0.3419722 -0.9359306 0.0381428 0.1023911 -0.9940127 0.03814184 0.1023911 -0.9940128 0.1070423 0.07629638 -0.9913228 0.07018607 0.01927542 -0.9973477 0.04995036 0.01956135 -0.9985601 0.04972296 0.0187512 -0.998587 6.17897e-4 0.01936405 -0.9998123 0.01261895 0.1051101 -0.9943806 0.003419518 0.105239 -0.9944411 0.004771709 0.222759 -0.9748618 -0.01103228 0.2228305 -0.9747948 0.01197755 0.3142851 -0.9492531 -0.01606673 0.4598886 -0.8878313 0.03461098 -0.1177148 -0.9924442 0.03461122 -0.1177151 -0.9924441 0.009221792 -0.07790219 -0.9969183 0.02571749 0.01613676 -0.999539 0.01361745 0.016231 -0.9997755 0.01443207 0.05980688 -0.9981057 0.02682983 0.1824342 -0.9828519 0.0192306 0.1725689 -0.9848096 0.0192306 0.1725692 -0.9848096 0.05065953 0.1726161 -0.9836856 0.050565 0.1673232 -0.9846045 0.06295812 0.1669784 -0.9839484 0.06874144 0.1812704 -0.9810279 0.1212842 0.1793622 -0.9762783 0.1094281 0.1570266 -0.9815132 0.05791652 0.1586561 -0.9856337 0.05294287 0.1404845 -0.9886664 -0.003639996 0.1416642 -0.989908 0.003006756 0.1893198 -0.9819109 -0.009260475 0.189538 -0.9818297 -0.004339039 0.2600213 -0.9655931 -0.03692656 0.2603475 -0.9648087 -0.008677721 0.3153825 -0.948925 -0.04855674 0.3155936 -0.9476512 -0.01759761 0.4242936 -0.9053536 -0.01264178 0.4242713 -0.9054468 -0.01101911 0.4598996 -0.8879026 0.0385304 0.6212826 -0.7826387 0.03520637 0.5314746 -0.8463422 0.06517368 0.6654126 -0.7436253 -0.1713074 0.3413789 -0.924183 0.1806669 -0.4271304 -0.8859566 -0.1551822 0.2786555 -0.9477709 -0.1743427 0.2816158 -0.9435556 -0.1035148 0.2768853 -0.9553111 -0.05154216 0.2313681 -0.9715 -0.004853844 0.1643217 -0.9863948 -0.004853904 0.1643218 -0.9863948 -0.005249261 0.1589227 -0.9872771 -0.07433897 0.2515984 -0.9649725 -0.04447025 0.2348453 -0.9710149 -0.04456692 0.2230404 -0.9737899 -0.05270236 0.1917706 -0.9800238 -0.03101283 0.2044403 -0.9783876 -0.02447772 0.2033141 -0.9788075 -0.01313984 0.1656473 -0.9860975 -0.01130795 0.1755728 -0.9844015 -0.01193249 0.1756724 -0.9843764 -0.01769131 0.1745594 -0.9844877 -0.0319879 0.1892428 -0.9814091 -0.03198796 0.1892428 -0.9814091 -0.1071629 0.2802345 -0.9539313 -0.1065117 0.3084559 -0.9452567 -0.1104954 0.3092588 -0.9445368 -0.1369694 0.2383084 -0.9614824 -0.1503117 0.2944434 -0.9437741 -0.1336616 0.291086 -0.9473139 -0.1335874 0.290614 -0.9474692 -0.1026069 0.2853206 -0.9529239 -0.1019505 0.2775055 -0.9552993 0.2109628 -0.5384441 -0.8158264 0.225473 -0.4534209 -0.8623058 0.2254723 -0.453421 -0.8623059 0.220363 -0.5565391 -0.8010646 0.2137206 -0.5570343 -0.8025187 0.2118135 -0.6585192 -0.722141 0.2194331 -0.6194944 -0.753708 0.2194324 -0.6194946 -0.7537081 0.2125113 -0.5271365 -0.8227795 0.2125132 -0.5271362 -0.8227792 0.179439 -0.4306195 -0.884516 0.1868417 -0.4298319 -0.8833656 0.1443125 -0.4134404 -0.8990222 0.1806645 -0.4271462 -0.8859494 0.19505 -0.3633125 -0.9110211 0.2258722 -0.3686958 -0.9016903 0.2422188 -0.2800378 -0.9289289 0.2113138 -0.274173 -0.9381769 0.2218444 -0.1771969 -0.9588463 0.1536591 -0.1634963 -0.9745039 0.1538979 -0.06860005 -0.9857025 0.04929369 -0.04894751 -0.9975843 0.03867626 0.02519828 -0.9989341 -0.05808323 0.04008316 -0.9975067 -0.06843167 0.0874325 -0.9938172 -0.1135396 0.09403204 -0.9890736 -0.1350748 0.1796118 -0.9744201 -0.1586697 0.1833859 -0.9701513 -0.1702792 0.2456854 -0.9542765 -0.1709275 0.2457861 -0.9541347 -0.09921216 0.03683823 -0.9943841 -0.08190363 0.03425908 -0.9960513 -0.01468235 -0.1268725 -0.9918103 0.01978343 -0.1297596 -0.9913481 0.0581879 -0.2097994 -0.9760116 0.1098743 -0.2125048 -0.9709631 0.1466751 -0.3169896 -0.9370187 0.1855831 -0.3189758 -0.9294156 0.2025955 -0.4302114 -0.8797006 0.2221049 -0.430988 -0.8745964 0.222809 -0.5305438 -0.8178505 0.2197709 -0.5304812 -0.8187127 0.2117869 -0.6127168 -0.7613964 -0.147217 0.2064605 -0.9673165 -0.1304655 0.1291502 -0.9830051 -0.1196165 0.1266108 -0.984714 -0.05956274 -0.08704775 -0.9944219 0.01604825 -0.1612076 -0.9867901 -0.002062022 -0.1591123 -0.9872583 0.2722837 -0.759331 -0.5909975 0.2722841 -0.759331 -0.5909974 0.2254256 4.67134e-4 -0.9742603 0.2254256 4.66651e-4 -0.9742603 0.225422 4.56139e-4 -0.9742611 0.213709 -0.02945983 -0.9764531 0.2112601 -0.02859216 -0.9770116 0.2392392 0.04388797 -0.9699683 0.1702247 0.06823807 -0.9830397 0.1943072 0.1338449 -0.9717666 0.08125895 0.170475 -0.9820057 0.09802961 0.2204397 -0.9704621 -0.05433422 0.2606477 -0.9639039 -0.04771018 0.2842652 -0.9575579 -0.1616042 0.306048 -0.9381997 -0.160351 0.3102999 -0.9370173 -0.1906663 0.3150279 -0.929733 -0.1902541 0.3220368 -0.9274134 -0.2013623 0.3236872 -0.924489 -0.2014202 0.323329 -0.9246016 -0.1864915 0.3211687 -0.9284781 -0.187972 0.3159272 -0.9299767 -0.1450846 0.3094143 -0.9397941 -0.156071 0.2834332 -0.9462069 -0.1407896 0.385922 -0.911725 -0.1407905 0.3859221 -0.9117248 -0.1996269 0.4143937 -0.8879341 -0.1733823 0.4462007 -0.877977 -0.2058569 0.4505134 -0.868712 -0.1783043 0.5029845 -0.8457035 -0.200288 0.5060186 -0.8389458 -0.1799759 0.5240309 -0.8324664 0.1232834 0.4174761 -0.900286 0.1407287 0.4221153 -0.8955523 0.1782432 0.4069328 -0.8958991 -0.1275209 0.5496482 -0.825606 -0.1275219 0.5496485 -0.8256057 -0.1106534 0.5312931 -0.8399307 0.03407317 0.4954001 -0.8679964 0.02472066 0.4981125 -0.8667599 0.03410899 0.5066603 -0.8614708 0.03410917 0.5066602 -0.8614708 0.1276468 0.2635017 -0.9561764 -0.03313148 0.2279685 -0.9731046 -0.033692 0.2097538 -0.9771736 -0.01793205 0.218075 -0.9757672 0.00145775 0.1631032 -0.9866079 0.00145781 0.1631032 -0.9866079 -0.01775825 0.1728882 -0.9847814 -0.01299881 0.1740816 -0.9846454 -0.02556109 0.1761273 -0.9840356 -0.01294308 0.1919167 -0.9813258 -0.01294296 0.1919167 -0.9813258 0.09417337 -0.7683928 -0.6330119 0.06248193 -0.9182741 -0.3909841 0.1220254 -0.7676976 -0.6290868 0.1585276 -0.611826 -0.7749439 0.1129508 -0.7679861 -0.630428 0.1878226 -0.4282353 -0.8839328 -0.1071631 0.2802346 -0.9539312 -0.07478171 0.267253 -0.9607204 -0.07551342 0.2715717 -0.9594512 -0.06792086 0.2504005 -0.965757 -0.05637788 0.2686865 -0.9615764 0.1478191 0.3748846 -0.9152109 0.1862618 0.2387187 -0.9530582 0.1862617 0.2387183 -0.9530583 0.1386238 0.03326892 -0.989786 0.2016405 0.1956435 -0.9597212 0.175643 0.2064746 -0.9625579 0.2114493 0.2603257 -0.9420827 0.1262969 0.2940734 -0.9474017 0.1552392 0.3351157 -0.9293 0.03427267 0.3766916 -0.9257044 0.05127149 0.3999601 -0.9150974 -0.09618222 0.4388874 -0.8933795 -0.09663873 0.4382538 -0.8936412 -0.1897474 0.4551503 -0.8699621 -0.2019131 0.4394041 -0.8753029 -0.2040221 0.4397037 -0.8746632 -0.2145075 0.4076071 -0.8876052 -0.1983509 0.40539 -0.8923653 -0.2124048 0.372728 -0.9033039 -0.1741288 0.3673693 -0.9136296 -0.189644 0.3387523 -0.9215649 -0.1306232 0.3297728 -0.9349799 -0.1449594 0.3082437 -0.9401981 -0.07770317 0.2965819 -0.9518411 -0.01752293 0.2629501 -0.9646503 -0.07171148 0.2693709 -0.9603628 -0.07700276 0.2704091 -0.9596612 -0.07175141 0.2768344 -0.958235 -0.1282107 0.2868902 -0.9493451 -0.07191824 0.359452 -0.9303882 -0.1384278 0.3364462 -0.9314729 -0.01777267 0.2361292 -0.9715591 -0.03739279 0.2399768 -0.9700582 -0.05639225 0.2693368 -0.9613937 -0.09282803 0.2764588 -0.956532 -0.09374022 0.2928359 -0.9515566 -0.136766 0.3002367 -0.9440091 -0.1347704 0.285631 -0.9488161 -0.1535634 0.2886494 -0.9450396 -0.1500068 0.2717788 -0.9505968 -0.1446871 0.2706293 -0.9517487 0.02748245 -0.9737813 -0.22582 -0.08061921 -0.9263646 0.3678984 0.1902906 -0.5952686 -0.7806695 -0.05952268 -0.9778338 0.2007441 0.363363 -0.9315007 -0.01654326 0.3606038 -0.9325881 -0.01563477 0.2361547 -0.8621596 0.4482319 0.1229007 -0.5444264 -0.8297562 -0.073596 0.07086819 -0.994767 -0.004728257 0.2376923 -0.971329 0.002174556 0.2895755 -0.9571528 0.017982 0.4068486 -0.9133185 0.07207387 0.7726556 -0.6307208 0.01793956 0.4065355 -0.9134588 0.0021829 0.2896308 -0.957136 0.002172708 0.2895541 -0.9571591 -0.01155561 0.4577675 -0.888997 -0.0115565 0.4577555 -0.889003 -0.006996452 0.513718 -0.8579306 -0.006854891 0.5136949 -0.8579456 -0.04507237 -0.09107595 -0.9948235 -0.01248419 0.4550287 -0.8903893 -0.005949854 0.5258117 -0.8505802 0.006410539 0.5237464 -0.8518501 -0.003006815 0.4368772 -0.8995161 0.02251327 0.4324194 -0.9013915 -0.004721939 0.2377378 -0.9713179 -0.06296092 0.1737748 -0.9827707 -0.04010945 0.4806188 -0.8760119 -0.04010945 0.4806187 -0.876012 -0.1010717 0.2715148 -0.9571124 -0.09167283 0.1909135 -0.9773168 0.1642297 -0.562044 -0.8106387 0.1521742 -0.5632691 -0.8121396 0.0480228 -0.3031606 -0.9517287 0.03497928 -0.3023804 -0.9525453 -0.03481417 -0.08780705 -0.9955289 -0.0286557 -0.1089535 -0.9936338 0.08554679 -0.4221066 -0.9025008 0.09585654 -0.4220974 -0.9014685 0.01545083 -0.237997 -0.971143 0.06988018 -0.4055723 -0.9113878 0.08142864 -0.405695 -0.9103741 0.1393907 -0.566236 -0.8123712 0.1547275 -0.5648327 -0.8105698 0.2015581 -0.67747 -0.7073957 0.215285 -0.6748372 -0.7058662 0.2445747 -0.7394524 -0.6272108 0.2490066 -0.7382574 -0.6268746 -0.0635038 -0.009928703 -0.9979323 -0.06348067 -0.01008975 -0.9979321 0.2336659 -0.8416429 0.4868648 0.2350974 -0.8543416 0.4634972 0.1705337 -0.8402858 -0.5146241 0.1868042 -0.7197976 -0.6685774 0.2029864 -0.716633 -0.6672583 0.2758306 -0.8834035 -0.3788348 0.2968115 -0.8761593 -0.3797997 0.338797 -0.9400782 -0.03833502 0.2229129 -0.8086469 -0.5444263 0.2403072 -0.8040394 -0.5438503 0.3047795 -0.9344776 -0.1840143 0.3264899 -0.9264035 -0.1875655 0.3445518 -0.9315912 0.1158526 0.2361404 -0.8621617 0.4482352 0.2361138 -0.8619549 0.4486469 0.2361109 -0.8619438 0.4486697 0.1326628 -0.9788951 -0.1554512 0.1123504 -0.9308331 0.3477456 0.2625082 -0.9030427 -0.3400049 0.2625073 -0.903043 -0.3400047 0.2618864 -0.8832506 0.3889523 0.3665761 -0.9092156 -0.197355 0.376178 -0.9046151 -0.2004041 -0.06614714 -0.9771099 0.2021899 -0.03076034 -0.997927 0.05652946 0.02888 -0.9985595 0.04521864 0.04948836 -0.9984833 -0.0241248 0.09885251 -0.994543 -0.03335094 0.1146386 -0.9889788 -0.09369623 0.1905043 -0.975666 -0.1085545 0.1998482 -0.9662824 -0.1623549 0.3127707 -0.931171 -0.1873371 0.3141397 -0.9218178 -0.2270861 0.3716648 -0.8963323 -0.2417716 0.3709642 -0.8939498 -0.2514742 0.3441099 -0.9064269 -0.2449051 0.3475404 -0.9126362 -0.2151993 0.3423802 -0.9148261 -0.2141703 0.3304095 -0.8925706 -0.3068342 0.3254705 -0.8945751 -0.3062747 0.3093311 -0.8638947 -0.3974924 0.2923954 -0.8700435 -0.3968996 0.37211 -0.9267799 0.05111861 0.3649621 -0.9283165 0.07092982 0.3664124 -0.9277893 0.07034868 0.3629019 -0.9103118 0.1990842 0.3629017 -0.9103118 0.1990852 0.249521 -0.8284876 -0.5013458 0.2693012 -0.8225668 -0.50086 0.3222475 -0.92211 -0.2141722 0.3388608 -0.9155358 -0.2167203 0.356081 -0.9334695 -0.04290741 0.3621553 -0.928965 0.07660007 0.3624388 -0.9255414 0.1095953 0.3607183 -0.9323153 0.02589327 0.1718766 -0.3515757 0.9202461 -0.0955761 0.05833679 -0.9937113 -0.09557628 0.05833673 -0.9937113 0.05869853 -0.3285829 -0.9426493 -0.1123524 0.1595419 -0.9807769 -0.08632349 0.07797467 -0.993211 -0.1228702 0.2692879 -0.9551895 -0.1178657 0.1599293 -0.9800665 -0.09817248 0.2372071 -0.9664858 -0.1097058 0.239178 -0.9647582 -0.1005733 0.1924004 -0.9761492 -0.01170974 -0.1796878 -0.9836539 -0.01170885 -0.179692 -0.9836533 -0.01170176 -0.1797201 -0.9836482 -0.01172953 -0.1796914 -0.9836531 -0.03807407 -0.1683255 -0.984996 -0.06348884 -0.01003146 -0.9979321 0.1787895 -0.5971175 -0.781975 0.1138613 -0.4366568 -0.8923937 0.1036762 -0.4369608 -0.8934856 0.02725338 -0.2376886 -0.970959 0.01917284 -0.2370172 -0.9713163 -0.06787854 -0.009864449 -0.9976449 -0.09891432 0.09669959 -0.9903864 -0.09640032 0.09629607 -0.9906736 -0.09989738 0.1114557 -0.9887356 -0.09545731 0.08175259 -0.9920707 0.04734581 -0.2381354 -0.9700773 0.047347 -0.2381354 -0.9700772 -0.1404275 0.2226358 -0.9647349 -0.1030017 0.1003987 -0.9896013 -0.1030013 0.1003987 -0.9896013 -0.1117662 0.1234636 -0.986035 -0.03941303 -0.1156631 -0.9925062 -0.02328759 -0.1176757 -0.992779 -0.006433069 -0.1641482 -0.9864147 0.1167917 -0.4523687 -0.8841506 0.1262097 -0.451862 -0.8831149 0.2149016 -0.6511949 -0.7278479 0.2854932 -0.8457283 -0.4508187 0.2274649 -0.7128715 -0.6633808 0.2854958 -0.8457275 -0.4508182 0.2532006 -0.6605517 -0.7067962 0.24624 -0.6624637 -0.7074657 -0.001700341 -0.9747467 -0.2233074 0.1132766 -0.8082154 -0.5778894 0.1801494 -0.9424321 -0.2817233 0.1801502 -0.9424319 -0.2817233 0.1962217 -0.806873 -0.5571831 -0.01128214 -0.986903 0.16092 -0.004637002 -0.987015 0.1605608 -0.05155038 -0.9461438 0.3196161 -0.0515502 -0.9461438 0.3196161 -0.1354921 0.2238103 -0.9651688 0.2568678 -0.6514007 -0.7139299 0.252636 -0.6410809 -0.7247002 0.2963016 -0.7391213 -0.6049007 0.2625658 -0.7512604 -0.6055305 0.2555061 -0.7359646 -0.6269551 0.2461112 -0.7386473 -0.6275584 0.1907551 -0.6086136 -0.7701961 0.1811381 -0.6101089 -0.771334 0.09821617 -0.4043241 -0.909327 0.08289408 -0.4042842 -0.9108693 -0.002371966 -0.1687152 -0.985662 -0.01422691 -0.1674003 -0.9857864 -0.07422822 0.0279538 -0.9968494 -0.07367283 0.0278688 -0.996893 -0.04097884 -0.08699458 -0.9953656 0.2511638 -0.876433 0.4108306 -0.007787227 -0.2359543 -0.9717329 -0.006238579 0.2037 -0.9790135 -0.006234169 0.2037355 -0.9790061 -0.009305775 0.1811376 -0.9834138 -0.03573626 0.1292182 -0.9909721 -0.04314035 0.2726994 -0.9611316 -0.05058473 0.1036627 -0.9933253 -0.01183027 0.4547553 -0.8905379 -0.0115562 0.457759 -0.8890013 -0.0115562 0.4577591 -0.8890013 -0.03573638 0.1292182 -0.9909721 -0.03640687 0.1227098 -0.9917746 -0.03613555 0.1226686 -0.9917897 -0.02120339 0.207759 -0.9779502 -0.01419216 0.156888 -0.9875144 -0.01297414 0.1567007 -0.9875609 -0.01123583 0.1814423 -0.9833374 0.1326618 -0.9788952 -0.1554511 0.1099629 -0.9913359 -0.07184183 0.1156462 -0.990611 -0.07290923 -0.03448063 -0.9528795 0.3013829 0.06367629 -0.9624153 -0.2640114 0.04029327 -0.9660075 -0.2553547 -0.04254585 -0.9794819 0.19699 -0.06348896 -0.01003181 -0.9979321 -0.06348741 -0.01004314 -0.9979321 -0.1060206 0.3364936 -0.9356986 -0.1035677 0.3357883 -0.9362265 -0.07772231 0.2082642 -0.9749796 -0.07687819 0.4180402 -0.9051697 -0.07687819 0.4180401 -0.9051697 0.02997732 -0.9736621 -0.2260164 0.01507502 -0.9862871 -0.1643484 0.08000475 -0.9819687 -0.1712797 0.1019281 -0.9634519 -0.2477321 0.1409472 -0.957689 -0.2509298 0.1589021 -0.9316958 -0.3266394 0.2118926 -0.9198016 -0.3302524 0.2216312 -0.8855293 -0.4083105 0.3000875 -0.8598056 -0.4131365 0.2959101 -0.8224918 -0.4857411 0.3305671 -0.8079776 -0.4877474 0.3347432 -0.8181908 -0.4674513 0.3028019 -0.8319303 -0.4649765 0.3108316 -0.8480641 -0.4291515 0.3052108 -0.8502447 -0.428871 0.2870334 -0.8126018 -0.5072377 0.281707 -0.8144113 -0.5073218 0.2653847 -0.7805041 -0.5660249 0.2503347 -0.7848216 -0.5669106 0.2210439 -0.718717 -0.659231 0.2028397 -0.7225497 -0.6608918 0.1467474 -0.5758411 -0.8042837 0.1319985 -0.5772107 -0.8058562 0.06886738 -0.3920739 -0.9173523 0.03445512 -0.3912606 -0.9196347 0.07842248 -0.5470058 -0.8334473 0.1138774 -0.6663009 -0.7369362 0.1657052 -0.659601 -0.7331224 0.2307397 -0.8256462 -0.514847 0.2415899 -0.6097384 0.7548863 0.2978461 -0.8300131 0.4715569 0.1438929 -0.2721552 0.9514338 0.2398517 -0.7830446 -0.5738574 0.1718764 -0.3515757 0.9202461 -0.05320477 0.1735349 -0.9833894 -0.05320489 0.1735349 -0.9833895 -0.06241893 0.2588528 -0.9638979 -0.07314342 0.2120592 -0.9745158 -0.07791966 0.2128137 -0.9739809 -0.0749548 0.2735545 -0.9589315 -0.09190827 0.2698399 -0.9585089 -0.1051412 0.2629155 -0.9590728 -0.1009728 0.2621925 -0.9597185 -0.09539163 0.1821182 -0.9786385 -0.09539175 0.1821182 -0.9786385 -0.110688 -0.6840646 0.7209742 0.03416955 -0.29534 0.954781 -0.001727104 -0.2160698 0.9763764 0.002933681 -0.2168108 0.9762093 -0.1173487 -0.9900619 0.07750225 -0.05664765 -0.5023918 0.8627825 -0.003668069 -0.2157602 0.9764394 0.006260931 -0.1830694 0.9830801 0.05189269 -0.2715606 0.9610214 0.01387625 -0.2493738 0.9683079 0.0347743 -0.2532451 0.9667769 5.59053e-4 -0.1821541 0.9832698 0.004706203 -0.1876906 0.9822168 4.56152e-4 -0.1870127 0.9823574 0.01589399 -0.2029325 0.9790638 1.72871e-4 -0.2003695 0.9797204 0.0236994 -0.2054474 0.9783812 0.01463764 -0.2171682 0.9760244 0.0146377 -0.2171683 0.9760245 0.006914794 -0.631024 0.7757325 0.025945 -0.635989 0.7712618 -0.05687141 -0.5899491 0.8054351 -0.04296064 -0.5819827 0.8120656 0.02824199 -0.6537057 0.7562216 0.02824193 -0.6537058 0.7562217 0.1076164 -0.6259285 0.7724197 0.1235647 -0.6338283 0.7635401 0.1819765 -0.6426353 0.7442477 0.1138039 -0.5852615 0.8028186 0.1138033 -0.5852614 0.8028187 0.1367841 -0.5316665 0.8358355 0.07257014 -0.5153949 0.8538745 0.1253858 -0.5245774 0.8420789 0.0521878 -0.4358142 0.8985224 0.09354245 -0.4433623 0.891448 0.06729745 -0.8184571 -0.570613 0.06729769 -0.8184571 -0.570613 0.1204442 -0.5117254 0.8506646 0.1204197 -0.5114861 0.850812 0.1204205 -0.5114928 0.8508079 0.2184054 -0.9474244 -0.2338505 0.1344708 -0.6646192 0.7349823 0.1127771 -0.9543066 -0.2767315 -0.01623982 -0.3476048 -0.9375005 0.1719113 -0.8555175 -0.4884018 0.1338855 -0.7080401 -0.6933642 0.1338844 -0.7080405 -0.693364 0.2240401 -0.9215431 -0.3171188 0.2406638 -0.9006705 0.3617643 0.1830056 -0.6618134 0.7269883 0.2161775 -0.6629787 0.7167472 0.3109074 -0.8362913 0.4516119 0.3308303 -0.9377001 -0.1061587 0.3308304 -0.9377002 -0.1061585 0.3700538 -0.8996039 0.2318904 0.2294844 -0.7072749 0.6686547 0.2746262 -0.7064364 0.6523252 0.2934951 -0.7839281 0.5470989 0.3352708 -0.7795261 0.5290865 0.3376686 -0.8437505 0.4172109 0.3519902 -0.8671144 0.3524425 0.3432272 -0.8689153 0.3566249 0.3614822 -0.9036259 0.2297629 0.3614836 -0.9036254 0.2297622 0.3545622 -0.886856 0.2962636 0.3545616 -0.886856 0.2962639 0.2986696 -0.9481045 0.1090614 0.1584202 -0.8701885 0.4665564 0.1584209 -0.8701886 0.4665561 -0.01167476 -0.8751481 0.4837143 -0.02457243 -0.8628078 0.5049344 -0.02457195 -0.8628079 0.5049343 -0.060777 -0.8779993 0.4747878 -0.1249125 -0.8187793 0.5603547 -0.1249121 -0.8187794 0.5603546 -0.1432965 -0.8778957 0.4569085 -0.110881 -0.6839928 0.7210125 -0.1108818 -0.6839973 0.7210083 -0.08417141 -0.8454791 0.527333 -0.08415246 -0.8453733 0.527506 -0.08417606 -0.8455055 0.5272901 -0.05568474 -0.671932 0.7385165 -0.04665499 -0.6140419 0.7878932 -0.04666244 -0.6140909 0.7878547 -0.0182535 -0.4100159 0.9118957 -0.0182535 -0.4100159 0.9118958 -0.01825702 -0.4100413 0.9118843 -0.07379263 -0.778485 -0.6233102 -0.07372468 -0.7742681 -0.6285488 -0.07374513 -0.7702499 -0.6334641 -0.07090157 -0.7703922 -0.6336156 0.001501739 -0.5758562 0.8175495 0.002932071 -0.2168222 0.9762067 -0.06431108 -0.6997901 0.7114477 -0.02576053 -0.7054891 0.7082524 -0.07379299 -0.7784969 -0.6232953 -0.07379287 -0.7784969 -0.6232953 0.03914231 -0.2412633 0.9696699 -0.07076698 -0.7627267 -0.6428374 -0.07364898 -0.7625834 -0.6426836 -0.07369118 -0.7698477 -0.6339591 -0.06879603 -0.7700903 -0.6342145 0.05798298 0.1169528 0.9914434 -0.06093335 -0.477487 -0.8765233 0.06267064 -0.2328006 0.970503 -0.04405838 -0.4103725 -0.910853 -0.04405814 -0.4103725 -0.910853 0.08263725 -0.3247589 0.9421798 -0.01836282 -0.3354923 -0.9418639 -0.0183624 -0.3354922 -0.941864 -0.06149744 -0.3790226 -0.9233417 -0.059978 -0.4775002 -0.8765822 -0.06006407 -0.4672721 -0.882071 -0.05199331 -0.4673638 -0.8825348 -0.05480843 -0.3954263 -0.916861 -0.03893721 -0.3946069 -0.9180247 -0.0452972 -0.32055 -0.9461479 -0.0177918 -0.3163471 -0.9484767 0.1504733 -0.8586736 0.489936 0.7917811 -0.609789 0.03521257 0.2420896 -0.9632194 0.1166241 -0.003363728 -0.6266533 0.7792909 0.02056699 -0.6295318 0.7767024 0.01593476 -0.6837832 0.7295112 0.0506218 -0.6872365 0.7246679 0.04911398 -0.7115249 0.7009424 0.0888198 -0.7144996 0.6939751 0.088355 -0.736122 0.6710572 0.1443538 -0.7385475 0.6585662 0.1496824 -0.8914387 0.4277057 0.2249506 -0.8919649 0.3921683 0.1143321 -0.6973566 -0.7075464 0.1389501 -0.686557 -0.7136753 0.2663245 -0.8947334 0.3585017 0.2568845 -0.8945807 0.3656991 0.2402844 -0.8968076 0.371483 0.03337866 -0.4409714 0.8969002 0.01266324 -0.4379085 0.8989304 0.01630973 -0.3974782 0.9174667 -1.36949e-4 -0.3950074 0.9186779 -0.01818674 -0.5732005 0.8192133 -0.03012657 -0.6757332 0.7365304 0.03523796 0.008653879 0.9993415 0.03524315 0.008705735 0.9993408 -0.06756132 -0.4971272 -0.8650434 0.1725444 -0.6166512 0.7680948 0.1433744 -0.6144797 0.7757954 0.1495621 -0.9207273 0.360406 0.1156238 -0.5500046 0.8271192 0.08822774 -0.5466 0.832733 0.0872538 -0.521881 0.848544 0.05729579 -0.5178946 0.8535234 0.05742847 -0.4932055 0.8680152 0.02978694 -0.4892513 0.8716341 -0.001727342 -0.2160721 0.9763759 -0.006004095 -0.2760557 0.9611228 0.01351153 -0.2791116 0.9601637 0.01349443 -0.2909647 0.9566386 0.02240169 -0.2923544 0.9560476 0.02151674 -0.3227061 0.9462547 0.03754317 -0.3252835 0.944871 0.03720337 -0.3650205 0.9302559 0.05821579 -0.3684802 0.927811 0.05985468 -0.3912191 0.9183492 0.08212268 -0.394839 0.9150727 0.08506721 -0.4199954 0.9035305 0.1020883 -0.4227613 0.9004726 0.1075883 -0.4447289 0.88918 0.1154407 -0.4458871 0.8876137 0.1267448 -0.4824068 0.8667292 0.1393245 -0.4840409 0.8638826 0.156607 -0.5296939 0.8336058 0.1736306 -0.5314771 0.8290866 0.1965141 -0.5814695 0.789478 0.219092 -0.5830332 0.7823497 0.2628404 -0.6815664 0.6829218 0.2689863 -0.6815866 0.6805045 0.3117558 -0.7646936 0.5639611 0.2951329 -0.7657163 0.5714676 0.3306612 -0.829833 0.449489 0.3294205 -0.8299852 0.4501185 0.3515447 -0.8525836 0.3866747 0.2413482 -0.8645101 0.440878 0.2545934 -0.8770823 0.4073191 0.08562827 -0.8764208 0.4738717 0.15342 -0.9374673 0.3124378 -0.01924085 -0.8738628 0.4857916 -0.04296058 -0.5819827 0.8120656 -0.08594238 -0.514173 0.8533698 -0.0441665 -0.5294495 0.847191 -0.05662107 -0.5185257 0.8531854 -0.03936767 -0.5086007 0.8601021 0.03710377 -0.3756486 0.9260192 0.03128272 -0.3733027 0.927182 0.06835907 -0.380059 0.9224328 0.02634334 -0.3470564 0.9374743 0.05403727 -0.3299165 0.9424623 0.0219888 -0.3237738 0.9458791 0.05583035 -0.3283668 0.9428989 0.03698348 -0.3134471 0.9488852 0.06286478 -0.318268 0.945914 0.03569436 -0.2952662 0.954748 0.03569471 -0.2952663 0.954748 -0.1258448 -0.4757174 0.8705493 -0.07176661 -0.5956019 0.8000676 -0.1157621 -0.5798466 0.8064596 -0.07403492 -0.6379315 0.7665262 -0.07217556 -0.6385293 0.7662056 -0.04430735 -0.6709481 0.7401794 0.0162692 -0.6868662 0.7266018 0.01922345 -0.6897221 0.723819 0.1581291 -0.7145767 0.6814509 0.1243141 -0.6880924 0.714895 0.243306 -0.7010205 0.6703524 0.1868193 -0.6598974 0.7277595 0.2209838 -0.6631903 0.7150838 0.1499889 -0.578462 0.8018013 0.1935376 -0.5837603 0.7885221 0.115057 -0.4922512 0.8628155 0.1547201 -0.4980133 0.8532552 0.08413285 -0.4124582 0.9070832 0.1137683 -0.4172948 0.9016218 0.06794089 -0.3783778 0.9231545 0.09437441 -0.3829334 0.9189426 0.05794906 -0.3502389 0.9348662 0.08358478 -0.35484 0.9311832 0.05586755 -0.3286438 0.9428002 0.0819633 -0.3334631 0.9391936 0.06256145 -0.3141813 0.9472994 0.07079434 -0.3157601 0.9461944 0.04931473 -0.2773784 0.9594944 0.03422367 -0.274525 0.9609708 -0.1108818 -0.6839974 0.7210081 -0.1107485 -0.6843296 0.7207134 -0.1255072 -0.6792195 0.7231244 -0.0876668 -0.7289614 0.6789181 -0.06470608 -0.7356572 0.6742562 -0.04141598 -0.7610014 0.647427 0.04487419 -0.7795889 0.624682 0.04466849 -0.7794045 0.6249266 0.2112388 -0.7973577 0.5653308 0.1801315 -0.7751855 0.6055082 0.3086048 -0.7773833 0.5481225 0.2583289 -0.743389 0.6169595 0.287373 -0.743525 0.6038107 0.2206839 -0.6622965 0.7160042 0.2627538 -0.6643302 0.6997327 0.1885008 -0.56977 0.7998935 0.2155423 -0.5722441 0.7912511 0.1472826 -0.4757405 0.8671671 0.1594803 -0.4773134 0.86414 0.1178058 -0.4323244 0.8939896 0.1293078 -0.4340243 0.891573 0.09698146 -0.3955147 0.9133251 0.1085774 -0.3973879 0.9112047 0.08537733 -0.3671196 0.9262473 0.09747397 -0.3691933 0.9242268 0.08330059 -0.3490739 0.9333854 0.08078444 -0.3486172 0.9337772 0.0709781 -0.3226323 0.9438594 0.05898642 -0.3205077 0.9454075 0.05155217 -0.2985093 0.9530134 0.039011 -0.2963094 0.954295 0.03441172 -0.2617173 0.9645309 0.02463513 -0.2600829 0.9652719 0.02196758 -0.2355805 0.9716065 0.01702237 -0.2347933 0.9718962 0.01450634 -0.2246825 0.9743241 -0.00282222 -0.2219342 0.9750576 -0.003668069 -0.2157604 0.9764394 -0.005021393 -0.0863685 0.9962506 0.005286633 0.1787893 -0.9838732 0.05005359 0.4013321 -0.9145639 0.02684402 0.1272518 -0.9915071 -0.0324651 9.07229e-4 -0.9994724 0.01002681 0.1003116 -0.9949055 0.02612674 0.1103004 -0.9935549 0.009105622 0.1061194 -0.9943118 0.03189134 0.1028053 -0.9941902 0.01671463 0.08943945 -0.995852 0.0819205 0.5086271 -0.8570808 0.01229411 0.130549 -0.9913657 -0.002647757 0.108752 -0.9940654 0.01176619 0.1123663 -0.9935972 0.006045758 0.1064913 -0.9942952 0.01478278 0.09815913 -0.995061 0.01905459 0.1034949 -0.9944475 0.01244693 0.1007727 -0.9948316 0.01143485 0.09438431 -0.9954702 0.02715706 0.1058674 -0.9940093 0.02684581 0.1272559 -0.9915066 -0.02087414 0.03728199 -0.9990867 0.09913194 0.346058 -0.9329613 0.07192605 0.3232138 -0.9435886 0.1278502 0.4767316 -0.8697018 0.1806304 0.6442073 -0.7432157 -0.04232227 -0.003829002 -0.9990966 0.01291632 0.08203971 -0.9965454 0.02100157 0.08675694 -0.996008 0.007523775 0.1623206 -0.9867094 8.75082e-4 0.1508388 -0.9885581 -0.01977568 0.06053161 -0.9979704 0.04473787 0.4025257 -0.9143149 0.1197893 0.7652057 -0.6325432 0.009659051 0.2011793 -0.9795069 0.009652137 0.2011458 -0.9795138 0.0167182 0.2342484 -0.972033 0.02753907 0.2854258 -0.9580051 -0.01077109 0.1024998 -0.9946747 0.02593827 0.2857345 -0.9579577 0.02595961 0.2858385 -0.9579262 0.02359306 0.2600709 -0.9653012 0.0220431 0.2599368 -0.9653741 0.01672434 0.234278 -0.9720258 0.005286931 0.1787906 -0.983873 0.005363702 0.1791444 -0.9838082 0.005474627 0.1791403 -0.9838083 0.0418868 0.3454211 -0.9375125 0.0795027 0.5072795 -0.8581066 -0.02064371 0.03800529 -0.9990643 0.01163744 0.1592683 -0.9871667 0.001376569 0.1579023 -0.9874538 0.001918315 0.1604734 -0.9870383 0.002488553 0.1604525 -0.9870404 0.003125607 0.1630349 -0.9866154 -0.0381906 0.008408546 -0.9992351 0.05103838 0.0827012 -0.9952666 0.00540781 0.05334866 -0.9985613 0.03616958 0.09404337 -0.9949108 0.0207073 0.08526456 -0.9961431 0.03222334 0.0970453 -0.9947582 0.03439348 0.09844917 -0.9945476 -3.31843e-4 0.1193616 -0.9928508 0.009240746 0.1217596 -0.9925165 0.006768465 0.1089692 -0.9940221 0.02081245 0.11475 -0.9931764 0.006970167 0.0786072 -0.9968813 -0.02791094 0.02394407 -0.9993236 0.02036273 0.1547544 -0.9877431 0.008438706 0.1328752 -0.9910969 0.03600412 0.1269437 -0.9912562 0.03600406 0.1269438 -0.9912563 0.1124234 0.5823589 -0.8051205 0.001347005 0.1388716 -0.9903095 -6.13925e-4 0.138608 -0.9903472 -0.002535045 0.1285635 -0.991698 0.008266389 0.1505655 -0.9885655 0.008531808 0.1527907 -0.9882217 0.007523775 0.1623208 -0.9867094 -0.02606695 -0.1654222 0.9858783 -0.1373295 -0.7478938 0.649458 -0.2389345 0.6353341 0.7343438 -0.03906983 -0.1185597 0.992178 -0.0371747 -0.1294479 0.9908891 -0.01283162 -0.03375416 0.9993478 -0.03139686 -0.1277065 0.991315 -0.3919727 -0.7812457 0.4858112 -0.2689675 -0.8845375 0.3811166 -0.1714001 0.5405952 0.8236377 -0.1714926 0.5411593 0.8232477 -0.1714385 0.5408294 0.8234758 -0.008295536 -0.1281961 0.9917141 -0.00830233 -0.1282281 0.99171 -0.180995 -0.9109158 0.3707737 0.02087634 -0.0372762 0.9990869 -0.3042002 -0.7243688 0.6186696 -0.1116441 -0.2851361 0.9519628 -0.0784716 -0.2169887 0.973015 -0.2253877 -0.5986164 0.7686734 -0.02014392 -0.1543858 0.9878053 -0.02420526 -0.1553894 0.9875566 -0.0386098 -0.2044481 0.9781157 -0.0369746 -0.2005715 0.9789811 -0.2436688 -0.8005602 0.5474749 -0.1919872 -0.6765708 0.71091 -0.08608448 -0.1181188 0.9892611 -0.08246499 -0.1205914 0.9892711 -0.02044707 -0.09663838 0.9951096 -0.05663251 -0.1523885 0.9866967 -0.04757267 -0.1178311 0.9918935 -0.2389357 0.6353344 0.7343432 -0.1695826 0.257225 0.9513553 -0.1102966 0.01968783 0.9937037 -0.111357 0.02467322 0.9934741 -0.08777654 -0.06413984 0.9940732 -0.1667254 0.1631396 0.9724135 -0.1247785 0.0221278 0.9919378 -0.2774829 0.4951218 0.8233211 -0.2774816 0.495122 0.8233215 -0.08812654 -0.0585671 0.9943861 -0.09018629 -0.05894643 0.994179 -0.09095042 -0.0539658 0.994392 -0.08565276 -0.05265522 0.9949327 -0.08653217 -0.04975789 0.9950056 -0.05878067 -0.09085929 0.9941275 -0.2795722 0.2867572 0.9163022 -0.2792264 0.2867777 0.9164012 -0.1626395 0.100349 0.9815694 -0.1459784 0.05390644 0.987818 -0.169518 0.1625678 0.9720264 -0.07032829 -0.1069768 0.9917711 -0.07670539 -0.1019666 0.9918261 -0.07008045 -0.1007587 0.9924396 -0.07612651 -0.09642457 0.9924248 -0.06193178 -0.09293842 0.9937439 -0.06623685 -0.09029376 0.9937101 -0.05756562 -0.08751821 0.9944983 -0.1031346 -0.09903466 0.9897249 -0.06359505 -0.1356932 0.9887078 -0.0766021 -0.1209802 0.9896949 -0.08999055 -0.125252 0.9880352 -0.1208736 -0.1148703 0.9859991 -0.1247777 -0.1152606 0.9854671 -0.7394407 0.6553872 0.1539322 -0.9325221 0.3610991 0.003149032 -0.419878 0.2733463 0.8654387 -0.1406813 -0.07390111 0.987293 -0.09116071 -0.09984213 0.9908185 -0.0900194 -0.09984761 0.9909223 -0.06549429 -0.115361 0.9911621 -0.05908519 -0.1136444 0.9917631 -0.04976928 -0.1287043 0.9904333 -0.03670603 -0.1249552 0.9914832 -0.932597 0.3609072 0.002979338 -0.4516135 0.03884804 0.8913675 -0.2790694 0.1316778 0.9511999 -0.3371574 0.1857897 0.9229339 -0.02464956 -0.1540851 0.9877501 -0.02953332 -0.1497459 0.9882833 -0.04567003 -0.156297 0.9866536 -0.04423332 -0.170476 0.9843686 -0.05480492 -0.1513373 0.9869617 -0.04970657 -0.1253511 0.9908665 -0.07671332 -0.1346616 0.9879177 -0.08848953 -0.1244347 0.988274 -0.1107546 -0.1323307 0.9849984 -0.1463255 -0.1269894 0.9810518 -0.1361964 -0.1025077 0.9853643 -0.1583684 -0.1080073 0.9814549 -0.08835631 -0.05710101 0.9944509 -0.5425992 -0.1031048 0.8336399 -0.3281848 -0.1397686 0.9342159 -0.3281838 -0.1397686 0.9342163 -0.2539513 -0.1243314 0.9591927 -0.23924 -0.1133288 0.9643241 -0.1822215 -0.1323227 0.9743131 -0.1255686 -0.1281265 0.9837765 0.2648147 -0.03706198 0.9635869 -0.523159 -0.1636855 0.8363682 -0.4148662 -0.1491255 0.8975787 -0.6918861 -0.1796398 0.6993019 -0.3101327 -0.01897138 0.950504 -0.3030279 -0.01703876 0.9528294 -0.2471035 -0.08421361 0.9653226 -0.3447533 -0.0855953 0.9347826 -0.4188017 -0.1128271 0.9010412 -0.05878317 -0.09086132 0.9941271 -0.05886548 -0.09071397 0.9941357 -0.1044309 -0.04659759 0.9934399 -0.5945693 0.6987976 0.397705 -0.0872125 -0.04997688 0.9949353 -0.08740329 -0.04962563 0.9949362 -0.05945777 -0.08660781 0.9944666 -0.0906412 0.1012609 0.9907222 -0.1713864 0.5405095 0.8236967 -0.1714377 0.5408254 0.8234786 -0.07085651 0.01347583 0.9973955 -0.05966198 -0.04477059 0.9972141 -0.05965876 -0.04478657 0.9972136 -0.08884018 0.1010353 0.9909083 -0.04006946 -0.1289637 0.9908395 -0.04006916 -0.1289651 0.9908393 -0.05355572 -0.07328623 0.9958719 -0.05243211 -0.07955378 0.9954508 -0.05878585 -0.04492157 0.9972593 -0.204413 0.765101 0.6106029 -0.2011976 0.7649027 0.6119178 -0.09065812 0.1013452 0.990712 -0.05129283 -0.1045339 0.9931977 -0.05159765 -0.1180338 0.9916681 -0.06497889 -0.06118619 0.996009 -0.06286311 -0.07290273 0.9953559 -0.08570355 0.02298688 0.9960554 -0.08369541 0.01393955 0.9963939 -0.04396826 -0.1489973 0.9878597 -0.0906077 0.04798322 0.9947301 -0.0442143 -0.1078568 0.9931828 -0.0380131 -0.107954 0.9934289 -0.0532518 -0.1128277 0.9921866 -0.04044044 -0.1138112 0.9926789 -0.06434053 -0.1196806 0.9907255 -0.0456236 -0.1220806 0.9914711 -0.06604939 -0.1258106 0.9898532 -0.04547387 -0.129348 0.9905561 -0.04627215 -0.1294508 0.9905057 -0.03137779 -0.1441775 0.9890543 -0.03710579 -0.1439411 0.9888904 -0.0265311 -0.1562845 0.9873557 -0.1769983 -0.9810225 0.07916152 0.01093459 -0.1017396 0.994751 -0.1488288 -0.8353629 0.5291681 -0.148765 -0.8351055 0.5295918 -0.003137111 -0.1667675 0.9859913 -0.1540844 -0.8342965 0.5293462 -0.09931087 -0.6057462 0.7894358 -0.09928756 -0.6056436 0.7895174 -0.132193 -0.7481554 0.6502218 -0.05280411 -0.4045417 0.9129939 -0.0527988 -0.4045173 0.9130049 -0.05279964 -0.4045212 0.9130032 -0.01399803 -0.2141002 0.9767115 -0.03364872 -0.3149492 0.9485118 -0.01003593 -0.2147334 0.9766212 -0.01436287 -0.2327717 0.9724252 -0.01172375 -0.2144624 0.9766619 -0.01172298 -0.2144585 0.9766628 -0.01959496 -0.2325672 0.9723829 -0.01429337 -0.2142593 0.9766723 -0.0358572 -0.3148511 0.9484636 -0.03244781 -0.3006259 0.95319 -0.1562379 -0.8268356 0.540308 -0.1809954 -0.9109159 0.3707733 -0.2196195 -0.8746122 0.4322278 -0.04228639 -0.3018016 0.9524325 -0.0170859 -0.1992164 0.9798065 -0.0230953 -0.2154007 0.9762526 -0.01299124 -0.1696172 0.9854244 -0.007281959 -0.1688596 0.9856132 -0.01711779 -0.1887494 0.9818761 -0.005291879 -0.1891977 0.9819248 -0.01932996 -0.213222 0.9768124 -0.01932984 -0.2132217 0.9768127 -0.01438021 -0.1797337 0.9836102 -0.01438003 -0.179732 0.9836105 -0.9067579 -0.3613628 0.2172718 -0.9067163 -0.3607611 0.2184419 -0.4842826 -0.2077658 0.8498846 -0.6693032 -0.2755315 0.6900113 -0.4187922 -0.1128312 0.9010451 -0.5083028 -0.094343 0.8559952 -0.1549264 -0.1284909 0.9795345 -0.1544604 -0.1282225 0.9796433 -0.1294776 -0.1282901 0.9832483 -0.06419372 -0.08615726 0.9942113 -0.04531031 -0.09662443 0.994289 -3.82634e-4 -0.03776717 0.9992864 -0.6764948 0.1606837 0.718704 -0.2687289 -0.03996944 0.9623862 -0.1796848 0.002518534 0.983721 -0.106886 -0.05830669 0.9925602 -0.1075997 -0.05793493 0.9925048 -0.0694552 -0.0904119 0.9934796 -0.06888681 -0.09046852 0.993514 -0.04982161 -0.1093949 0.992749 -0.04586267 -0.1085314 0.9930346 -0.03830105 -0.12596 0.9912957 -0.03342711 -0.1239679 0.991723 -0.0254302 -0.1238557 0.9919744 -0.03787118 -0.1278389 0.9910716 -0.02094519 -0.1285253 0.9914851 -0.04420971 -0.1342697 0.9899582 -0.01781255 -0.1366198 0.9904634 -0.04401546 -0.1482291 0.9879731 -0.01176351 -0.1440194 0.989505 -0.03012615 -0.1630948 0.9861504 -0.02430152 -0.1633311 0.9862719 -0.02666145 -0.1687039 0.9853062 -0.2346433 -0.9683676 0.08489263 0.02228754 -0.2709804 0.9623268 0.4023828 0.7917145 0.459648 -0.04624664 0.998768 -0.01799768 0.3948704 0.8391501 0.3740381 0.3968726 0.8172762 0.4177939 0.3981623 0.5866999 0.7051596 0.3872245 0.8203001 0.4209097 0.1726195 -0.05424171 0.9834939 0.2055125 -0.0180788 0.9784874 0.1888199 -0.07993054 0.9787533 0.2349032 0.03358948 0.9714383 0.3012495 0.1838464 0.9356545 0.327091 0.3023039 0.8953346 0.3776151 0.4861042 0.788105 0.3870973 0.8210713 0.4195204 0.01836842 -0.2876759 0.9575517 0.04614758 -0.2788863 0.9592147 0.09415423 -0.2307742 0.9684412 0.1030259 -0.1968268 0.9750102 0.0651735 -0.2128631 0.974906 0.1392419 -0.1667978 0.9761097 0.00853908 -0.3163919 0.9485902 -0.05339711 -0.3586331 0.93195 -0.05539089 -0.3367705 0.9399561 -0.1219234 -0.4453293 0.8870267 -0.05772107 -0.3516165 0.934363 -0.05772143 -0.3516182 0.9343623 -0.1645659 -0.3964203 0.9031993 -0.164566 -0.396421 0.903199 -0.2425044 -0.5135534 0.8230763 -0.2586598 -0.4854897 0.8351018 -0.2791729 -0.6362427 0.7192063 -0.29044 -0.7646815 0.5752451 -0.3074849 -0.6521859 0.6928973 -0.2746353 -0.9583615 -0.07822132 -0.2413185 -0.9482821 -0.2062193 -0.24997 -0.8864403 0.3895364 -0.312209 -0.836592 0.4501549 -0.3078426 -0.9172455 0.252772 -0.3023469 -0.9309801 0.2046031 -0.2923585 -0.9482363 0.1239937 -0.5755247 -0.8163027 0.0492075 0.04226988 -0.3562566 0.9334316 0.003012597 -0.3928496 0.9195978 0.1831375 -0.01156103 0.9830194 0.2655642 0.2659372 0.9266893 0.2760993 0.4024687 0.8728048 0.2760991 0.4024668 0.8728057 0.1831408 -0.01154959 0.9830188 0.1831412 -0.01154774 0.9830188 0.18716 -0.07439774 0.9795082 0.07422375 -0.2945444 0.952751 0.07422453 -0.2945414 0.9527518 0.07078921 -0.2473119 0.9663467 0.04181939 -0.2832005 0.9581485 0.04181975 -0.2831985 0.9581491 0.3225733 0.7380552 0.5926391 0.3031763 0.5737106 0.7608814 0.3092495 0.7421519 0.5946218 0.2875883 0.9196571 0.2674395 0.3283761 0.7361571 0.5918123 -0.2080976 -0.3708121 0.9050932 -0.1279013 -0.4051359 0.9052658 -0.1537615 -0.5514878 0.8198895 -0.1963767 -0.597126 0.7777383 -0.2193918 -0.7933318 0.5678837 -0.2325283 -0.8314356 0.5046242 -0.2307745 -0.9424431 0.2419587 -0.2308259 -0.9590147 0.1643478 -0.2383292 -0.8906599 0.3872004 -0.2346437 -0.9683675 0.08489274 -0.09113264 -0.9724768 -0.2144377 -0.1258461 -0.9755563 0.1801461 -0.100288 -0.9919071 0.07786256 -0.06258493 -0.9740573 -0.2174751 -0.06258529 -0.9740579 -0.2174727 -0.1223281 -0.9691158 0.214127 -0.1223285 -0.969115 0.2141304 -0.1223278 -0.9691163 0.214125 -0.1536692 -0.6684045 0.7277509 -0.1320869 -0.8931067 0.4300156 -0.1303572 -0.8813276 0.454168 -0.1291123 -0.9164019 0.3788633 -0.1536691 -0.6684082 0.7277474 -0.1519458 -0.6636207 0.7324753 -0.1501807 -0.6697371 0.7272539 -0.01374661 -0.4232639 0.9059021 -0.02718383 -0.5128698 0.8580359 -0.07549232 -0.4083261 0.9097091 -0.09795439 -0.4868202 0.8679925 -0.09998124 -0.5093804 0.8547136 -0.07967811 -0.4938379 0.8658958 -0.1501807 -0.6697369 0.7272539 0.3240215 0.8189107 0.4737039 0.3138747 0.9122201 0.2633197 0.3367936 0.6094405 0.7177412 0.3299386 0.564882 0.7563391 0.2958592 0.3137001 0.9022526 0.2773327 0.2618451 0.9244045 0.2155348 -0.021573 0.9762579 0.1724519 -0.06931465 0.9825761 0.1375935 -0.2087073 0.9682506 0.08150678 -0.2510657 0.9645323 0.06860131 -0.3054221 0.9497427 0.01121306 -0.3452127 0.9384576 0.004072308 -0.3799098 0.9250146 -0.05076789 -0.4178694 0.9070875 -0.05944895 -0.4697579 0.8807914 -0.1083256 -0.5060824 0.8556554 -0.1230859 -0.626796 0.7694003 -0.1562032 -0.6619536 0.733088 -0.1669574 -0.8539761 0.4927982 -0.1757314 -0.8808857 0.4394983 -0.1653528 -0.9744865 0.1517719 -0.1645282 -0.9821919 0.09071648 -0.1215379 -0.9414206 -0.3145726 -0.1409984 -0.9733625 0.1807896 0.07874059 -0.3276051 -0.941528 0.2856066 0.9465875 0.1496697 0.01786464 -0.4445468 -0.8955775 -0.1367542 -0.8418449 -0.5221068 0.0160818 0.5052632 -0.8628154 0.03234273 0.3001691 -0.9533375 0.0193811 0.2479385 -0.9685819 0.02690893 0.2709828 -0.962208 0.04334229 0.2404332 -0.9696975 0.05491602 0.1718697 -0.9835879 0.006251931 0.3698824 -0.9290575 0.01589637 0.4854716 -0.8741079 -0.01799386 0.4556388 -0.8899828 -0.01950246 0.4541314 -0.8907212 -0.01585137 0.4529539 -0.891393 0.01608514 0.5052697 -0.8628116 0.07113164 0.6725647 -0.7366119 0.07113188 0.672565 -0.7366116 0.1944705 0.8575992 -0.4761354 0.4052519 0.6621205 0.6303707 0.3652123 0.9292404 0.05596578 0.1944579 0.8575868 -0.4761629 0.2792594 0.9273805 -0.2489572 0.283864 0.929166 -0.2367949 0.3194803 0.9387664 -0.1290353 0.0853812 0.9935553 -0.07455146 -0.223194 -0.9324345 -0.2841663 -0.1288797 -0.7720565 -0.6223495 -0.2012957 -0.9120947 -0.3571602 -0.08854109 -0.72918 -0.6785699 -0.1103187 -0.7647533 -0.6348088 0.007079064 -0.4736481 -0.8806858 0.0103414 -0.449647 -0.8931465 -0.1103171 -0.76475 -0.6348131 -0.09901672 0.07377815 -0.992347 0.1170119 -0.009514451 -0.9930849 0.07265967 -0.1550866 -0.9852253 -0.03746837 -0.05823987 -0.9975993 0.05986702 -0.1951942 -0.9789358 0.08794808 -0.4108561 -0.9074482 0.05158358 -0.6432987 -0.7638756 0.01602047 -0.7671651 -0.6412495 0.08794671 -0.4108642 -0.9074448 0.08794903 -0.4108559 -0.9074483 0.1009185 -0.3666407 -0.9248731 0.1031739 0.04645264 -0.993578 0.1093342 -0.02852421 -0.9935957 0.1372012 0.03380197 -0.9899663 0.1372004 0.0337944 -0.9899666 0.1008455 0.2744089 -0.9563106 0.1263349 0.1730527 -0.9767764 0.1636059 0.2484509 -0.9547278 0.1031736 0.04645127 -0.9935781 0.01601928 -0.7671696 -0.6412444 0.1004869 -0.3275386 -0.9394791 -0.01201301 -0.7655658 -0.6432456 -0.1367557 -0.8418446 -0.5221069 -0.1259478 -0.8034912 -0.5818411 -0.09832161 -0.7275883 -0.6789316 -0.08378517 -0.6717994 -0.7359794 -0.02040964 -0.4675775 -0.8837165 -0.01135182 -0.3968382 -0.9178184 0.05632418 -0.1498742 -0.9870994 0.04198276 -0.06629347 -0.9969165 0.06434637 0.01543581 -0.9978082 0.06374365 0.1364238 -0.9885976 0.02318716 0.08567833 -0.9960529 0.05491501 0.1718663 -0.9835885 0.244255 0.9385169 -0.2439782 0.2622788 0.9498681 -0.1701777 0.3809767 0.6729243 0.6340579 0.3578975 0.9236371 0.1371271 0.1006767 0.8088411 -0.5793448 0.1492156 0.8166383 -0.5575273 0.138635 0.8197365 -0.5557087 0.154978 0.8576124 -0.4903905 0.1386211 0.8623394 -0.4869856 0.1088385 0.8064998 -0.5811302 0.200816 0.9454033 -0.2566813 0.2008146 0.9454022 -0.2566865 0.2266464 0.9601463 -0.1635553 0.2893046 0.9421848 0.1690882 0.2878227 0.9442448 0.1598746 0.2888262 0.9423187 0.1691591 0.2888276 0.9423162 0.1691704 0.05531114 0.5289995 -0.8468177 0.05531203 0.5290011 -0.8468167 0.0243954 0.4824898 -0.8755619 0.05485242 0.6515477 -0.7566218 0.05485248 0.651548 -0.7566217 0.002639353 0.6032607 -0.7975397 0.04346865 0.590826 -0.8056271 0.03628635 0.6564965 -0.7534559 0.0543527 0.6507921 -0.7573081 0.100679 0.8088451 -0.5793388 -0.1212467 -0.8041528 -0.5819256 -0.1154127 -0.912232 -0.393081 -0.04468762 -0.6772935 -0.7343545 -0.03709548 -0.6337816 -0.7726221 0.01548355 -0.4028677 -0.9151272 0.01832711 -0.3483104 -0.9372001 0.07258248 -0.07647556 -0.9944261 0.05634021 -0.01005893 -0.9983609 0.08450716 0.1285476 -0.9880962 0.05671268 0.2004122 -0.9780688 0.06942164 0.254707 -0.9645231 0.03978228 0.3262561 -0.944444 0.006251394 0.3698809 -0.9290581 0.009890198 0.374873 -0.9270234 0.007842123 0.3756172 -0.9267418 0.0762127 0.4549421 -0.8872539 0.148909 0.492949 -0.8572208 0.1489055 0.4929462 -0.8572229 0.1008454 0.2744082 -0.9563108 0.1291328 0.3431233 -0.9303715 0.09422338 0.3048869 -0.9477162 0.0846945 0.397 -0.9139026 0.09337866 0.436957 -0.8946223 -0.005608022 0.2170885 -0.9761359 -0.0352385 0.2910729 -0.9560517 -0.07192844 0.341515 -0.93712 -0.139787 0.3640248 -0.9208396 -0.0842719 0.3402633 -0.9365464 -0.08425825 0.3402609 -0.9365485 -0.07192742 0.3380539 -0.9383741 -0.08479332 0.3283255 -0.9407511 -0.1395131 0.3582792 -0.9231317 -0.1175477 0.3584491 -0.9261192 -0.1175454 0.3584488 -0.9261197 -0.1761177 0.47693 -0.8611157 -0.1408442 0.5215945 -0.8414881 -0.1802558 0.5276638 -0.8301077 -0.1413041 0.5345714 -0.8332266 -0.1255815 0.5272102 -0.8404039 0.006874024 0.5110375 -0.8595309 0.03416216 0.5352566 -0.8439984 0.07581007 0.4782263 -0.8749586 0.1447023 0.4802881 -0.8650923 0.07972282 0.5212556 -0.8496686 0.03410619 0.5054808 -0.8621634 0.07702887 0.4916406 -0.8673847 0.006872773 0.5110374 -0.8595311 -0.1409412 0.5242657 -0.8398101 -0.07911115 0.5141463 -0.8540463 -0.1252197 0.5230854 -0.8430312 -0.07918727 0.5667891 -0.8200484 0.03415811 0.5793377 -0.8143715 -0.07918745 0.5662698 -0.8204071 -0.07918632 0.5662695 -0.8204075 -0.1168757 0.3957682 -0.9108829 -0.1343473 0.3968088 -0.9080162 -0.1413096 0.3979105 -0.9064761 -0.1343982 0.3995653 -0.9067992 -0.1741375 0.4545016 -0.8735586 -0.13515 0.4483531 -0.8835802 -0.1351525 0.4483545 -0.8835791 0.001225054 0.1791168 -0.9838271 0.001225113 0.1791169 -0.983827 0.001098394 0.1784333 -0.9839514 0.005795478 0.1900224 -0.9817626 0.005795478 0.1900224 -0.9817627 -0.01285195 0.2183488 -0.9757862 -0.005635678 0.227256 -0.9738187 -0.0177896 0.2342392 -0.9720162 0.005795598 0.1900225 -0.9817627 -0.006420195 0.1912116 -0.9815279 -0.01292568 0.1971589 -0.9802864 -0.006564915 0.1968427 -0.9804132 -0.01292341 0.1978754 -0.9801419 -0.00703144 0.2151632 -0.9765529 -0.005607485 0.2170885 -0.9761359 0.1093035 0.3871706 -0.9155064 0.1093025 0.3871703 -0.9155064 0.09669965 0.3563706 -0.9293272 0.1401739 0.4145078 -0.8991855 0.1184245 0.4514372 -0.8844094 0.07580965 0.4782264 -0.8749585 -0.00466746 0.2465014 -0.9691312 -0.004668116 0.2465015 -0.9691312 -0.01765495 0.2489822 -0.9683471 -0.01765483 0.2489824 -0.9683471 -0.004234373 0.2830986 -0.9590814 -0.07182759 0.2929454 -0.9534274 -0.03523868 0.291073 -0.9560517 -0.0352391 0.291073 -0.9560517 0.002695798 -0.3927369 0.9196469 7.48674e-4 -0.1731835 0.9848892 0.02535074 -0.412132 0.9107714 0.0984947 -0.5089557 0.8551392 0.06500548 -0.5151686 0.8546202 0.0650053 -0.5151684 0.8546203 0.1087735 -0.5602052 0.8211812 0.1087728 -0.5602051 0.8211813 0.07108259 -0.5687159 0.8194568 0.01208466 -0.5241594 0.8515344 -0.008262455 -0.519588 0.8543771 -0.008263468 -0.5195877 0.8543772 0.01433205 -0.3054841 0.9520894 0.01879262 -0.306604 0.9516516 0.01435059 -0.3057376 0.9520077 0.01935321 -0.3096237 0.9506622 1.6413e-4 -0.3260747 0.945344 0.02326309 -0.3306013 0.9434838 0.001164138 -0.3318899 0.9433174 0.03760242 -0.377654 0.9251829 0.01867061 -0.373125 0.9275932 0.04684025 -0.4146044 0.9087954 0.04684048 -0.4146045 0.9087954 -0.001461565 -0.1748828 0.9845882 -0.001461684 -0.1748828 0.9845882 0.00181657 -0.1699766 0.9854464 0.02067238 -0.2480939 0.9685154 0.01395982 -0.2458826 0.9691991 0.006443142 -0.2376682 0.9713249 0.01412063 -0.239138 0.9708828 6.33437e-4 -0.1786354 0.9839151 6.33432e-4 -0.1786354 0.9839151 -0.001433134 -0.178498 0.9839392 0.01492756 -0.2046604 0.9787192 0.006763577 -0.2151775 0.9765515 0.006763458 -0.2151775 0.9765516 -0.03223252 -0.4165588 0.9085371 -0.02203601 -0.4476956 0.8939145 -0.0455513 -0.4527793 0.8904583 -0.004832267 -0.4667938 0.8843529 -0.04509603 -0.4806196 0.875769 -0.008274137 -0.517782 0.8554726 -0.04463332 -0.5060673 0.8613383 -0.008043527 -0.5515838 0.8340807 0.01527184 -0.5506002 0.8346294 0.01527267 -0.5506005 0.8346292 0.03425192 -0.2598625 0.965038 0.03425192 -0.2598625 0.965038 0.02052307 -0.2729384 0.9618126 0.03456759 -0.2794331 0.9595426 0.02050143 -0.2764809 0.9608008 0.03469204 -0.2811828 0.9590269 0.03469198 -0.2811828 0.959027 -0.02387374 -0.1192649 0.9925754 0.09185749 0.7052872 0.7029453 0.1062905 0.978712 -0.1755708 0.06053096 0.6852094 -0.7258265 0.07586485 0.8702626 0.4867107 -0.01950931 0.08657485 0.9960544 -0.02737087 0.2882159 0.9571742 -0.134272 0.539358 0.8313025 -0.1344046 0.5403824 0.8306156 -0.1343665 0.5400892 0.8308125 -0.0170077 0.4177317 -0.9084112 -0.01699697 0.4176511 -0.9084485 -0.0628826 0.09715533 0.9932808 -0.1193787 0.5395928 0.8334196 -0.1193426 0.5392713 0.833633 -0.06287151 0.09707731 0.9932891 -0.03443634 -0.1180155 0.9924145 -0.1335168 0.5403941 0.8307511 0.009028136 -0.3607054 0.9326361 -0.08581638 0.9648659 0.2483333 -0.07144469 0.4784053 0.875228 -0.03400534 0.04937052 0.9982014 -0.05637001 0.0528261 0.9970115 -0.1159839 0.5392651 0.8341109 -0.1472992 0.9826552 0.1126573 -0.1311284 0.9842537 0.1185331 -0.02388328 -0.01452082 0.9996093 0.02632427 0.5195752 0.8540191 -0.001903355 0.5233865 0.8520932 -0.009428858 0.365063 0.930935 -0.01411408 0.2190625 0.9756088 0.02556884 0.9353253 0.3528637 -0.01662516 0.9394962 0.3421557 -0.0246675 0.06081676 0.997844 -0.02296757 -0.01127219 0.9996726 -0.0207355 0.05784624 0.9981101 -0.0260089 0.05885654 0.9979276 -0.02601712 0.05932033 0.9978999 -0.02400892 0.05897182 0.9979709 -0.01783037 0.9983435 -0.05470162 -0.01782929 0.9983436 -0.05470144 -0.0406531 0.4990321 0.8656294 0.005301117 0.2752352 0.9613623 0.009916007 0.274656 0.9614915 0.03612387 0.5866374 0.8090437 0.06569212 0.8703773 0.4879835 0.05074071 0.7147567 0.6975301 0.04844832 0.7148203 0.697628 0.02903985 0.4971371 0.8671859 0.03170162 0.4969149 0.8672201 0.1660206 0.98592 -0.01997059 0.1304981 0.988114 0.08124667 0.1341943 0.9843116 0.1145535 0.1024757 0.9868927 0.1246656 0.08725613 0.9782159 0.1883615 0.08403754 0.943566 0.320345 0.07628315 0.9437932 0.3216133 0.06558179 0.8392474 0.5397803 0.0633369 0.8392979 0.5399699 0.04508501 0.6452357 0.7626523 0.04547572 0.645213 0.7626482 0.02619695 0.4193056 0.9074671 0.03044664 0.5700584 0.8210398 0.01323217 0.3612942 0.932358 0.01471924 0.3803675 0.9247183 0.001644253 0.2160616 0.9763784 0.003846347 0.2452993 0.9694398 -0.008657157 0.08432495 0.9964007 -0.004137516 0.1501942 0.9886479 -0.01585686 -0.01280933 0.9997922 -0.0147857 0.005216479 0.999877 0.07848465 0.9314879 0.3552049 0.08498883 0.9884485 0.1254856 0.07545536 0.9066709 0.4150356 0.06256359 0.7780014 0.6251395 0.07004374 0.8675205 0.4924452 0.05983877 0.6840974 -0.7269319 0.08548343 0.984574 0.1526643 0.08831036 0.9958845 0.02038264 0.08803194 0.9959083 0.02042239 0.08759105 0.9490371 -0.3027477 0.08092314 0.8741114 -0.4789372 0.09046351 0.9921889 -0.08589315 0.09034186 0.9957182 -0.01958352 0.0871104 0.9659772 -0.2435153 0.08834987 0.9778079 -0.1899627 0.08835136 0.9778065 -0.1899697 0.08866477 0.9793273 -0.1818145 0.08950495 0.9802945 -0.1761006 0.1021477 0.9907861 -0.0889312 0.08911496 0.9715641 -0.2193668 0.08809673 0.9717163 -0.2191036 0.08955544 0.9821128 -0.1656331 0.1622518 0.982924 -0.08680325 0.1802068 0.9812863 0.06784307 0.1484231 0.977639 -0.1489713 0.162245 0.9829232 -0.08682554 0.1062927 0.9787116 -0.1755714 0.1062912 0.9787124 -0.1755683 0.1100116 0.9858976 -0.1261098 0.1169812 0.9891226 -0.08917325 0.08835369 0.9778074 -0.1899638 0.08781027 0.9928616 0.08071613 0.08846038 0.9908553 -0.1018846 0.08982414 0.9907108 -0.1020961 0.08982235 0.9910278 -0.09897387 0.08922481 0.9821548 -0.165562 0.08658993 0.988343 0.1252209 0.08798199 0.9959391 -0.01908832 0.08711093 0.9659772 -0.2435154 0.08711093 0.9659771 -0.2435155 0.08108323 0.904614 -0.4184485 0.08807903 0.9563502 -0.2786328 0.08814507 0.9462726 -0.3111248 0.06983536 0.7214888 -0.6888955 0.06983608 0.7214895 -0.6888946 -0.01680153 0.1250013 0.9920144 -0.01576077 0.1248216 0.992054 -0.01001948 0.1965156 0.9804494 0.08859235 0.6514023 0.7535427 0.05564343 0.6516222 0.7565 4.96745e-4 0.1408681 0.9900283 0.01332837 0.3410785 0.9399403 0.005747973 0.3416645 0.9398045 -0.03356218 -0.5090391 0.8600888 -0.03356242 -0.5090391 0.8600888 -0.01431101 0.1601017 0.9869968 -0.01431065 0.1601017 0.9869968 0.02105647 0.3831661 0.9234395 0.02581566 0.4980008 0.8667922 0.07513082 0.4966621 0.8646861 0.0928232 0.7763859 0.623385 0.1053685 0.05058622 0.9931458 0.1199978 0.1804966 0.9762281 0.2420002 0.9541187 0.1763333 0.1958953 0.946371 0.2569182 0.2177157 0.2911511 0.9315745 0.2177153 0.2911509 0.9315745 0.1053693 0.05058622 0.9931457 0.1217241 0.1804116 0.9760301 0.1524131 0.7058048 0.6918162 0.1528666 0.8235511 0.546256 0.1003954 0.8234336 0.5584602 0.0996589 0.8055722 0.584056 0.06909316 0.8055438 0.5884941 0.06182384 0.6829513 0.7278429 0.04479682 0.6830175 0.7290269 0.03248947 0.5121191 0.8582998 0.02124059 0.5125628 0.858387 -0.04328197 -0.08108031 0.9957674 -0.06215953 0.09701126 0.9933403 -0.04168134 -0.04775118 0.9979892 -0.04535931 -0.0229066 0.998708 -0.04788118 -0.04671889 0.9977598 -0.04788142 -0.0467236 0.9977596 -0.0238738 -0.1192649 0.9925754 -0.02449262 -0.05108743 0.9983938 -0.034159 0.05076813 0.9981262 -0.02345144 0.04907107 0.99852 -0.05285435 0.9645439 0.2585757 -0.0361486 0.2894802 0.9565012 -0.01800209 -0.0848006 0.9962354 -0.03671407 0.3138427 0.9487649 -0.01417106 -0.1297872 0.9914407 0.1857348 0.9633054 -0.1937656 0.1732949 0.9522645 -0.2513189 0.2425428 0.9539967 0.1762477 0.1660106 0.9539409 -0.2498747 0.2158095 0.975992 -0.02942973 0.1775377 0.9581883 -0.2244004 0.1857425 0.9633095 -0.1937379 0.1410381 0.9665182 -0.2143611 0.1409621 0.9665235 -0.2143877 0.1409713 0.9665216 -0.2143897 0.05089151 0.6851621 0.7266106 0.04284721 0.5853123 0.8096749 0.0417872 0.5854021 0.8096655 0.0596947 0.7781662 0.625215 0.05115741 0.6731827 0.7377045 0.07365465 0.9067636 0.4151565 0.07982212 0.9705751 0.2271836 0.06780606 0.8551499 0.5139269 0.05553257 0.8558988 0.514153 0.06407773 0.9407021 0.3331269 0.04178828 0.9460402 0.3213437 0.07117354 0.8864262 -0.4573654 0.07284986 0.8860713 -0.4577886 -0.01871907 0.07881993 0.9967131 0.03392231 0.5867372 0.8090666 0.01583898 0.3736977 0.9274153 0.01880943 0.3733812 0.9274873 0.01130068 0.2861839 0.9581081 9.82173e-4 0.1492924 0.9887926 0.02380198 0.4195753 0.9074084 0.01001757 0.2442998 0.969648 0.02521818 0.4217166 0.906377 0.02207547 0.3793385 0.9249946 0.04790031 0.6734439 0.7376849 0.03970801 0.5690779 0.8213243 0.05537337 0.7426287 0.6674101 0.04542315 0.7433859 0.6673185 0.06626933 0.9580338 0.2788903 0.02781105 0.965732 0.2580471 -0.02221173 0.03816783 0.9990244 -0.02621656 -0.09362596 0.9952622 0.2419984 0.9541217 0.1763198 0.2452824 0.9485411 0.2002659 0.1911798 0.9590126 0.2091537 0.2057998 0.9188682 0.3366417 0.1488203 0.9248104 0.3501118 0.1503599 0.914448 0.3757352 0.1048182 0.9155163 0.3883852 0.1047247 0.900737 0.4215514 0.0805149 0.9010528 0.4261705 0.08444648 0.9733676 0.2131296 0.04711288 0.6672524 0.7433402 0.0402553 0.6673465 0.7436587 0.008040785 0.3258205 0.9453975 0.004519999 0.3261611 0.9453034 -0.01723045 0.06454217 0.9977662 -0.01343166 0.06391274 0.9978652 -0.02888077 -0.1593595 0.9867981 -0.02627944 -0.1435606 0.9892926 -0.01683694 -0.07492351 0.9970471 -0.0168367 -0.07492357 0.9970472 -0.0167188 -0.08990502 0.99581 -0.02370578 -0.05202317 0.9983645 -0.02489608 -0.05183255 0.9983454 -0.02326798 -0.08288341 0.9962877 -0.02326816 -0.08288335 0.9962876 -0.0239166 -0.08353948 0.9962174 -0.02846252 -0.1431372 0.9892935 -0.02574497 -0.08858293 0.995736 -0.02310049 -0.08916771 0.9957488 -0.002741396 0.1642252 0.9864191 -0.005903542 0.1646898 0.9863277 0.02104961 0.469976 0.8824282 0.02308267 0.4698414 0.882449 0.05320936 0.7739147 0.6310507 0.06533014 0.7738242 0.6300223 0.08314371 0.9475905 0.3084791 0.1092064 0.9467705 0.3028196 0.1056457 0.9772326 0.183999 0.1013686 0.9924354 0.06925719 0.08959412 0.9933568 0.07221615 0.08890873 0.9852597 0.1461456 0.0838223 0.9855594 0.147128 0.07827872 0.9367893 0.3410252 0.07626783 0.93686 0.3412867 0.06275224 0.802546 0.593281 0.06426376 0.8024821 0.5932053 0.07785946 0.9315169 0.3552662 0.07239097 0.8674131 0.4922947 0.08564287 0.9845636 0.1526428 0.08601588 0.9878442 0.1294803 0.08303689 0.9646418 0.2501422 0.0796402 0.9648451 0.2504624 0.08332061 0.9932054 0.08124601 0.0617206 0.6839234 -0.7269383 0.08146995 0.956847 -0.2789383 0.06053102 0.6852095 -0.7258264 0.09904897 -0.3030141 0.9478248 -0.0204007 -0.1572981 0.9873404 0.0976783 -0.3025502 0.9481151 -0.03894066 -0.2586854 0.9651765 -0.02195364 -0.1350096 0.990601 -0.02285754 -0.131827 0.9910091 -0.03501844 -0.1298096 0.9909204 -0.0228576 -0.1318274 0.9910091 -0.0246846 -0.1345448 0.9906 -0.01711636 -0.1743192 0.9845405 -0.01947683 -0.1704497 0.985174 -0.01251572 -0.196323 0.9804594 -0.02156794 -0.1945298 0.9806595 -0.01153647 -0.2363085 0.9716096 -0.02926272 -0.2323746 0.972186 -0.007793605 -0.1480142 0.9889545 -0.01724898 -0.1708546 0.9851453 -0.01331353 -0.1362515 0.9905849 -0.02226507 -0.148053 0.9887288 -0.03776407 -0.1905287 0.9809549 -0.03776389 -0.1905288 0.980955 -0.03363609 -0.1606218 0.9864427 -0.02785032 -0.1845808 0.9824227 -0.02785015 -0.1845808 0.9824226 0.2074458 0.9751547 0.07771438 0.1832411 0.3435264 0.9210931 0.1955626 0.4783767 0.8561022 0.2452108 0.4127228 0.8772295 0.1732575 -0.008114695 0.9848431 0.2023122 0.1774095 0.9631177 0.1481473 0.1930705 0.9699361 0.1383752 0.02261567 0.9901216 0.0790072 0.03426295 0.996285 0.07766407 -0.07088583 0.9944564 0.009722888 -0.06082254 0.9981012 0.01238471 -0.1323769 0.991122 -0.04214632 -0.1223493 0.9915919 -0.03748726 -0.1760731 0.983663 -0.05503588 -0.1725095 0.9834692 0.1518236 0.9179642 0.3664579 0.1518236 0.9179642 0.3664578 0.1380366 0.5823917 0.8011028 0.1527015 0.5815364 0.7990605 0.04217582 0.1843714 0.9819512 0.05604946 0.5648464 0.8232903 0.05604952 0.5648464 0.8232904 0.172743 0.2929068 0.940407 0.119017 0.3008821 0.9462056 0.09960007 0.1421527 0.984821 0.03927159 0.1476224 0.9882637 0.02354842 0.01263403 0.9996429 -0.01809716 0.01873666 0.9996607 -0.03027319 -0.04279786 0.998625 -0.05593013 -0.2550168 0.9653177 -0.0525546 -0.262616 0.9634681 -0.04570955 -0.2641155 0.9634073 -0.04489976 -0.2662599 0.962855 -0.002505779 -0.2753897 0.9613294 -0.003716528 -0.2712014 0.9625155 0.04830461 -0.2816751 0.9582931 0.04260259 -0.2519791 0.9667945 0.08514124 -0.2622442 0.9612382 0.07550227 -0.1458216 0.9864256 0.1053501 -0.1551097 0.9822638 0.1396098 -0.09908074 0.985237 0.17326 -0.008101344 0.9848428 0.1732596 -0.008103191 0.9848428 -0.0200113 -0.3045614 0.9522824 -2.9186e-4 -0.3234184 0.9462561 -0.03052383 -0.3168457 0.9479858 0.008173763 -0.372305 0.9280744 -0.02022957 -0.3673406 0.9298665 0.03028804 -0.4406465 0.8971695 0.01660746 -0.4378913 0.8988747 0.0350486 -0.4678794 0.8830972 -0.008383631 -0.5009917 0.8654115 0.01597106 -0.4819547 0.8760505 0.06123059 -0.4820227 0.8740165 0.0612303 -0.4820227 0.8740165 0.04267603 -0.496513 0.8669795 0.06589829 -0.5230237 0.8497668 -0.008382439 -0.500992 0.8654113 0.01426875 -0.2732999 0.9618231 0.02350926 -0.408249 0.9125679 0.001866996 -0.4010277 0.9160641 0.02827787 -0.4301726 0.9023036 -0.008721172 -0.4434828 0.8962404 -0.008722126 -0.4434826 0.8962405 -0.001460909 -0.1749774 0.9845714 -0.008349955 -0.1738669 0.9847337 -0.01009041 -0.1467636 0.9891201 -0.01267683 -0.1471909 0.9890269 0.2539289 0.7576063 0.6012925 0.2174368 0.9730727 0.07648968 0.2678766 0.7539691 0.5998106 0.2513129 0.4638515 0.8495197 0.2588919 0.7563686 0.6007341 0.2452108 0.4127215 0.8772301 -0.02226543 -0.1480529 0.9887288 -0.019535 -0.1641003 0.9862503 -0.02201044 -0.1636033 0.9862806 -0.0206834 -0.1642329 0.9862047 -0.03056025 -0.2101475 0.977192 -0.02849799 -0.2106103 0.9771546 -0.0374971 -0.245911 0.9685668 0.09767866 -0.302548 0.9481158 0.09795206 -0.3053556 0.9471871 0.04512435 -0.2876847 0.9566615 0.07121473 -0.3594239 0.930453 0.02410441 -0.3446835 0.9384095 0.04246389 -0.4236666 0.9048224 0.04085624 -0.4232559 0.9050885 0.03475463 -0.4070088 0.9127628 0.01380687 -0.4023956 0.9153618 -0.003303885 -0.3662435 0.9305133 -0.02085065 -0.3623086 0.931825 -0.04218012 -0.324386 0.9449838 -0.02918004 -0.3272764 0.944478 -0.0507974 -0.2923945 0.9549476 -0.02052158 -0.2989177 0.9540583 -0.03849554 -0.2706589 0.9619054 -0.0019809 -0.2784197 0.9604575 -0.00142008 -0.1801435 0.9836393 -0.00142014 -0.1801435 0.9836394 -0.006789624 -0.1832467 0.9830435 0.00703603 -0.1957626 0.9806261 -0.01252645 -0.1922801 0.9812602 0.006649971 -0.2231851 0.9747534 0.00665009 -0.2231851 0.9747534 0.02053505 -0.2710319 0.9623513 0.02053594 -0.2710322 0.9623512 -0.002233624 -0.2688096 0.9631908 0.01325631 -0.2906564 0.9567357 0.01325637 -0.2906564 0.9567357 0.02082479 -0.2198225 0.9753176 -0.003697276 -0.2319648 0.9727172 -0.01190912 -0.2524425 0.9675386 -0.01909661 -0.2508603 0.967835 -0.01910674 -0.2531958 0.9672264 -0.04416835 -0.2477969 0.9678047 -0.04342156 -0.2058852 0.9776123 -0.05102735 -0.2042871 0.9775803 -0.04439169 -0.04846471 0.997838 -0.02882444 -0.05121475 0.9982716 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 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 5 2 4 2 6 2 5 3 6 3 2 3 2 4 6 4 7 4 2 5 7 5 0 5 8 6 9 6 3 6 3 7 9 7 10 7 3 8 10 8 4 8 11 9 12 9 13 9 14 10 15 10 16 10 17 11 18 11 16 11 16 12 18 12 19 12 16 13 19 13 14 13 20 14 21 14 17 14 17 15 21 15 22 15 17 16 22 16 18 16 13 17 23 17 11 17 11 18 23 18 24 18 11 19 24 19 8 19 8 20 24 20 25 20 8 21 25 21 9 21 26 22 27 22 28 22 28 23 27 23 29 23 28 24 29 24 12 24 12 25 29 25 30 25 12 26 30 26 13 26 14 27 31 27 15 27 15 28 31 28 32 28 15 29 32 29 26 29 26 30 32 30 33 30 26 31 33 31 27 31 34 32 35 32 36 32 36 33 35 33 37 33 36 34 37 34 38 34 39 35 40 35 34 35 34 36 40 36 41 36 34 37 41 37 35 37 37 38 42 38 38 38 38 39 42 39 43 39 38 40 43 40 20 40 20 41 43 41 44 41 20 42 44 42 21 42 45 43 46 43 39 43 39 44 46 44 47 44 39 45 47 45 40 45 48 46 49 46 45 46 45 47 49 47 50 47 45 48 50 48 46 48 0 49 51 49 1 49 1 50 51 50 52 50 1 51 52 51 53 51 53 52 52 52 54 52 53 53 54 53 48 53 48 54 54 54 55 54 48 55 55 55 49 55 56 56 57 56 1 56 1 57 57 57 2 57 57 58 58 58 2 58 2 59 58 59 59 59 2 60 59 60 5 60 5 61 59 61 60 61 5 62 60 62 3 62 3 63 60 63 61 63 3 64 61 64 8 64 8 65 61 65 62 65 8 66 62 66 11 66 11 67 62 67 63 67 11 68 63 68 12 68 12 69 63 69 64 69 12 70 64 70 28 70 28 71 64 71 65 71 28 72 65 72 26 72 26 73 65 73 66 73 26 74 66 74 15 74 15 75 66 75 67 75 15 76 67 76 16 76 16 77 67 77 68 77 16 78 68 78 17 78 17 79 68 79 69 79 17 80 69 80 20 80 20 81 69 81 70 81 20 82 70 82 38 82 38 83 70 83 71 83 38 84 71 84 36 84 36 85 71 85 72 85 36 86 72 86 34 86 34 87 72 87 73 87 34 88 73 88 39 88 39 89 73 89 74 89 39 90 74 90 45 90 45 91 74 91 75 91 45 92 75 92 48 92 48 93 75 93 56 93 48 94 56 94 53 94 53 95 56 95 1 95 76 96 77 96 51 96 51 97 77 97 52 97 77 98 78 98 52 98 52 99 78 99 79 99 52 100 79 100 54 100 54 101 79 101 80 101 54 102 80 102 55 102 55 103 80 103 81 103 55 104 81 104 49 104 49 105 81 105 82 105 49 106 82 106 50 106 50 107 82 107 83 107 50 108 83 108 46 108 46 109 83 109 84 109 46 110 84 110 47 110 47 111 84 111 85 111 47 112 85 112 40 112 40 113 85 113 86 113 40 114 86 114 41 114 41 115 86 115 87 115 41 116 87 116 35 116 35 117 87 117 88 117 35 118 88 118 37 118 37 119 88 119 89 119 37 120 89 120 42 120 42 121 89 121 90 121 42 122 90 122 43 122 43 123 90 123 91 123 43 124 91 124 44 124 44 125 91 125 92 125 44 126 92 126 21 126 21 127 92 127 93 127 21 128 93 128 22 128 22 129 93 129 94 129 22 130 94 130 18 130 18 131 94 131 95 131 18 132 95 132 19 132 19 133 95 133 96 133 19 134 96 134 14 134 14 135 96 135 97 135 14 136 97 136 31 136 31 137 97 137 98 137 31 138 98 138 32 138 32 139 98 139 99 139 32 140 99 140 33 140 33 141 99 141 100 141 33 142 100 142 27 142 27 143 100 143 101 143 27 144 101 144 29 144 29 145 101 145 102 145 29 146 102 146 30 146 30 147 102 147 103 147 30 148 103 148 13 148 13 149 103 149 104 149 13 150 104 150 23 150 23 151 104 151 105 151 23 152 105 152 24 152 24 153 105 153 106 153 24 154 106 154 25 154 25 155 106 155 107 155 25 156 107 156 9 156 9 157 107 157 108 157 9 158 108 158 10 158 10 159 108 159 109 159 10 160 109 160 4 160 4 161 109 161 110 161 4 162 110 162 6 162 6 163 110 163 111 163 6 164 111 164 7 164 7 165 111 165 76 165 7 166 76 166 0 166 0 167 76 167 51 167 112 168 113 168 114 168 114 169 113 169 115 169 114 170 115 170 116 170 116 171 115 171 117 171 116 172 117 172 118 172 118 173 117 173 119 173 118 174 119 174 120 174 120 175 119 175 121 175 66 176 119 176 67 176 67 177 119 177 117 177 67 178 117 178 68 178 68 179 117 179 69 179 66 180 65 180 119 180 119 181 65 181 64 181 119 182 64 182 121 182 121 183 64 183 63 183 63 184 62 184 121 184 121 185 62 185 61 185 121 186 61 186 122 186 122 187 61 187 60 187 60 188 59 188 122 188 122 189 59 189 58 189 122 190 58 190 113 190 113 191 58 191 57 191 113 192 57 192 56 192 73 193 115 193 74 193 74 194 115 194 113 194 74 195 113 195 75 195 75 196 113 196 56 196 73 197 72 197 115 197 115 198 72 198 71 198 115 199 71 199 117 199 117 200 71 200 70 200 117 201 70 201 69 201 123 202 122 202 112 202 112 203 122 203 113 203 124 204 125 204 126 204 126 205 125 205 123 205 126 206 123 206 112 206 126 207 127 207 124 207 124 208 127 208 128 208 124 209 128 209 129 209 129 210 128 210 130 210 130 211 131 211 129 211 129 212 131 212 132 212 129 213 132 213 133 213 134 214 127 214 114 214 114 215 127 215 126 215 114 216 126 216 112 216 134 217 135 217 127 217 127 218 135 218 136 218 127 219 136 219 128 219 128 220 136 220 137 220 128 221 137 221 130 221 130 222 137 222 138 222 130 223 138 223 131 223 131 224 138 224 139 224 131 225 139 225 132 225 114 226 116 226 140 226 141 227 135 227 140 227 140 228 135 228 134 228 140 229 134 229 114 229 138 230 137 230 141 230 141 231 137 231 136 231 141 232 136 232 135 232 141 233 142 233 138 233 138 234 142 234 143 234 138 235 143 235 139 235 116 236 118 236 144 236 116 237 144 237 140 237 140 238 144 238 145 238 140 239 145 239 141 239 141 240 145 240 146 240 141 241 146 241 142 241 142 242 146 242 147 242 142 243 147 243 143 243 118 244 120 244 148 244 118 245 148 245 144 245 144 246 148 246 149 246 144 247 149 247 145 247 145 248 149 248 150 248 145 249 150 249 146 249 146 250 150 250 151 250 146 251 151 251 147 251 120 252 121 252 123 252 123 253 121 253 122 253 91 254 90 254 143 254 86 255 139 255 87 255 87 256 139 256 88 256 99 257 98 257 147 257 105 258 104 258 151 258 151 259 104 259 103 259 143 260 90 260 139 260 139 261 90 261 89 261 139 262 89 262 88 262 94 263 93 263 143 263 143 264 93 264 92 264 143 265 92 265 91 265 111 266 110 266 133 266 133 267 110 267 109 267 82 268 81 268 132 268 132 269 81 269 80 269 132 270 80 270 79 270 79 271 78 271 132 271 132 272 78 272 77 272 132 273 77 273 133 273 133 274 77 274 76 274 133 275 76 275 111 275 86 276 85 276 139 276 139 277 85 277 84 277 139 278 84 278 132 278 132 279 84 279 83 279 132 280 83 280 82 280 98 281 97 281 147 281 147 282 97 282 96 282 147 283 96 283 143 283 143 284 96 284 95 284 143 285 95 285 94 285 109 286 108 286 133 286 133 287 108 287 107 287 133 288 107 288 151 288 151 289 107 289 106 289 151 290 106 290 105 290 103 291 102 291 151 291 151 292 102 292 101 292 151 293 101 293 147 293 147 294 101 294 100 294 147 295 100 295 99 295 120 296 123 296 125 296 120 297 125 297 148 297 148 298 125 298 124 298 148 299 124 299 149 299 149 300 124 300 129 300 149 301 129 301 150 301 150 302 129 302 133 302 150 303 133 303 151 303 152 304 153 304 154 304 152 305 154 305 155 305 156 306 157 306 154 306 154 307 157 307 158 307 154 308 158 308 155 308 159 309 160 309 154 309 154 310 160 310 161 310 154 311 161 311 156 311 162 312 163 312 154 312 154 313 163 313 164 313 154 314 164 314 159 314 165 315 166 315 167 315 168 316 169 316 167 316 167 317 169 317 170 317 167 318 170 318 165 318 171 319 172 319 167 319 167 320 172 320 173 320 167 321 173 321 168 321 174 322 175 322 167 322 167 323 175 323 176 323 167 324 176 324 171 324 177 325 178 325 179 325 180 326 181 326 182 326 183 327 184 327 185 327 186 328 187 328 188 328 189 329 190 329 191 329 191 330 190 330 192 330 193 331 194 331 195 331 195 332 194 332 196 332 195 333 196 333 197 333 198 334 199 334 200 334 201 335 202 335 203 335 203 336 202 336 204 336 203 337 204 337 189 337 205 338 206 338 207 338 207 339 206 339 208 339 207 340 208 340 209 340 210 341 211 341 212 341 212 342 211 342 213 342 213 343 214 343 205 343 205 344 214 344 215 344 205 345 215 345 206 345 210 346 212 346 216 346 216 347 212 347 217 347 216 348 217 348 218 348 219 349 220 349 217 349 217 350 220 350 221 350 217 351 221 351 218 351 222 352 223 352 224 352 222 353 224 353 188 353 188 354 224 354 225 354 188 355 225 355 186 355 226 356 227 356 228 356 228 357 227 357 229 357 228 358 229 358 222 358 222 359 229 359 230 359 222 360 230 360 223 360 184 361 231 361 185 361 185 362 231 362 232 362 185 363 232 363 228 363 228 364 232 364 233 364 228 365 233 365 226 365 182 366 181 366 185 366 185 367 181 367 234 367 185 368 234 368 183 368 235 369 236 369 237 369 237 370 236 370 238 370 180 371 182 371 239 371 239 372 182 372 240 372 239 373 240 373 241 373 241 374 240 374 237 374 241 375 237 375 242 375 242 376 237 376 238 376 242 377 238 377 243 377 244 378 245 378 246 378 246 379 245 379 247 379 248 380 249 380 250 380 250 381 249 381 251 381 250 382 251 382 252 382 252 383 251 383 253 383 254 384 255 384 256 384 256 385 255 385 257 385 256 386 257 386 258 386 258 387 257 387 259 387 258 388 259 388 260 388 261 389 262 389 263 389 263 390 262 390 264 390 265 391 266 391 267 391 267 392 266 392 268 392 267 393 268 393 269 393 270 394 271 394 272 394 272 395 271 395 273 395 272 396 273 396 267 396 267 397 273 397 274 397 267 398 274 398 265 398 270 399 272 399 275 399 275 400 272 400 276 400 275 401 276 401 277 401 277 402 276 402 278 402 278 403 276 403 279 403 278 404 279 404 280 404 281 405 282 405 279 405 279 406 282 406 283 406 279 407 283 407 280 407 284 408 285 408 281 408 281 409 285 409 286 409 281 410 286 410 282 410 287 411 288 411 284 411 284 412 288 412 289 412 284 413 289 413 285 413 290 414 291 414 292 414 292 415 291 415 293 415 294 416 295 416 296 416 296 417 295 417 297 417 294 418 298 418 295 418 295 419 298 419 299 419 295 420 299 420 300 420 301 421 302 421 303 421 303 422 302 422 304 422 303 423 304 423 305 423 306 424 307 424 308 424 308 425 307 425 309 425 308 426 309 426 303 426 303 427 309 427 310 427 303 428 310 428 301 428 311 429 312 429 253 429 249 430 244 430 251 430 251 431 244 431 246 431 251 432 246 432 253 432 253 433 246 433 313 433 253 434 313 434 311 434 311 435 314 435 312 435 312 436 314 436 315 436 312 437 315 437 316 437 316 438 315 438 317 438 316 439 317 439 318 439 260 440 252 440 258 440 258 441 252 441 253 441 258 442 253 442 256 442 256 443 253 443 312 443 256 444 312 444 254 444 254 445 312 445 316 445 264 446 319 446 263 446 263 447 319 447 320 447 263 448 320 448 321 448 321 449 320 449 322 449 321 450 322 450 323 450 319 451 255 451 320 451 320 452 255 452 254 452 320 453 254 453 322 453 322 454 254 454 316 454 322 455 316 455 323 455 323 456 316 456 318 456 323 457 318 457 324 457 324 458 318 458 325 458 290 459 287 459 291 459 291 460 287 460 284 460 291 461 284 461 326 461 326 462 284 462 281 462 326 463 281 463 327 463 327 464 281 464 279 464 327 465 279 465 328 465 328 466 279 466 276 466 328 467 276 467 329 467 329 468 276 468 272 468 329 469 272 469 330 469 330 470 272 470 267 470 330 471 267 471 331 471 331 472 267 472 269 472 332 473 333 473 334 473 334 474 333 474 335 474 334 475 335 475 336 475 336 476 335 476 337 476 336 477 337 477 338 477 338 478 337 478 339 478 338 479 339 479 325 479 325 480 339 480 340 480 325 481 340 481 324 481 333 482 293 482 335 482 335 483 293 483 291 483 335 484 291 484 337 484 337 485 291 485 326 485 337 486 326 486 339 486 339 487 326 487 327 487 339 488 327 488 340 488 340 489 327 489 328 489 340 490 328 490 324 490 324 491 328 491 329 491 324 492 329 492 323 492 323 493 329 493 330 493 323 494 330 494 321 494 321 495 330 495 331 495 321 496 331 496 263 496 263 497 331 497 269 497 263 498 269 498 261 498 341 499 342 499 343 499 343 500 342 500 344 500 343 501 344 501 195 501 195 502 344 502 345 502 195 503 345 503 193 503 193 504 345 504 346 504 193 505 346 505 347 505 303 506 341 506 308 506 308 507 341 507 343 507 308 508 343 508 306 508 306 509 343 509 195 509 306 510 195 510 348 510 348 511 195 511 197 511 349 512 350 512 351 512 189 513 191 513 203 513 203 514 191 514 352 514 203 515 352 515 201 515 199 516 347 516 200 516 200 517 347 517 346 517 200 518 346 518 353 518 353 519 346 519 345 519 353 520 345 520 354 520 354 521 345 521 344 521 354 522 344 522 355 522 355 523 344 523 342 523 355 524 342 524 356 524 356 525 342 525 341 525 356 526 341 526 357 526 357 527 341 527 303 527 357 528 303 528 300 528 300 529 303 529 305 529 300 530 305 530 295 530 295 531 305 531 358 531 295 532 358 532 297 532 198 533 200 533 192 533 192 534 200 534 353 534 192 535 353 535 191 535 191 536 353 536 354 536 191 537 354 537 352 537 352 538 354 538 355 538 352 539 355 539 359 539 359 540 355 540 356 540 359 541 356 541 332 541 332 542 356 542 357 542 332 543 357 543 333 543 333 544 357 544 300 544 333 545 300 545 293 545 293 546 300 546 299 546 293 547 299 547 292 547 185 548 360 548 182 548 182 549 360 549 361 549 182 550 361 550 240 550 240 551 361 551 362 551 240 552 362 552 237 552 237 553 362 553 179 553 237 554 179 554 235 554 235 555 179 555 178 555 351 556 350 556 363 556 363 557 350 557 364 557 363 558 364 558 365 558 365 559 364 559 366 559 365 560 366 560 188 560 188 561 366 561 367 561 188 562 367 562 222 562 222 563 367 563 368 563 222 564 368 564 228 564 228 565 368 565 369 565 228 566 369 566 185 566 185 567 369 567 370 567 185 568 370 568 360 568 187 569 219 569 188 569 188 570 219 570 217 570 188 571 217 571 365 571 365 572 217 572 212 572 365 573 212 573 363 573 363 574 212 574 213 574 363 575 213 575 351 575 351 576 213 576 205 576 351 577 205 577 349 577 349 578 205 578 207 578 247 579 177 579 246 579 246 580 177 580 179 580 246 581 179 581 313 581 313 582 179 582 362 582 313 583 362 583 311 583 311 584 362 584 361 584 311 585 361 585 314 585 314 586 361 586 360 586 314 587 360 587 315 587 315 588 360 588 370 588 315 589 370 589 317 589 317 590 370 590 369 590 317 591 369 591 318 591 318 592 369 592 368 592 318 593 368 593 325 593 325 594 368 594 367 594 325 595 367 595 338 595 338 596 367 596 366 596 338 597 366 597 336 597 336 598 366 598 364 598 336 599 364 599 334 599 334 600 364 600 350 600 334 601 350 601 332 601 332 602 350 602 349 602 332 603 349 603 359 603 359 604 349 604 207 604 359 605 207 605 352 605 352 606 207 606 209 606 352 607 209 607 201 607 371 608 372 608 373 608 374 609 375 609 376 609 377 610 378 610 379 610 380 611 381 611 382 611 382 612 381 612 383 612 384 613 385 613 386 613 387 614 388 614 389 614 372 615 371 615 390 615 391 616 392 616 393 616 394 617 387 617 395 617 395 618 387 618 389 618 395 619 389 619 396 619 388 620 397 620 398 620 398 621 397 621 399 621 398 622 399 622 400 622 393 623 390 623 391 623 391 624 390 624 371 624 391 625 371 625 401 625 401 626 371 626 400 626 401 627 400 627 402 627 402 628 400 628 399 628 403 629 385 629 404 629 404 630 385 630 384 630 404 631 384 631 405 631 405 632 384 632 406 632 407 633 406 633 408 633 408 634 406 634 384 634 408 635 384 635 409 635 409 636 384 636 386 636 409 637 386 637 410 637 411 638 412 638 413 638 414 639 415 639 416 639 416 640 415 640 417 640 416 641 417 641 418 641 418 642 417 642 419 642 418 643 419 643 413 643 413 644 419 644 420 644 413 645 420 645 411 645 411 646 421 646 412 646 412 647 421 647 422 647 412 648 422 648 423 648 423 649 422 649 424 649 423 650 424 650 425 650 378 651 426 651 379 651 379 652 426 652 427 652 379 653 427 653 428 653 428 654 427 654 429 654 428 655 429 655 430 655 430 656 429 656 431 656 430 657 431 657 432 657 432 658 431 658 433 658 432 659 433 659 434 659 434 660 433 660 435 660 434 661 435 661 436 661 436 662 435 662 437 662 436 663 437 663 438 663 438 664 437 664 439 664 438 665 439 665 440 665 381 666 440 666 383 666 383 667 440 667 439 667 383 668 439 668 441 668 441 669 439 669 437 669 441 670 437 670 425 670 425 671 437 671 435 671 425 672 435 672 423 672 423 673 435 673 433 673 423 674 433 674 412 674 412 675 433 675 431 675 412 676 431 676 413 676 413 677 431 677 429 677 413 678 429 678 418 678 418 679 429 679 427 679 418 680 427 680 416 680 442 681 382 681 443 681 443 682 382 682 383 682 443 683 383 683 444 683 444 684 383 684 441 684 444 685 441 685 445 685 445 686 441 686 425 686 445 687 425 687 446 687 446 688 425 688 424 688 447 689 448 689 449 689 449 690 448 690 450 690 450 691 377 691 449 691 449 692 377 692 379 692 449 693 379 693 451 693 451 694 379 694 428 694 451 695 428 695 452 695 452 696 428 696 430 696 452 697 430 697 453 697 453 698 430 698 432 698 453 699 432 699 454 699 454 700 432 700 434 700 454 701 434 701 455 701 455 702 434 702 436 702 455 703 436 703 456 703 456 704 436 704 438 704 456 705 438 705 457 705 457 706 438 706 440 706 457 707 440 707 458 707 458 708 440 708 381 708 458 709 381 709 459 709 459 710 381 710 380 710 376 711 460 711 374 711 374 712 460 712 461 712 374 713 461 713 462 713 462 714 461 714 463 714 462 715 463 715 464 715 464 716 463 716 465 716 464 717 465 717 466 717 466 718 465 718 467 718 468 719 469 719 470 719 470 720 469 720 471 720 470 721 471 721 472 721 467 722 473 722 466 722 466 723 473 723 474 723 466 724 474 724 475 724 475 725 474 725 476 725 475 726 476 726 468 726 468 727 476 727 477 727 468 728 477 728 469 728 471 729 478 729 479 729 388 730 398 730 389 730 389 731 398 731 480 731 389 732 480 732 396 732 373 733 481 733 371 733 371 734 481 734 482 734 371 735 482 735 400 735 400 736 482 736 483 736 400 737 483 737 398 737 398 738 483 738 484 738 398 739 484 739 480 739 485 740 414 740 486 740 486 741 414 741 416 741 486 742 416 742 487 742 487 743 416 743 427 743 487 744 427 744 488 744 488 745 427 745 426 745 403 746 489 746 385 746 385 747 489 747 394 747 385 748 394 748 386 748 386 749 394 749 395 749 386 750 395 750 410 750 471 751 479 751 472 751 472 752 479 752 490 752 472 753 490 753 491 753 491 754 447 754 472 754 472 755 447 755 449 755 472 756 449 756 470 756 470 757 449 757 451 757 470 758 451 758 468 758 468 759 451 759 452 759 468 760 452 760 475 760 475 761 452 761 453 761 475 762 453 762 466 762 466 763 453 763 454 763 466 764 454 764 464 764 464 765 454 765 455 765 464 766 455 766 462 766 462 767 455 767 456 767 462 768 456 768 374 768 374 769 456 769 457 769 374 770 457 770 375 770 375 771 457 771 458 771 375 772 458 772 492 772 492 773 458 773 459 773 492 774 459 774 493 774 494 775 495 775 493 775 493 776 495 776 496 776 493 777 496 777 492 777 492 778 496 778 497 778 492 779 497 779 375 779 375 780 497 780 498 780 375 781 498 781 376 781 396 782 494 782 395 782 395 783 494 783 493 783 395 784 493 784 410 784 410 785 493 785 459 785 410 786 459 786 409 786 409 787 459 787 380 787 409 788 380 788 408 788 408 789 380 789 382 789 408 790 382 790 407 790 407 791 382 791 442 791 499 792 500 792 501 792 502 793 503 793 504 793 505 794 506 794 507 794 508 795 509 795 510 795 511 796 512 796 513 796 512 797 511 797 514 797 515 798 516 798 517 798 518 799 519 799 520 799 521 800 522 800 523 800 524 801 525 801 526 801 526 802 525 802 527 802 528 803 525 803 529 803 529 804 525 804 530 804 528 805 531 805 525 805 525 806 531 806 532 806 525 807 532 807 527 807 533 808 534 808 535 808 535 809 534 809 536 809 535 810 536 810 537 810 537 811 536 811 538 811 537 812 538 812 525 812 539 813 535 813 540 813 540 814 535 814 537 814 540 815 537 815 541 815 541 816 537 816 525 816 541 817 525 817 542 817 542 818 525 818 524 818 543 819 544 819 545 819 545 820 544 820 546 820 545 821 546 821 547 821 548 822 549 822 550 822 550 823 549 823 551 823 552 824 553 824 554 824 554 825 553 825 555 825 554 826 555 826 556 826 556 827 555 827 557 827 558 828 557 828 559 828 559 829 557 829 555 829 559 830 555 830 560 830 560 831 555 831 553 831 561 832 558 832 562 832 562 833 558 833 559 833 562 834 559 834 563 834 563 835 559 835 560 835 563 836 560 836 564 836 564 837 560 837 553 837 564 838 553 838 565 838 565 839 553 839 552 839 565 840 552 840 566 840 567 841 568 841 551 841 551 842 568 842 569 842 517 843 570 843 571 843 571 844 570 844 572 844 571 845 572 845 573 845 520 846 574 846 518 846 518 847 574 847 575 847 518 848 575 848 576 848 576 849 575 849 577 849 576 850 577 850 578 850 519 851 518 851 579 851 579 852 518 852 576 852 579 853 576 853 580 853 580 854 576 854 578 854 580 855 578 855 581 855 517 856 516 856 570 856 570 857 516 857 582 857 570 858 582 858 572 858 583 859 584 859 585 859 583 860 585 860 586 860 585 861 587 861 586 861 586 862 587 862 588 862 586 863 588 863 589 863 589 864 588 864 590 864 589 865 590 865 513 865 500 866 508 866 501 866 501 867 508 867 510 867 501 868 510 868 591 868 591 869 510 869 592 869 591 870 592 870 593 870 593 871 592 871 583 871 593 872 583 872 594 872 594 873 583 873 586 873 594 874 586 874 595 874 595 875 586 875 589 875 595 876 589 876 596 876 596 877 589 877 513 877 596 878 513 878 597 878 597 879 513 879 512 879 597 880 512 880 598 880 598 881 512 881 514 881 598 882 514 882 599 882 599 883 514 883 600 883 599 884 600 884 601 884 590 885 602 885 513 885 513 886 602 886 603 886 513 887 603 887 511 887 511 888 603 888 604 888 511 889 604 889 605 889 574 890 601 890 575 890 575 891 601 891 600 891 575 892 600 892 577 892 577 893 600 893 514 893 577 894 514 894 578 894 578 895 514 895 511 895 578 896 511 896 581 896 581 897 511 897 605 897 581 898 605 898 606 898 442 899 443 899 607 899 607 900 443 900 444 900 607 901 444 901 608 901 609 902 610 902 406 902 572 903 611 903 610 903 610 904 611 904 405 904 610 905 405 905 406 905 548 906 611 906 549 906 549 907 611 907 572 907 549 908 572 908 551 908 551 909 572 909 612 909 551 910 612 910 613 910 613 911 612 911 522 911 613 912 522 912 551 912 551 913 522 913 521 913 551 914 521 914 567 914 506 915 505 915 614 915 614 916 505 916 615 916 614 917 615 917 616 917 615 918 617 918 616 918 616 919 617 919 618 919 616 920 618 920 609 920 609 921 618 921 619 921 609 922 619 922 610 922 610 923 619 923 620 923 610 924 620 924 572 924 444 925 445 925 608 925 608 926 445 926 446 926 608 927 446 927 621 927 406 928 407 928 609 928 609 929 407 929 442 929 609 930 442 930 616 930 616 931 442 931 607 931 616 932 607 932 614 932 614 933 607 933 608 933 614 934 608 934 506 934 506 935 608 935 621 935 506 936 621 936 507 936 622 937 421 937 411 937 622 938 411 938 623 938 421 939 622 939 422 939 422 940 622 940 624 940 422 941 624 941 424 941 485 942 625 942 414 942 414 943 625 943 626 943 411 944 420 944 623 944 623 945 420 945 419 945 623 946 419 946 627 946 627 947 419 947 417 947 627 948 417 948 626 948 626 949 417 949 415 949 626 950 415 950 414 950 446 951 424 951 621 951 621 952 424 952 624 952 621 953 624 953 507 953 507 954 624 954 628 954 507 955 628 955 505 955 505 956 628 956 566 956 505 957 566 957 615 957 615 958 566 958 552 958 615 959 552 959 617 959 617 960 552 960 554 960 617 961 554 961 618 961 618 962 554 962 556 962 618 963 556 963 619 963 619 964 556 964 557 964 619 965 557 965 620 965 620 966 557 966 558 966 620 967 558 967 572 967 572 968 558 968 561 968 542 969 629 969 541 969 541 970 629 970 630 970 541 971 630 971 631 971 539 972 399 972 397 972 397 973 545 973 539 973 539 974 545 974 547 974 539 975 547 975 535 975 535 976 547 976 632 976 535 977 632 977 533 977 399 978 539 978 402 978 402 979 539 979 540 979 402 980 540 980 401 980 401 981 540 981 541 981 401 982 541 982 391 982 391 983 541 983 631 983 391 984 631 984 392 984 584 985 583 985 633 985 633 986 583 986 592 986 633 987 592 987 634 987 634 988 592 988 510 988 634 989 510 989 504 989 504 990 510 990 509 990 504 991 509 991 502 991 569 992 635 992 551 992 551 993 635 993 636 993 551 994 636 994 550 994 550 995 636 995 637 995 550 996 637 996 543 996 543 997 637 997 638 997 543 998 638 998 544 998 625 999 499 999 626 999 626 1000 499 1000 501 1000 626 1001 501 1001 627 1001 627 1002 501 1002 591 1002 627 1003 591 1003 623 1003 623 1004 591 1004 593 1004 623 1005 593 1005 622 1005 622 1006 593 1006 594 1006 622 1007 594 1007 624 1007 624 1008 594 1008 595 1008 624 1009 595 1009 628 1009 628 1010 595 1010 596 1010 628 1011 596 1011 566 1011 566 1012 596 1012 597 1012 566 1013 597 1013 565 1013 565 1014 597 1014 598 1014 565 1015 598 1015 564 1015 564 1016 598 1016 599 1016 564 1017 599 1017 563 1017 563 1018 599 1018 601 1018 563 1019 601 1019 562 1019 562 1020 601 1020 574 1020 562 1021 574 1021 561 1021 561 1022 574 1022 520 1022 561 1023 520 1023 572 1023 572 1024 520 1024 519 1024 572 1025 519 1025 573 1025 573 1026 519 1026 579 1026 573 1027 579 1027 571 1027 571 1028 579 1028 580 1028 571 1029 580 1029 517 1029 517 1030 580 1030 581 1030 517 1031 581 1031 515 1031 515 1032 581 1032 606 1032 397 1033 388 1033 545 1033 545 1034 388 1034 387 1034 545 1035 387 1035 543 1035 543 1036 387 1036 394 1036 543 1037 394 1037 550 1037 550 1038 394 1038 489 1038 550 1039 489 1039 548 1039 548 1040 489 1040 403 1040 548 1041 403 1041 611 1041 611 1042 403 1042 404 1042 611 1043 404 1043 405 1043 639 1044 640 1044 641 1044 642 1045 643 1045 644 1045 645 1046 646 1046 647 1046 648 1047 649 1047 650 1047 651 1048 530 1048 525 1048 652 1049 653 1049 654 1049 655 1050 656 1050 657 1050 655 1051 657 1051 658 1051 659 1052 660 1052 661 1052 661 1053 660 1053 662 1053 661 1054 662 1054 663 1054 664 1055 658 1055 665 1055 665 1056 658 1056 657 1056 665 1057 657 1057 666 1057 666 1058 657 1058 667 1058 666 1059 667 1059 668 1059 668 1060 667 1060 663 1060 668 1061 663 1061 669 1061 669 1062 663 1062 662 1062 670 1063 671 1063 672 1063 672 1064 671 1064 673 1064 673 1065 671 1065 674 1065 673 1066 674 1066 675 1066 672 1067 676 1067 670 1067 670 1068 676 1068 677 1068 670 1069 677 1069 678 1069 678 1070 677 1070 679 1070 678 1071 679 1071 680 1071 679 1072 681 1072 680 1072 680 1073 681 1073 682 1073 680 1074 682 1074 683 1074 683 1075 682 1075 684 1075 683 1076 684 1076 685 1076 685 1077 684 1077 686 1077 685 1078 686 1078 687 1078 635 1079 569 1079 688 1079 688 1080 569 1080 568 1080 568 1081 567 1081 689 1081 567 1082 521 1082 689 1082 689 1083 521 1083 523 1083 689 1084 523 1084 522 1084 568 1085 689 1085 688 1085 688 1086 689 1086 690 1086 688 1087 690 1087 635 1087 612 1088 691 1088 692 1088 612 1089 572 1089 691 1089 691 1090 572 1090 582 1090 691 1091 582 1091 693 1091 693 1092 582 1092 516 1092 694 1093 695 1093 696 1093 696 1094 695 1094 697 1094 698 1095 515 1095 699 1095 699 1096 515 1096 606 1096 699 1097 606 1097 605 1097 700 1098 701 1098 602 1098 695 1099 698 1099 697 1099 697 1100 698 1100 699 1100 697 1101 699 1101 702 1101 702 1102 699 1102 605 1102 702 1103 605 1103 703 1103 703 1104 605 1104 604 1104 703 1105 604 1105 701 1105 701 1106 604 1106 603 1106 701 1107 603 1107 602 1107 602 1108 590 1108 700 1108 700 1109 590 1109 588 1109 700 1110 588 1110 704 1110 704 1111 588 1111 587 1111 704 1112 587 1112 585 1112 705 1113 706 1113 584 1113 584 1114 633 1114 705 1114 705 1115 633 1115 634 1115 705 1116 634 1116 707 1116 707 1117 634 1117 504 1117 707 1118 504 1118 503 1118 503 1119 708 1119 707 1119 707 1120 708 1120 709 1120 707 1121 709 1121 710 1121 711 1122 712 1122 525 1122 525 1123 712 1123 713 1123 525 1124 713 1124 651 1124 714 1125 715 1125 525 1125 525 1126 715 1126 716 1126 525 1127 716 1127 711 1127 717 1128 718 1128 714 1128 714 1129 718 1129 719 1129 714 1130 719 1130 715 1130 533 1131 720 1131 534 1131 534 1132 720 1132 721 1132 534 1133 721 1133 536 1133 536 1134 721 1134 722 1134 723 1135 724 1135 725 1135 649 1136 717 1136 650 1136 650 1137 717 1137 714 1137 650 1138 714 1138 726 1138 533 1139 632 1139 720 1139 720 1140 632 1140 547 1140 720 1141 547 1141 727 1141 722 1142 721 1142 724 1142 724 1143 721 1143 720 1143 724 1144 720 1144 725 1144 725 1145 720 1145 727 1145 725 1146 727 1146 728 1146 729 1147 546 1147 544 1147 729 1148 544 1148 730 1148 544 1149 638 1149 730 1149 730 1150 638 1150 637 1150 730 1151 637 1151 690 1151 690 1152 637 1152 636 1152 690 1153 636 1153 635 1153 547 1154 546 1154 727 1154 727 1155 546 1155 729 1155 727 1156 729 1156 728 1156 728 1157 729 1157 730 1157 728 1158 730 1158 731 1158 731 1159 730 1159 690 1159 731 1160 690 1160 732 1160 732 1161 690 1161 689 1161 732 1162 689 1162 692 1162 692 1163 689 1163 522 1163 692 1164 522 1164 612 1164 723 1165 725 1165 733 1165 733 1166 725 1166 728 1166 733 1167 728 1167 734 1167 734 1168 728 1168 731 1168 734 1169 731 1169 735 1169 735 1170 731 1170 732 1170 735 1171 732 1171 736 1171 736 1172 732 1172 692 1172 736 1173 692 1173 694 1173 694 1174 692 1174 691 1174 694 1175 691 1175 695 1175 695 1176 691 1176 693 1176 695 1177 693 1177 698 1177 698 1178 693 1178 516 1178 698 1179 516 1179 515 1179 734 1180 737 1180 733 1180 733 1181 737 1181 726 1181 733 1182 726 1182 723 1182 723 1183 726 1183 714 1183 723 1184 714 1184 724 1184 724 1185 714 1185 525 1185 724 1186 525 1186 722 1186 722 1187 525 1187 538 1187 722 1188 538 1188 536 1188 696 1189 738 1189 694 1189 694 1190 738 1190 739 1190 694 1191 739 1191 736 1191 736 1192 739 1192 740 1192 736 1193 740 1193 735 1193 735 1194 740 1194 741 1194 735 1195 741 1195 734 1195 734 1196 741 1196 742 1196 734 1197 742 1197 737 1197 646 1198 648 1198 647 1198 647 1199 648 1199 650 1199 647 1200 650 1200 743 1200 743 1201 650 1201 726 1201 743 1202 726 1202 744 1202 744 1203 726 1203 737 1203 744 1204 737 1204 745 1204 745 1205 737 1205 742 1205 745 1206 742 1206 746 1206 746 1207 742 1207 741 1207 746 1208 741 1208 747 1208 747 1209 741 1209 740 1209 747 1210 740 1210 748 1210 748 1211 740 1211 739 1211 748 1212 739 1212 749 1212 749 1213 739 1213 738 1213 749 1214 738 1214 750 1214 750 1215 738 1215 696 1215 750 1216 696 1216 751 1216 751 1217 696 1217 697 1217 751 1218 697 1218 752 1218 752 1219 697 1219 702 1219 752 1220 702 1220 753 1220 753 1221 702 1221 703 1221 753 1222 703 1222 754 1222 754 1223 703 1223 701 1223 754 1224 701 1224 755 1224 755 1225 701 1225 700 1225 755 1226 700 1226 756 1226 756 1227 700 1227 704 1227 756 1228 704 1228 706 1228 706 1229 704 1229 585 1229 706 1230 585 1230 584 1230 675 1231 674 1231 757 1231 757 1232 674 1232 654 1232 757 1233 654 1233 758 1233 758 1234 654 1234 653 1234 758 1235 653 1235 759 1235 686 1236 760 1236 687 1236 687 1237 760 1237 761 1237 687 1238 761 1238 762 1238 762 1239 761 1239 763 1239 762 1240 763 1240 764 1240 764 1241 763 1241 765 1241 764 1242 765 1242 766 1242 766 1243 765 1243 767 1243 766 1244 767 1244 642 1244 642 1245 767 1245 768 1245 642 1246 768 1246 643 1246 640 1247 652 1247 641 1247 641 1248 652 1248 654 1248 641 1249 654 1249 769 1249 769 1250 654 1250 674 1250 769 1251 674 1251 770 1251 770 1252 674 1252 671 1252 770 1253 671 1253 771 1253 771 1254 671 1254 670 1254 771 1255 670 1255 772 1255 772 1256 670 1256 678 1256 772 1257 678 1257 773 1257 773 1258 678 1258 680 1258 773 1259 680 1259 774 1259 774 1260 680 1260 683 1260 774 1261 683 1261 775 1261 775 1262 683 1262 685 1262 775 1263 685 1263 776 1263 776 1264 685 1264 687 1264 776 1265 687 1265 777 1265 777 1266 687 1266 762 1266 777 1267 762 1267 778 1267 778 1268 762 1268 764 1268 778 1269 764 1269 779 1269 779 1270 764 1270 766 1270 779 1271 766 1271 780 1271 780 1272 766 1272 642 1272 780 1273 642 1273 659 1273 659 1274 642 1274 644 1274 659 1275 644 1275 660 1275 710 1276 639 1276 707 1276 707 1277 639 1277 641 1277 707 1278 641 1278 705 1278 705 1279 641 1279 769 1279 705 1280 769 1280 706 1280 706 1281 769 1281 770 1281 706 1282 770 1282 756 1282 756 1283 770 1283 771 1283 756 1284 771 1284 755 1284 755 1285 771 1285 772 1285 755 1286 772 1286 754 1286 754 1287 772 1287 773 1287 754 1288 773 1288 753 1288 753 1289 773 1289 774 1289 753 1290 774 1290 752 1290 752 1291 774 1291 775 1291 752 1292 775 1292 751 1292 751 1293 775 1293 776 1293 751 1294 776 1294 750 1294 750 1295 776 1295 777 1295 750 1296 777 1296 749 1296 749 1297 777 1297 778 1297 749 1298 778 1298 748 1298 748 1299 778 1299 779 1299 748 1300 779 1300 747 1300 747 1301 779 1301 780 1301 747 1302 780 1302 746 1302 746 1303 780 1303 659 1303 746 1304 659 1304 745 1304 745 1305 659 1305 661 1305 745 1306 661 1306 744 1306 744 1307 661 1307 663 1307 744 1308 663 1308 743 1308 743 1309 663 1309 667 1309 743 1310 667 1310 647 1310 647 1311 667 1311 657 1311 647 1312 657 1312 645 1312 645 1313 657 1313 656 1313 781 1314 782 1314 783 1314 392 1315 631 1315 784 1315 531 1316 528 1316 785 1316 786 1317 782 1317 787 1317 788 1318 789 1318 790 1318 791 1319 792 1319 793 1319 793 1320 792 1320 794 1320 793 1321 794 1321 795 1321 796 1322 797 1322 798 1322 798 1323 797 1323 799 1323 789 1324 788 1324 800 1324 795 1325 801 1325 793 1325 793 1326 801 1326 802 1326 793 1327 802 1327 791 1327 791 1328 802 1328 803 1328 804 1329 799 1329 803 1329 803 1330 799 1330 797 1330 803 1331 797 1331 791 1331 791 1332 797 1332 796 1332 791 1333 796 1333 792 1333 786 1334 787 1334 805 1334 806 1335 805 1335 807 1335 807 1336 805 1336 787 1336 807 1337 787 1337 808 1337 808 1338 787 1338 809 1338 808 1339 809 1339 810 1339 781 1340 811 1340 804 1340 804 1341 811 1341 812 1341 804 1342 812 1342 799 1342 390 1343 393 1343 813 1343 813 1344 393 1344 814 1344 785 1345 528 1345 815 1345 815 1346 528 1346 529 1346 815 1347 529 1347 530 1347 630 1348 629 1348 816 1348 816 1349 629 1349 542 1349 524 1350 526 1350 817 1350 817 1351 526 1351 527 1351 817 1352 527 1352 785 1352 785 1353 527 1353 532 1353 785 1354 532 1354 531 1354 818 1355 816 1355 817 1355 817 1356 816 1356 542 1356 817 1357 542 1357 524 1357 631 1358 630 1358 784 1358 784 1359 630 1359 816 1359 784 1360 816 1360 800 1360 800 1361 816 1361 818 1361 800 1362 818 1362 789 1362 788 1363 810 1363 800 1363 800 1364 810 1364 819 1364 800 1365 819 1365 784 1365 784 1366 819 1366 814 1366 784 1367 814 1367 392 1367 392 1368 814 1368 393 1368 781 1369 820 1369 811 1369 811 1370 820 1370 821 1370 811 1371 821 1371 812 1371 812 1372 821 1372 822 1372 812 1373 822 1373 799 1373 799 1374 822 1374 823 1374 799 1375 823 1375 798 1375 801 1376 809 1376 802 1376 802 1377 809 1377 787 1377 802 1378 787 1378 803 1378 803 1379 787 1379 782 1379 803 1380 782 1380 804 1380 804 1381 782 1381 781 1381 373 1382 372 1382 824 1382 824 1383 372 1383 795 1383 824 1384 795 1384 825 1384 825 1385 795 1385 794 1385 810 1386 809 1386 819 1386 819 1387 809 1387 801 1387 819 1388 801 1388 814 1388 814 1389 801 1389 795 1389 814 1390 795 1390 813 1390 813 1391 795 1391 372 1391 813 1392 372 1392 390 1392 826 1393 827 1393 828 1393 818 1394 817 1394 829 1394 830 1395 831 1395 832 1395 833 1396 834 1396 835 1396 835 1397 834 1397 836 1397 837 1398 781 1398 838 1398 839 1399 840 1399 841 1399 782 1400 842 1400 781 1400 808 1401 810 1401 843 1401 844 1402 845 1402 846 1402 846 1403 845 1403 847 1403 846 1404 847 1404 197 1404 810 1405 788 1405 848 1405 848 1406 788 1406 790 1406 848 1407 790 1407 789 1407 805 1408 807 1408 786 1408 786 1409 807 1409 849 1409 786 1410 849 1410 782 1410 782 1411 849 1411 850 1411 782 1412 850 1412 842 1412 851 1413 852 1413 853 1413 853 1414 852 1414 850 1414 853 1415 850 1415 843 1415 843 1416 850 1416 849 1416 843 1417 849 1417 808 1417 808 1418 849 1418 807 1418 854 1419 855 1419 856 1419 856 1420 855 1420 857 1420 781 1421 842 1421 857 1421 857 1422 842 1422 858 1422 857 1423 858 1423 856 1423 831 1424 859 1424 832 1424 832 1425 859 1425 860 1425 832 1426 860 1426 861 1426 861 1427 860 1427 862 1427 861 1428 862 1428 863 1428 864 1429 862 1429 865 1429 865 1430 862 1430 860 1430 865 1431 860 1431 866 1431 866 1432 860 1432 859 1432 863 1433 862 1433 867 1433 867 1434 862 1434 864 1434 867 1435 864 1435 868 1435 868 1436 864 1436 869 1436 868 1437 869 1437 870 1437 871 1438 872 1438 873 1438 873 1439 872 1439 869 1439 873 1440 869 1440 874 1440 874 1441 869 1441 864 1441 874 1442 864 1442 875 1442 875 1443 864 1443 865 1443 876 1444 863 1444 877 1444 877 1445 863 1445 867 1445 877 1446 867 1446 878 1446 878 1447 867 1447 868 1447 878 1448 868 1448 879 1448 879 1449 868 1449 870 1449 879 1450 870 1450 880 1450 837 1451 838 1451 881 1451 882 1452 883 1452 884 1452 884 1453 883 1453 885 1453 884 1454 885 1454 886 1454 886 1455 885 1455 887 1455 886 1456 887 1456 888 1456 889 1457 890 1457 891 1457 892 1458 893 1458 894 1458 894 1459 893 1459 895 1459 896 1460 887 1460 897 1460 897 1461 887 1461 885 1461 897 1462 885 1462 898 1462 898 1463 885 1463 883 1463 898 1464 883 1464 899 1464 899 1465 883 1465 882 1465 899 1466 882 1466 900 1466 892 1467 901 1467 893 1467 893 1468 901 1468 891 1468 893 1469 891 1469 895 1469 895 1470 891 1470 890 1470 852 1471 902 1471 850 1471 850 1472 902 1472 900 1472 850 1473 900 1473 842 1473 842 1474 900 1474 882 1474 842 1475 882 1475 858 1475 858 1476 882 1476 884 1476 858 1477 884 1477 856 1477 856 1478 884 1478 886 1478 856 1479 886 1479 854 1479 854 1480 886 1480 888 1480 881 1481 903 1481 837 1481 837 1482 903 1482 904 1482 837 1483 904 1483 781 1483 905 1484 906 1484 907 1484 907 1485 906 1485 908 1485 907 1486 908 1486 909 1486 903 1487 910 1487 904 1487 904 1488 910 1488 781 1488 881 1489 907 1489 903 1489 903 1490 907 1490 909 1490 903 1491 909 1491 910 1491 910 1492 909 1492 911 1492 910 1493 911 1493 912 1493 912 1494 911 1494 913 1494 896 1495 914 1495 887 1495 887 1496 914 1496 839 1496 887 1497 839 1497 888 1497 888 1498 839 1498 841 1498 888 1499 841 1499 915 1499 871 1500 916 1500 872 1500 872 1501 916 1501 890 1501 872 1502 890 1502 869 1502 869 1503 890 1503 889 1503 869 1504 889 1504 870 1504 870 1505 889 1505 917 1505 870 1506 917 1506 880 1506 918 1507 919 1507 846 1507 846 1508 919 1508 920 1508 846 1509 920 1509 844 1509 921 1510 922 1510 923 1510 923 1511 924 1511 921 1511 921 1512 924 1512 925 1512 921 1513 925 1513 926 1513 835 1514 927 1514 833 1514 833 1515 927 1515 928 1515 833 1516 928 1516 922 1516 922 1517 928 1517 929 1517 922 1518 929 1518 923 1518 930 1519 921 1519 846 1519 846 1520 921 1520 926 1520 846 1521 926 1521 918 1521 876 1522 834 1522 863 1522 863 1523 834 1523 833 1523 863 1524 833 1524 861 1524 861 1525 833 1525 922 1525 861 1526 922 1526 832 1526 832 1527 922 1527 921 1527 832 1528 921 1528 830 1528 830 1529 921 1529 930 1529 880 1530 931 1530 879 1530 879 1531 931 1531 932 1531 879 1532 932 1532 878 1532 878 1533 932 1533 933 1533 878 1534 933 1534 877 1534 877 1535 933 1535 934 1535 877 1536 934 1536 876 1536 876 1537 934 1537 935 1537 876 1538 935 1538 834 1538 834 1539 935 1539 828 1539 834 1540 828 1540 836 1540 836 1541 828 1541 827 1541 530 1542 651 1542 815 1542 815 1543 651 1543 785 1543 651 1544 713 1544 785 1544 785 1545 713 1545 712 1545 785 1546 712 1546 817 1546 817 1547 712 1547 711 1547 711 1548 716 1548 817 1548 817 1549 716 1549 715 1549 817 1550 715 1550 829 1550 829 1551 715 1551 719 1551 829 1552 719 1552 718 1552 718 1553 717 1553 829 1553 829 1554 717 1554 649 1554 829 1555 649 1555 936 1555 645 1556 937 1556 646 1556 646 1557 937 1557 936 1557 646 1558 936 1558 648 1558 648 1559 936 1559 649 1559 937 1560 938 1560 936 1560 936 1561 938 1561 939 1561 936 1562 939 1562 829 1562 829 1563 939 1563 848 1563 829 1564 848 1564 818 1564 818 1565 848 1565 789 1565 810 1566 848 1566 843 1566 843 1567 848 1567 939 1567 843 1568 939 1568 853 1568 853 1569 939 1569 938 1569 853 1570 938 1570 851 1570 851 1571 938 1571 937 1571 851 1572 937 1572 940 1572 940 1573 937 1573 645 1573 940 1574 645 1574 656 1574 656 1575 655 1575 940 1575 940 1576 655 1576 658 1576 940 1577 658 1577 664 1577 913 1578 941 1578 912 1578 912 1579 941 1579 942 1579 912 1580 942 1580 910 1580 910 1581 942 1581 781 1581 915 1582 905 1582 888 1582 888 1583 905 1583 907 1583 888 1584 907 1584 854 1584 854 1585 907 1585 881 1585 854 1586 881 1586 855 1586 855 1587 881 1587 838 1587 855 1588 838 1588 857 1588 857 1589 838 1589 781 1589 901 1590 914 1590 891 1590 891 1591 914 1591 896 1591 891 1592 896 1592 889 1592 889 1593 896 1593 897 1593 889 1594 897 1594 917 1594 917 1595 897 1595 898 1595 917 1596 898 1596 880 1596 880 1597 898 1597 899 1597 880 1598 899 1598 931 1598 931 1599 899 1599 900 1599 931 1600 900 1600 932 1600 932 1601 900 1601 902 1601 932 1602 902 1602 933 1602 933 1603 902 1603 852 1603 933 1604 852 1604 934 1604 934 1605 852 1605 851 1605 934 1606 851 1606 935 1606 935 1607 851 1607 940 1607 935 1608 940 1608 828 1608 828 1609 940 1609 664 1609 828 1610 664 1610 826 1610 943 1611 944 1611 945 1611 946 1612 947 1612 948 1612 948 1613 949 1613 950 1613 154 1614 946 1614 951 1614 951 1615 946 1615 948 1615 951 1616 948 1616 952 1616 952 1617 948 1617 950 1617 953 1618 954 1618 955 1618 955 1619 954 1619 956 1619 955 1620 956 1620 957 1620 953 1621 958 1621 954 1621 954 1622 958 1622 959 1622 954 1623 959 1623 949 1623 949 1624 959 1624 960 1624 949 1625 960 1625 950 1625 957 1626 956 1626 961 1626 961 1627 956 1627 962 1627 961 1628 962 1628 963 1628 964 1629 965 1629 962 1629 962 1630 965 1630 966 1630 962 1631 966 1631 963 1631 967 1632 968 1632 964 1632 964 1633 968 1633 969 1633 964 1634 969 1634 965 1634 970 1635 971 1635 967 1635 967 1636 971 1636 972 1636 967 1637 972 1637 968 1637 973 1638 974 1638 975 1638 974 1639 973 1639 976 1639 976 1640 973 1640 977 1640 976 1641 977 1641 978 1641 978 1642 977 1642 979 1642 979 1643 977 1643 980 1643 979 1644 980 1644 981 1644 982 1645 983 1645 984 1645 984 1646 983 1646 985 1646 984 1647 985 1647 986 1647 981 1648 980 1648 987 1648 987 1649 980 1649 985 1649 987 1650 985 1650 988 1650 988 1651 985 1651 983 1651 988 1652 983 1652 989 1652 990 1653 991 1653 992 1653 992 1654 991 1654 993 1654 994 1655 995 1655 996 1655 996 1656 995 1656 997 1656 996 1657 997 1657 998 1657 998 1658 997 1658 999 1658 994 1659 1000 1659 995 1659 995 1660 1000 1660 1001 1660 995 1661 1001 1661 1002 1661 1001 1662 1003 1662 1002 1662 1002 1663 1003 1663 1004 1663 1002 1664 1004 1664 990 1664 990 1665 1004 1665 1005 1665 990 1666 1005 1666 991 1666 999 1667 997 1667 1006 1667 1006 1668 997 1668 1007 1668 1006 1669 1007 1669 1008 1669 1008 1670 1007 1670 1009 1670 1008 1671 1009 1671 1010 1671 975 1672 971 1672 973 1672 973 1673 971 1673 970 1673 973 1674 970 1674 977 1674 977 1675 970 1675 1011 1675 977 1676 1011 1676 980 1676 980 1677 1011 1677 1012 1677 980 1678 1012 1678 985 1678 985 1679 1012 1679 945 1679 985 1680 945 1680 986 1680 986 1681 945 1681 944 1681 485 1682 1013 1682 625 1682 625 1683 1013 1683 1014 1683 1015 1684 500 1684 1014 1684 1014 1685 500 1685 499 1685 1014 1686 499 1686 625 1686 502 1687 509 1687 1015 1687 1015 1688 509 1688 508 1688 1015 1689 508 1689 500 1689 1016 1690 709 1690 708 1690 1016 1691 708 1691 1015 1691 1015 1692 708 1692 503 1692 1015 1693 503 1693 502 1693 709 1694 1016 1694 710 1694 710 1695 1016 1695 1017 1695 710 1696 1017 1696 639 1696 993 1697 759 1697 992 1697 992 1698 759 1698 653 1698 992 1699 653 1699 1018 1699 1018 1700 653 1700 652 1700 1018 1701 652 1701 1017 1701 1017 1702 652 1702 640 1702 1017 1703 640 1703 639 1703 947 1704 1009 1704 948 1704 948 1705 1009 1705 1007 1705 948 1706 1007 1706 949 1706 949 1707 1007 1707 997 1707 949 1708 997 1708 954 1708 954 1709 997 1709 995 1709 954 1710 995 1710 956 1710 956 1711 995 1711 1002 1711 956 1712 1002 1712 962 1712 962 1713 1002 1713 990 1713 962 1714 990 1714 964 1714 964 1715 990 1715 992 1715 964 1716 992 1716 967 1716 967 1717 992 1717 1018 1717 967 1718 1018 1718 970 1718 970 1719 1018 1719 1017 1719 970 1720 1017 1720 1011 1720 1011 1721 1017 1721 1016 1721 1011 1722 1016 1722 1012 1722 1012 1723 1016 1723 1015 1723 1012 1724 1015 1724 945 1724 945 1725 1015 1725 1014 1725 945 1726 1014 1726 943 1726 943 1727 1014 1727 1013 1727 943 1728 1013 1728 1019 1728 1009 1729 947 1729 1020 1729 1021 1730 1022 1730 1023 1730 1024 1731 1025 1731 1026 1731 984 1732 986 1732 1027 1732 1028 1733 1029 1733 1027 1733 1027 1734 1029 1734 1030 1734 1027 1735 1030 1735 984 1735 984 1736 1030 1736 1031 1736 984 1737 1031 1737 982 1737 1032 1738 1033 1738 1034 1738 1034 1739 1033 1739 1028 1739 1034 1740 1028 1740 1035 1740 1035 1741 1028 1741 1027 1741 1025 1742 1036 1742 1026 1742 1026 1743 1036 1743 1037 1743 1026 1744 1037 1744 1034 1744 1034 1745 1037 1745 1038 1745 1034 1746 1038 1746 1032 1746 1039 1747 1040 1747 1041 1747 1042 1748 1043 1748 1044 1748 1044 1749 1043 1749 1045 1749 1044 1750 1045 1750 1040 1750 1040 1751 1045 1751 1046 1751 1040 1752 1046 1752 1041 1752 1047 1753 1048 1753 1049 1753 1049 1754 1048 1754 1050 1754 1049 1755 1050 1755 1051 1755 1051 1756 1050 1756 1023 1756 1051 1757 1023 1757 1052 1757 1052 1758 1023 1758 1022 1758 1053 1759 1054 1759 1055 1759 1055 1760 1054 1760 1021 1760 1056 1761 1057 1761 1053 1761 946 1762 154 1762 1058 1762 1058 1763 154 1763 1059 1763 1057 1764 1056 1764 1060 1764 1060 1765 1056 1765 1058 1765 1060 1766 1058 1766 1061 1766 1061 1767 1058 1767 1059 1767 1061 1768 1059 1768 1062 1768 426 1769 1063 1769 488 1769 488 1770 1063 1770 1019 1770 488 1771 1019 1771 487 1771 426 1772 378 1772 1063 1772 1063 1773 378 1773 377 1773 1063 1774 377 1774 1064 1774 447 1775 1065 1775 448 1775 448 1776 1065 1776 1064 1776 448 1777 1064 1777 450 1777 450 1778 1064 1778 377 1778 479 1779 1066 1779 490 1779 490 1780 1066 1780 1065 1780 490 1781 1065 1781 491 1781 491 1782 1065 1782 447 1782 487 1783 1019 1783 486 1783 486 1784 1019 1784 1013 1784 486 1785 1013 1785 485 1785 986 1786 944 1786 1027 1786 1027 1787 944 1787 1067 1787 1027 1788 1067 1788 1035 1788 1035 1789 1067 1789 1068 1789 1035 1790 1068 1790 1034 1790 1034 1791 1068 1791 1069 1791 1034 1792 1069 1792 1026 1792 1026 1793 1069 1793 1039 1793 1026 1794 1039 1794 1024 1794 1024 1795 1039 1795 1041 1795 1056 1796 1070 1796 1058 1796 1058 1797 1070 1797 1020 1797 1058 1798 1020 1798 946 1798 946 1799 1020 1799 947 1799 1071 1800 244 1800 249 1800 1053 1801 1055 1801 1056 1801 1056 1802 1055 1802 1071 1802 1056 1803 1071 1803 1070 1803 1070 1804 1071 1804 249 1804 1070 1805 249 1805 248 1805 248 1806 1072 1806 1070 1806 1070 1807 1072 1807 1073 1807 1070 1808 1073 1808 1020 1808 1020 1809 1073 1809 1074 1809 1020 1810 1074 1810 1009 1810 1009 1811 1074 1811 1075 1811 1009 1812 1075 1812 1010 1812 235 1813 178 1813 1048 1813 1048 1814 178 1814 177 1814 1048 1815 177 1815 1050 1815 1050 1816 177 1816 247 1816 1050 1817 247 1817 245 1817 1021 1818 1023 1818 1055 1818 1055 1819 1023 1819 1050 1819 1055 1820 1050 1820 1071 1820 1071 1821 1050 1821 245 1821 1071 1822 245 1822 244 1822 944 1823 943 1823 1067 1823 1067 1824 943 1824 1019 1824 1067 1825 1019 1825 1068 1825 1068 1826 1019 1826 1063 1826 1068 1827 1063 1827 1069 1827 1069 1828 1063 1828 1064 1828 1069 1829 1064 1829 1039 1829 1039 1830 1064 1830 1065 1830 1039 1831 1065 1831 1040 1831 1040 1832 1065 1832 1066 1832 1040 1833 1066 1833 1044 1833 1044 1834 1066 1834 1076 1834 1047 1835 1042 1835 1048 1835 1048 1836 1042 1836 1044 1836 1048 1837 1044 1837 235 1837 235 1838 1044 1838 1076 1838 235 1839 1076 1839 236 1839 236 1840 1076 1840 238 1840 479 1841 478 1841 1066 1841 1066 1842 478 1842 1077 1842 1066 1843 1077 1843 1076 1843 1076 1844 1077 1844 243 1844 1076 1845 243 1845 238 1845 209 1846 208 1846 484 1846 210 1847 216 1847 496 1847 496 1848 216 1848 497 1848 460 1849 376 1849 187 1849 216 1850 218 1850 497 1850 497 1851 218 1851 221 1851 497 1852 221 1852 498 1852 498 1853 221 1853 220 1853 498 1854 220 1854 376 1854 376 1855 220 1855 219 1855 376 1856 219 1856 187 1856 463 1857 230 1857 465 1857 465 1858 230 1858 229 1858 465 1859 229 1859 467 1859 467 1860 229 1860 227 1860 467 1861 227 1861 473 1861 473 1862 227 1862 226 1862 473 1863 226 1863 233 1863 184 1864 477 1864 231 1864 231 1865 477 1865 476 1865 231 1866 476 1866 232 1866 180 1867 471 1867 181 1867 181 1868 471 1868 469 1868 181 1869 469 1869 234 1869 234 1870 469 1870 477 1870 234 1871 477 1871 183 1871 183 1872 477 1872 184 1872 232 1873 476 1873 233 1873 233 1874 476 1874 474 1874 233 1875 474 1875 473 1875 187 1876 186 1876 460 1876 460 1877 186 1877 225 1877 460 1878 225 1878 461 1878 461 1879 225 1879 224 1879 461 1880 224 1880 463 1880 463 1881 224 1881 223 1881 463 1882 223 1882 230 1882 373 1883 1078 1883 481 1883 481 1884 1078 1884 482 1884 1078 1885 198 1885 482 1885 482 1886 198 1886 192 1886 482 1887 192 1887 190 1887 484 1888 208 1888 480 1888 480 1889 208 1889 206 1889 480 1890 206 1890 396 1890 190 1891 189 1891 482 1891 482 1892 189 1892 204 1892 482 1893 204 1893 483 1893 483 1894 204 1894 202 1894 483 1895 202 1895 484 1895 484 1896 202 1896 201 1896 484 1897 201 1897 209 1897 243 1898 1077 1898 242 1898 242 1899 1077 1899 241 1899 1077 1900 478 1900 241 1900 241 1901 478 1901 471 1901 241 1902 471 1902 239 1902 239 1903 471 1903 180 1903 206 1904 215 1904 396 1904 396 1905 215 1905 214 1905 396 1906 214 1906 494 1906 494 1907 214 1907 495 1907 495 1908 214 1908 213 1908 495 1909 213 1909 496 1909 496 1910 213 1910 211 1910 496 1911 211 1911 210 1911 993 1912 991 1912 1079 1912 826 1913 664 1913 665 1913 1080 1914 682 1914 1081 1914 1081 1915 682 1915 681 1915 1081 1916 681 1916 1082 1916 1082 1917 681 1917 1083 1917 681 1918 679 1918 1083 1918 1083 1919 679 1919 677 1919 1083 1920 677 1920 1084 1920 1084 1921 677 1921 676 1921 1084 1922 676 1922 1085 1922 1085 1923 676 1923 1086 1923 1087 1924 765 1924 1088 1924 1088 1925 765 1925 763 1925 1088 1926 763 1926 1089 1926 1089 1927 763 1927 761 1927 1089 1928 761 1928 1090 1928 1090 1929 761 1929 760 1929 1090 1930 760 1930 1091 1930 1091 1931 760 1931 686 1931 1091 1932 686 1932 1080 1932 1080 1933 686 1933 684 1933 1080 1934 684 1934 682 1934 1092 1935 1093 1935 665 1935 665 1936 1093 1936 827 1936 665 1937 827 1937 826 1937 1094 1938 1095 1938 660 1938 660 1939 1095 1939 662 1939 662 1940 1095 1940 1096 1940 662 1941 1096 1941 669 1941 665 1942 666 1942 1092 1942 1092 1943 666 1943 668 1943 1092 1944 668 1944 1097 1944 1097 1945 668 1945 669 1945 1097 1946 669 1946 1098 1946 1098 1947 669 1947 1096 1947 759 1948 993 1948 758 1948 758 1949 993 1949 1079 1949 758 1950 1079 1950 757 1950 757 1951 1079 1951 1099 1951 757 1952 1099 1952 675 1952 675 1953 1099 1953 1100 1953 675 1954 1100 1954 673 1954 673 1955 1100 1955 1086 1955 673 1956 1086 1956 672 1956 672 1957 1086 1957 676 1957 660 1958 644 1958 1094 1958 1094 1959 644 1959 643 1959 1094 1960 643 1960 1101 1960 1101 1961 643 1961 768 1961 1101 1962 768 1962 1087 1962 1087 1963 768 1963 767 1963 1087 1964 767 1964 765 1964 1074 1965 1073 1965 1102 1965 1103 1966 1104 1966 1105 1966 1106 1967 1107 1967 1108 1967 264 1968 262 1968 1109 1968 1110 1969 1111 1969 1112 1969 1113 1970 1114 1970 1115 1970 305 1971 304 1971 1116 1971 348 1972 197 1972 847 1972 348 1973 847 1973 306 1973 310 1974 309 1974 1117 1974 1117 1975 309 1975 307 1975 1117 1976 307 1976 306 1976 1118 1977 918 1977 926 1977 844 1978 920 1978 1118 1978 1118 1979 920 1979 919 1979 1118 1980 919 1980 918 1980 306 1981 847 1981 1117 1981 1117 1982 847 1982 845 1982 1117 1983 845 1983 310 1983 304 1984 302 1984 1119 1984 1119 1985 302 1985 1118 1985 1119 1986 1118 1986 1105 1986 1105 1987 1118 1987 926 1987 845 1988 844 1988 310 1988 310 1989 844 1989 1118 1989 310 1990 1118 1990 301 1990 301 1991 1118 1991 302 1991 1120 1992 1121 1992 1122 1992 1122 1993 1121 1993 292 1993 1123 1994 292 1994 1124 1994 1124 1995 292 1995 1121 1995 1124 1996 1121 1996 1125 1996 1125 1997 1121 1997 1126 1997 298 1998 294 1998 299 1998 299 1999 294 1999 1116 1999 1127 2000 1126 2000 1128 2000 1128 2001 1126 2001 1121 2001 1128 2002 1121 2002 1129 2002 1129 2003 1121 2003 1120 2003 1129 2004 1120 2004 1130 2004 358 2005 305 2005 297 2005 297 2006 305 2006 1116 2006 297 2007 1116 2007 296 2007 296 2008 1116 2008 294 2008 1131 2009 1132 2009 1133 2009 1133 2010 1132 2010 1134 2010 1133 2011 1134 2011 1127 2011 1135 2012 1136 2012 1137 2012 1137 2013 1136 2013 1134 2013 1137 2014 1134 2014 1138 2014 1138 2015 1134 2015 1132 2015 1138 2016 1132 2016 1139 2016 1139 2017 1132 2017 1131 2017 1139 2018 1131 2018 1114 2018 1115 2019 1140 2019 1113 2019 1113 2020 1140 2020 1141 2020 1113 2021 1141 2021 1142 2021 1142 2022 1141 2022 1143 2022 1142 2023 1143 2023 1144 2023 1144 2024 1143 2024 1145 2024 1146 2025 1110 2025 1135 2025 1135 2026 1110 2026 1112 2026 1135 2027 1112 2027 1136 2027 1114 2028 1113 2028 1139 2028 1139 2029 1113 2029 1142 2029 1139 2030 1142 2030 1138 2030 1138 2031 1142 2031 1144 2031 1138 2032 1144 2032 1137 2032 1137 2033 1144 2033 1145 2033 1137 2034 1145 2034 1135 2034 1135 2035 1145 2035 1147 2035 1135 2036 1147 2036 1146 2036 1127 2037 1134 2037 1126 2037 1126 2038 1134 2038 1136 2038 1126 2039 1136 2039 1125 2039 1125 2040 1136 2040 1112 2040 1125 2041 1112 2041 1124 2041 1124 2042 1112 2042 1111 2042 1124 2043 1111 2043 1123 2043 1148 2044 1149 2044 1150 2044 1150 2045 1149 2045 1151 2045 1152 2046 1153 2046 1154 2046 1154 2047 1153 2047 1155 2047 1156 2048 1152 2048 1157 2048 1157 2049 1152 2049 1154 2049 1157 2050 1154 2050 1158 2050 1159 2051 1160 2051 1158 2051 1158 2052 1160 2052 1161 2052 1158 2053 1161 2053 1157 2053 1157 2054 1161 2054 1162 2054 1157 2055 1162 2055 1156 2055 1148 2056 1150 2056 1163 2056 1163 2057 1150 2057 1164 2057 1163 2058 1164 2058 1165 2058 1166 2059 280 2059 1167 2059 1167 2060 280 2060 283 2060 1167 2061 283 2061 282 2061 1168 2062 1169 2062 1170 2062 1170 2063 1169 2063 1171 2063 273 2064 271 2064 1172 2064 266 2065 265 2065 1173 2065 1173 2066 265 2066 274 2066 1173 2067 274 2067 1170 2067 1170 2068 274 2068 273 2068 1170 2069 273 2069 1168 2069 1168 2070 273 2070 1172 2070 1168 2071 1172 2071 1169 2071 1169 2072 1172 2072 1174 2072 259 2073 257 2073 1175 2073 1175 2074 257 2074 255 2074 1175 2075 255 2075 1109 2075 1109 2076 255 2076 319 2076 1109 2077 319 2077 264 2077 262 2078 261 2078 1109 2078 1109 2079 261 2079 269 2079 1109 2080 269 2080 1173 2080 1173 2081 269 2081 268 2081 1173 2082 268 2082 266 2082 1167 2083 1165 2083 1166 2083 1166 2084 1165 2084 1164 2084 1166 2085 1164 2085 1174 2085 1174 2086 1164 2086 1150 2086 1174 2087 1150 2087 1169 2087 1169 2088 1150 2088 1151 2088 1169 2089 1151 2089 1171 2089 271 2090 270 2090 1172 2090 1172 2091 270 2091 275 2091 1172 2092 275 2092 1174 2092 1174 2093 275 2093 277 2093 1174 2094 277 2094 1166 2094 1166 2095 277 2095 278 2095 1166 2096 278 2096 280 2096 1073 2097 1072 2097 1102 2097 1102 2098 1072 2098 1175 2098 1102 2099 1175 2099 1176 2099 1176 2100 1175 2100 1109 2100 1176 2101 1109 2101 1177 2101 1177 2102 1109 2102 1173 2102 1177 2103 1173 2103 1178 2103 1179 2104 1180 2104 1181 2104 1181 2105 1180 2105 1182 2105 1181 2106 1182 2106 1183 2106 1107 2107 1184 2107 1108 2107 1108 2108 1184 2108 1185 2108 1108 2109 1185 2109 1182 2109 1182 2110 1185 2110 1186 2110 1182 2111 1186 2111 1183 2111 1187 2112 1188 2112 1189 2112 1189 2113 1188 2113 1190 2113 1180 2114 1191 2114 1182 2114 1182 2115 1191 2115 1187 2115 1182 2116 1187 2116 1108 2116 1108 2117 1187 2117 1189 2117 1108 2118 1189 2118 1106 2118 1106 2119 1189 2119 1190 2119 1106 2120 1190 2120 1192 2120 1193 2121 1194 2121 1195 2121 1010 2122 1075 2122 1196 2122 1193 2123 1195 2123 1196 2123 1196 2124 1195 2124 1197 2124 1196 2125 1197 2125 1010 2125 1192 2126 1194 2126 1106 2126 1106 2127 1194 2127 1193 2127 1106 2128 1193 2128 1107 2128 1107 2129 1193 2129 1198 2129 1107 2130 1198 2130 1184 2130 1184 2131 1198 2131 1199 2131 1184 2132 1199 2132 1185 2132 1185 2133 1199 2133 1200 2133 1185 2134 1200 2134 1186 2134 1186 2135 1200 2135 1201 2135 1186 2136 1201 2136 1183 2136 929 2137 928 2137 1103 2137 926 2138 925 2138 1105 2138 1105 2139 925 2139 924 2139 1105 2140 924 2140 1103 2140 1103 2141 924 2141 923 2141 1103 2142 923 2142 929 2142 1104 2143 1202 2143 1105 2143 1105 2144 1202 2144 1130 2144 1105 2145 1130 2145 1119 2145 1119 2146 1130 2146 1120 2146 1119 2147 1120 2147 304 2147 304 2148 1120 2148 1122 2148 304 2149 1122 2149 1116 2149 1116 2150 1122 2150 292 2150 1116 2151 292 2151 299 2151 248 2152 250 2152 1072 2152 1072 2153 250 2153 252 2153 1072 2154 252 2154 1175 2154 1175 2155 252 2155 260 2155 1175 2156 260 2156 259 2156 1159 2157 286 2157 1160 2157 1160 2158 286 2158 285 2158 1160 2159 285 2159 1161 2159 1161 2160 285 2160 289 2160 1161 2161 289 2161 288 2161 1147 2162 1155 2162 1146 2162 1146 2163 1155 2163 1153 2163 1146 2164 1153 2164 1110 2164 1110 2165 1153 2165 1152 2165 1110 2166 1152 2166 1111 2166 1111 2167 1152 2167 1156 2167 1111 2168 1156 2168 1123 2168 1123 2169 1156 2169 1162 2169 1123 2170 1162 2170 292 2170 292 2171 1162 2171 1161 2171 292 2172 1161 2172 290 2172 290 2173 1161 2173 288 2173 290 2174 288 2174 287 2174 1075 2175 1074 2175 1196 2175 1196 2176 1074 2176 1102 2176 1196 2177 1102 2177 1193 2177 1193 2178 1102 2178 1176 2178 1193 2179 1176 2179 1198 2179 1198 2180 1176 2180 1177 2180 1198 2181 1177 2181 1199 2181 1199 2182 1177 2182 1178 2182 1199 2183 1178 2183 1200 2183 1200 2184 1178 2184 1203 2184 1200 2185 1203 2185 1201 2185 1201 2186 1203 2186 1204 2186 1201 2187 1204 2187 1183 2187 1183 2188 1204 2188 1205 2188 1183 2189 1205 2189 1181 2189 1181 2190 1205 2190 1206 2190 1181 2191 1206 2191 1179 2191 1179 2192 1206 2192 1207 2192 1202 2193 1208 2193 1130 2193 1130 2194 1208 2194 1209 2194 1130 2195 1209 2195 1129 2195 1129 2196 1209 2196 1210 2196 1129 2197 1210 2197 1128 2197 1128 2198 1210 2198 1211 2198 1128 2199 1211 2199 1212 2199 1212 2200 1207 2200 1128 2200 1128 2201 1207 2201 1206 2201 1128 2202 1206 2202 1127 2202 1127 2203 1206 2203 1205 2203 1127 2204 1205 2204 1133 2204 1133 2205 1205 2205 1204 2205 1133 2206 1204 2206 1131 2206 1131 2207 1204 2207 1203 2207 1131 2208 1203 2208 1114 2208 1114 2209 1203 2209 1178 2209 1114 2210 1178 2210 1115 2210 1115 2211 1178 2211 1173 2211 1115 2212 1173 2212 1140 2212 1140 2213 1173 2213 1170 2213 1140 2214 1170 2214 1141 2214 1141 2215 1170 2215 1171 2215 1141 2216 1171 2216 1143 2216 1143 2217 1171 2217 1151 2217 1143 2218 1151 2218 1145 2218 1145 2219 1151 2219 1149 2219 1145 2220 1149 2220 1147 2220 1147 2221 1149 2221 1148 2221 1147 2222 1148 2222 1155 2222 1155 2223 1148 2223 1163 2223 1155 2224 1163 2224 1154 2224 1154 2225 1163 2225 1165 2225 1154 2226 1165 2226 1158 2226 1158 2227 1165 2227 1167 2227 1158 2228 1167 2228 1159 2228 1159 2229 1167 2229 282 2229 1159 2230 282 2230 286 2230 1003 2231 1001 2231 1213 2231 1214 2232 836 2232 827 2232 1005 2233 1004 2233 1215 2233 1216 2234 1217 2234 1218 2234 1202 2235 1104 2235 1214 2235 836 2236 1214 2236 835 2236 1103 2237 928 2237 927 2237 835 2238 1214 2238 927 2238 927 2239 1214 2239 1104 2239 927 2240 1104 2240 1103 2240 1219 2241 1220 2241 1221 2241 1221 2242 1220 2242 1222 2242 1221 2243 1222 2243 1223 2243 1223 2244 1222 2244 1224 2244 1223 2245 1224 2245 1225 2245 1226 2246 1220 2246 1208 2246 1208 2247 1220 2247 1219 2247 1208 2248 1219 2248 1209 2248 1209 2249 1219 2249 1210 2249 1191 2250 1180 2250 1227 2250 1227 2251 1180 2251 1179 2251 1227 2252 1179 2252 1228 2252 1228 2253 1179 2253 1207 2253 1228 2254 1207 2254 1212 2254 1197 2255 1195 2255 1229 2255 1229 2256 1195 2256 1230 2256 1229 2257 1230 2257 1231 2257 996 2258 998 2258 1231 2258 994 2259 996 2259 1232 2259 1232 2260 996 2260 1231 2260 1232 2261 1231 2261 1233 2261 1233 2262 1231 2262 1234 2262 1233 2263 1234 2263 1235 2263 1235 2264 1234 2264 1236 2264 1235 2265 1236 2265 1237 2265 1237 2266 1236 2266 1238 2266 1237 2267 1238 2267 1239 2267 1239 2268 1238 2268 1240 2268 1239 2269 1240 2269 1218 2269 1195 2270 1194 2270 1230 2270 1230 2271 1194 2271 1192 2271 1230 2272 1192 2272 1241 2272 1241 2273 1192 2273 1190 2273 1241 2274 1190 2274 1242 2274 1242 2275 1190 2275 1188 2275 1242 2276 1188 2276 1187 2276 1231 2277 1230 2277 1234 2277 1234 2278 1230 2278 1241 2278 1234 2279 1241 2279 1236 2279 1236 2280 1241 2280 1242 2280 1236 2281 1242 2281 1238 2281 1238 2282 1242 2282 1187 2282 1238 2283 1187 2283 1240 2283 1218 2284 1217 2284 1239 2284 1239 2285 1217 2285 1243 2285 1239 2286 1243 2286 1237 2286 1237 2287 1243 2287 1244 2287 1237 2288 1244 2288 1235 2288 1235 2289 1244 2289 1245 2289 1235 2290 1245 2290 1233 2290 1233 2291 1245 2291 1246 2291 1233 2292 1246 2292 1232 2292 1232 2293 1246 2293 1247 2293 1232 2294 1247 2294 1213 2294 1213 2295 1001 2295 1232 2295 1232 2296 1001 2296 1000 2296 1232 2297 1000 2297 994 2297 1248 2298 1089 2298 1249 2298 1249 2299 1089 2299 1090 2299 1249 2300 1090 2300 1250 2300 1250 2301 1090 2301 1091 2301 1250 2302 1091 2302 1251 2302 1251 2303 1091 2303 1080 2303 1251 2304 1080 2304 1252 2304 1252 2305 1080 2305 1081 2305 1253 2306 1085 2306 1086 2306 1253 2307 1086 2307 1254 2307 1081 2308 1082 2308 1252 2308 1252 2309 1082 2309 1083 2309 1252 2310 1083 2310 1253 2310 1253 2311 1083 2311 1084 2311 1253 2312 1084 2312 1085 2312 991 2313 1005 2313 1079 2313 1079 2314 1005 2314 1215 2314 1079 2315 1215 2315 1099 2315 1099 2316 1215 2316 1254 2316 1099 2317 1254 2317 1100 2317 1100 2318 1254 2318 1086 2318 827 2319 1093 2319 1214 2319 1214 2320 1093 2320 1226 2320 1214 2321 1226 2321 1202 2321 1202 2322 1226 2322 1208 2322 1010 2323 1197 2323 1008 2323 1008 2324 1197 2324 1229 2324 1008 2325 1229 2325 1006 2325 1006 2326 1229 2326 1231 2326 1006 2327 1231 2327 999 2327 999 2328 1231 2328 998 2328 1210 2329 1219 2329 1211 2329 1211 2330 1219 2330 1221 2330 1211 2331 1221 2331 1212 2331 1212 2332 1221 2332 1223 2332 1212 2333 1223 2333 1228 2333 1228 2334 1223 2334 1225 2334 1228 2335 1225 2335 1227 2335 1004 2336 1003 2336 1215 2336 1215 2337 1003 2337 1213 2337 1215 2338 1213 2338 1254 2338 1254 2339 1213 2339 1247 2339 1254 2340 1247 2340 1253 2340 1253 2341 1247 2341 1246 2341 1253 2342 1246 2342 1252 2342 1252 2343 1246 2343 1245 2343 1252 2344 1245 2344 1251 2344 1251 2345 1245 2345 1244 2345 1251 2346 1244 2346 1250 2346 1250 2347 1244 2347 1243 2347 1250 2348 1243 2348 1249 2348 1249 2349 1243 2349 1217 2349 1249 2350 1217 2350 1248 2350 1248 2351 1217 2351 1216 2351 1248 2352 1216 2352 1255 2352 1093 2353 1092 2353 1226 2353 1226 2354 1092 2354 1097 2354 1226 2355 1097 2355 1220 2355 1220 2356 1097 2356 1098 2356 1220 2357 1098 2357 1222 2357 1222 2358 1098 2358 1096 2358 1222 2359 1096 2359 1095 2359 1094 2360 1101 2360 1255 2360 1255 2361 1101 2361 1087 2361 1255 2362 1087 2362 1248 2362 1248 2363 1087 2363 1088 2363 1248 2364 1088 2364 1089 2364 1095 2365 1094 2365 1222 2365 1222 2366 1094 2366 1255 2366 1222 2367 1255 2367 1224 2367 1224 2368 1255 2368 1216 2368 1224 2369 1216 2369 1225 2369 1225 2370 1216 2370 1218 2370 1225 2371 1218 2371 1227 2371 1227 2372 1218 2372 1240 2372 1227 2373 1240 2373 1191 2373 1191 2374 1240 2374 1187 2374 1256 2375 1257 2375 1258 2375 1259 2376 1260 2376 1261 2376 1262 2377 1263 2377 1264 2377 1265 2378 1266 2378 1267 2378 1268 2379 1269 2379 1270 2379 1271 2380 1272 2380 1273 2380 1273 2381 1272 2381 1274 2381 1273 2382 1274 2382 1275 2382 1276 2383 1277 2383 1278 2383 1278 2384 1279 2384 1276 2384 1276 2385 1279 2385 1280 2385 1276 2386 1280 2386 1281 2386 1270 2387 1269 2387 1280 2387 1280 2388 1269 2388 1282 2388 1280 2389 1282 2389 1281 2389 1283 2390 1284 2390 1285 2390 1283 2391 1285 2391 1286 2391 1285 2392 1287 2392 1286 2392 1286 2393 1287 2393 1288 2393 1286 2394 1288 2394 1270 2394 1270 2395 1288 2395 1289 2395 1270 2396 1289 2396 1268 2396 1290 2397 1291 2397 1292 2397 1292 2398 1291 2398 1293 2398 1294 2399 1295 2399 1296 2399 1296 2400 1295 2400 1297 2400 1296 2401 1297 2401 1292 2401 1292 2402 1297 2402 1298 2402 1292 2403 1298 2403 1290 2403 1299 2404 1300 2404 1301 2404 1302 2405 1303 2405 1299 2405 1303 2406 1304 2406 1299 2406 1299 2407 1304 2407 1305 2407 1299 2408 1305 2408 1300 2408 1306 2409 1307 2409 1308 2409 1308 2410 1307 2410 1309 2410 1308 2411 1309 2411 1310 2411 1310 2412 1309 2412 1311 2412 1310 2413 1311 2413 1312 2413 1313 2414 1314 2414 1315 2414 1315 2415 1314 2415 1316 2415 1315 2416 1316 2416 1317 2416 1313 2417 1318 2417 1314 2417 1314 2418 1318 2418 1319 2418 1314 2419 1319 2419 1308 2419 1308 2420 1319 2420 1320 2420 1308 2421 1320 2421 1306 2421 1267 2422 1266 2422 1316 2422 1316 2423 1266 2423 1321 2423 1316 2424 1321 2424 1317 2424 1322 2425 1323 2425 1324 2425 1265 2426 1267 2426 1325 2426 1325 2427 1267 2427 1326 2427 1325 2428 1326 2428 1327 2428 1327 2429 1326 2429 1322 2429 1327 2430 1322 2430 1328 2430 1328 2431 1322 2431 1324 2431 1328 2432 1324 2432 1329 2432 1330 2433 1331 2433 1332 2433 1332 2434 1331 2434 1333 2434 1330 2435 1334 2435 1335 2435 1335 2436 1334 2436 1336 2436 1337 2437 1338 2437 1339 2437 1340 2438 1338 2438 1341 2438 1341 2439 1338 2439 1337 2439 1341 2440 1337 2440 1342 2440 1342 2441 1337 2441 1264 2441 1342 2442 1264 2442 1343 2442 1343 2443 1264 2443 1263 2443 1344 2444 1345 2444 1346 2444 1346 2445 1345 2445 1347 2445 1346 2446 1347 2446 1348 2446 1349 2447 1350 2447 1351 2447 1346 2448 1352 2448 1344 2448 1344 2449 1352 2449 1349 2449 1344 2450 1349 2450 1353 2450 1353 2451 1349 2451 1351 2451 1352 2452 1354 2452 1349 2452 1349 2453 1354 2453 1355 2453 1349 2454 1355 2454 1261 2454 1260 2455 1356 2455 1261 2455 1261 2456 1356 2456 1357 2456 1261 2457 1357 2457 1349 2457 1349 2458 1357 2458 1358 2458 1349 2459 1358 2459 1350 2459 1359 2460 1360 2460 1259 2460 1361 2461 1362 2461 1363 2461 1364 2462 1365 2462 1366 2462 1366 2463 1365 2463 1367 2463 1366 2464 1367 2464 1361 2464 1361 2465 1367 2465 1368 2465 1361 2466 1368 2466 1362 2466 1369 2467 1370 2467 1371 2467 1371 2468 1370 2468 1372 2468 1373 2469 1374 2469 1366 2469 1366 2470 1374 2470 1375 2470 1366 2471 1375 2471 1364 2471 1376 2472 1377 2472 1371 2472 1371 2473 1377 2473 1378 2473 1371 2474 1378 2474 1369 2474 1379 2475 1380 2475 1381 2475 1381 2476 1380 2476 1382 2476 1381 2477 1382 2477 1258 2477 1258 2478 1382 2478 1383 2478 1258 2479 1383 2479 1256 2479 1278 2480 1384 2480 1279 2480 1279 2481 1384 2481 1385 2481 1279 2482 1385 2482 1280 2482 1280 2483 1385 2483 1386 2483 1280 2484 1386 2484 1270 2484 1270 2485 1386 2485 1387 2485 1270 2486 1387 2486 1286 2486 1286 2487 1387 2487 1388 2487 1286 2488 1388 2488 1283 2488 1283 2489 1388 2489 1389 2489 1390 2490 1296 2490 1389 2490 1389 2491 1296 2491 1292 2491 1389 2492 1292 2492 1283 2492 1283 2493 1292 2493 1293 2493 1283 2494 1293 2494 1284 2494 1391 2495 1392 2495 1393 2495 1393 2496 1392 2496 1394 2496 1393 2497 1394 2497 1395 2497 1395 2498 1394 2498 1396 2498 1395 2499 1396 2499 1397 2499 1397 2500 1396 2500 1398 2500 1397 2501 1398 2501 1399 2501 1399 2502 1398 2502 1400 2502 1399 2503 1400 2503 1401 2503 1310 2504 1391 2504 1308 2504 1308 2505 1391 2505 1393 2505 1308 2506 1393 2506 1314 2506 1314 2507 1393 2507 1395 2507 1314 2508 1395 2508 1316 2508 1316 2509 1395 2509 1397 2509 1316 2510 1397 2510 1267 2510 1267 2511 1397 2511 1399 2511 1267 2512 1399 2512 1326 2512 1326 2513 1399 2513 1401 2513 1326 2514 1401 2514 1322 2514 1348 2515 1402 2515 1346 2515 1346 2516 1402 2516 1403 2516 1346 2517 1403 2517 1352 2517 1352 2518 1403 2518 1404 2518 1352 2519 1404 2519 1354 2519 1354 2520 1404 2520 1405 2520 1354 2521 1405 2521 1355 2521 1355 2522 1405 2522 1406 2522 1407 2523 1262 2523 1408 2523 1408 2524 1262 2524 1264 2524 1408 2525 1264 2525 1409 2525 1409 2526 1264 2526 1337 2526 1409 2527 1337 2527 1334 2527 1334 2528 1337 2528 1339 2528 1334 2529 1339 2529 1336 2529 1330 2530 1332 2530 1334 2530 1334 2531 1332 2531 1410 2531 1334 2532 1410 2532 1409 2532 1409 2533 1410 2533 1403 2533 1409 2534 1403 2534 1408 2534 1408 2535 1403 2535 1402 2535 1408 2536 1402 2536 1407 2536 1312 2537 1302 2537 1310 2537 1310 2538 1302 2538 1299 2538 1310 2539 1299 2539 1391 2539 1391 2540 1299 2540 1411 2540 1391 2541 1411 2541 1392 2541 1392 2542 1411 2542 1406 2542 1392 2543 1406 2543 1394 2543 1394 2544 1406 2544 1405 2544 1394 2545 1405 2545 1396 2545 1396 2546 1405 2546 1404 2546 1396 2547 1404 2547 1398 2547 1398 2548 1404 2548 1403 2548 1398 2549 1403 2549 1400 2549 1400 2550 1403 2550 1410 2550 1400 2551 1410 2551 1401 2551 1401 2552 1410 2552 1332 2552 1401 2553 1332 2553 1322 2553 1322 2554 1332 2554 1333 2554 1322 2555 1333 2555 1323 2555 1259 2556 1261 2556 1359 2556 1359 2557 1261 2557 1355 2557 1359 2558 1355 2558 1412 2558 1412 2559 1355 2559 1406 2559 1412 2560 1406 2560 1413 2560 1413 2561 1406 2561 1411 2561 1413 2562 1411 2562 1390 2562 1390 2563 1411 2563 1299 2563 1390 2564 1299 2564 1296 2564 1296 2565 1299 2565 1301 2565 1296 2566 1301 2566 1294 2566 1275 2567 1414 2567 1273 2567 1273 2568 1414 2568 1379 2568 1273 2569 1379 2569 1415 2569 1415 2570 1379 2570 1381 2570 1415 2571 1381 2571 1416 2571 1416 2572 1381 2572 1258 2572 1416 2573 1258 2573 1417 2573 1417 2574 1258 2574 1418 2574 1417 2575 1418 2575 1419 2575 1419 2576 1418 2576 1366 2576 1419 2577 1366 2577 1420 2577 1420 2578 1366 2578 1361 2578 1420 2579 1361 2579 1421 2579 1257 2580 1422 2580 1258 2580 1258 2581 1422 2581 1376 2581 1258 2582 1376 2582 1418 2582 1418 2583 1376 2583 1371 2583 1418 2584 1371 2584 1366 2584 1366 2585 1371 2585 1372 2585 1366 2586 1372 2586 1373 2586 1277 2587 1423 2587 1278 2587 1278 2588 1423 2588 1424 2588 1278 2589 1424 2589 1384 2589 1384 2590 1424 2590 1271 2590 1384 2591 1271 2591 1385 2591 1385 2592 1271 2592 1273 2592 1385 2593 1273 2593 1386 2593 1386 2594 1273 2594 1415 2594 1386 2595 1415 2595 1387 2595 1387 2596 1415 2596 1416 2596 1387 2597 1416 2597 1388 2597 1388 2598 1416 2598 1417 2598 1388 2599 1417 2599 1389 2599 1389 2600 1417 2600 1419 2600 1389 2601 1419 2601 1390 2601 1390 2602 1419 2602 1420 2602 1390 2603 1420 2603 1413 2603 1413 2604 1420 2604 1421 2604 1413 2605 1421 2605 1412 2605 1412 2606 1421 2606 1361 2606 1412 2607 1361 2607 1359 2607 1359 2608 1361 2608 1363 2608 1359 2609 1363 2609 1360 2609 1425 2610 1426 2610 1427 2610 1428 2611 1429 2611 1430 2611 1431 2612 1432 2612 1433 2612 1433 2613 1432 2613 1434 2613 1435 2614 1436 2614 1437 2614 1438 2615 1439 2615 1440 2615 1441 2616 1442 2616 1443 2616 1443 2617 1442 2617 1444 2617 1443 2618 1444 2618 1445 2618 1446 2619 1438 2619 1447 2619 1447 2620 1438 2620 1440 2620 1447 2621 1440 2621 1448 2621 1439 2622 1449 2622 1450 2622 1450 2623 1449 2623 1451 2623 1450 2624 1451 2624 1452 2624 1453 2625 1441 2625 1454 2625 1454 2626 1441 2626 1443 2626 1454 2627 1443 2627 1455 2627 1455 2628 1443 2628 1452 2628 1455 2629 1452 2629 1456 2629 1456 2630 1452 2630 1451 2630 1457 2631 1436 2631 1458 2631 1458 2632 1436 2632 1435 2632 1458 2633 1435 2633 1459 2633 1459 2634 1435 2634 1460 2634 1461 2635 1460 2635 1462 2635 1462 2636 1460 2636 1435 2636 1462 2637 1435 2637 1463 2637 1463 2638 1435 2638 1437 2638 1463 2639 1437 2639 1464 2639 1465 2640 1466 2640 1467 2640 1468 2641 1469 2641 1470 2641 1470 2642 1469 2642 1471 2642 1470 2643 1471 2643 1472 2643 1472 2644 1471 2644 1473 2644 1472 2645 1473 2645 1467 2645 1467 2646 1473 2646 1474 2646 1467 2647 1474 2647 1465 2647 1465 2648 1475 2648 1466 2648 1466 2649 1475 2649 1476 2649 1466 2650 1476 2650 1477 2650 1477 2651 1476 2651 1478 2651 1477 2652 1478 2652 1479 2652 1429 2653 1480 2653 1430 2653 1430 2654 1480 2654 1481 2654 1430 2655 1481 2655 1482 2655 1482 2656 1481 2656 1483 2656 1482 2657 1483 2657 1484 2657 1484 2658 1483 2658 1485 2658 1484 2659 1485 2659 1486 2659 1486 2660 1485 2660 1487 2660 1486 2661 1487 2661 1488 2661 1488 2662 1487 2662 1489 2662 1488 2663 1489 2663 1490 2663 1490 2664 1489 2664 1491 2664 1490 2665 1491 2665 1492 2665 1492 2666 1491 2666 1493 2666 1492 2667 1493 2667 1494 2667 1432 2668 1494 2668 1434 2668 1434 2669 1494 2669 1493 2669 1434 2670 1493 2670 1495 2670 1495 2671 1493 2671 1491 2671 1495 2672 1491 2672 1479 2672 1479 2673 1491 2673 1489 2673 1479 2674 1489 2674 1477 2674 1477 2675 1489 2675 1487 2675 1477 2676 1487 2676 1466 2676 1466 2677 1487 2677 1485 2677 1466 2678 1485 2678 1467 2678 1467 2679 1485 2679 1483 2679 1467 2680 1483 2680 1472 2680 1472 2681 1483 2681 1481 2681 1472 2682 1481 2682 1470 2682 1496 2683 1433 2683 1497 2683 1497 2684 1433 2684 1434 2684 1497 2685 1434 2685 1498 2685 1498 2686 1434 2686 1495 2686 1498 2687 1495 2687 1499 2687 1499 2688 1495 2688 1479 2688 1499 2689 1479 2689 1500 2689 1500 2690 1479 2690 1478 2690 1501 2691 1502 2691 1503 2691 1503 2692 1502 2692 1504 2692 1504 2693 1428 2693 1503 2693 1503 2694 1428 2694 1430 2694 1503 2695 1430 2695 1505 2695 1505 2696 1430 2696 1482 2696 1505 2697 1482 2697 1506 2697 1506 2698 1482 2698 1484 2698 1506 2699 1484 2699 1507 2699 1507 2700 1484 2700 1486 2700 1507 2701 1486 2701 1508 2701 1508 2702 1486 2702 1488 2702 1508 2703 1488 2703 1509 2703 1509 2704 1488 2704 1490 2704 1509 2705 1490 2705 1510 2705 1510 2706 1490 2706 1492 2706 1510 2707 1492 2707 1511 2707 1511 2708 1492 2708 1494 2708 1511 2709 1494 2709 1512 2709 1512 2710 1494 2710 1432 2710 1512 2711 1432 2711 1513 2711 1513 2712 1432 2712 1431 2712 1427 2713 1514 2713 1425 2713 1425 2714 1514 2714 1515 2714 1425 2715 1515 2715 1516 2715 1516 2716 1515 2716 1517 2716 1516 2717 1517 2717 1518 2717 1518 2718 1517 2718 1519 2718 1518 2719 1519 2719 1520 2719 1520 2720 1519 2720 1521 2720 1522 2721 1523 2721 1524 2721 1524 2722 1523 2722 1525 2722 1524 2723 1525 2723 1526 2723 1521 2724 1527 2724 1520 2724 1520 2725 1527 2725 1528 2725 1520 2726 1528 2726 1529 2726 1529 2727 1528 2727 1530 2727 1529 2728 1530 2728 1522 2728 1522 2729 1530 2729 1531 2729 1522 2730 1531 2730 1523 2730 1525 2731 1532 2731 1533 2731 1439 2732 1450 2732 1440 2732 1440 2733 1450 2733 1534 2733 1440 2734 1534 2734 1448 2734 1445 2735 1535 2735 1443 2735 1443 2736 1535 2736 1536 2736 1443 2737 1536 2737 1452 2737 1452 2738 1536 2738 1537 2738 1452 2739 1537 2739 1450 2739 1450 2740 1537 2740 1538 2740 1450 2741 1538 2741 1534 2741 1539 2742 1468 2742 1540 2742 1540 2743 1468 2743 1470 2743 1540 2744 1470 2744 1541 2744 1541 2745 1470 2745 1481 2745 1541 2746 1481 2746 1542 2746 1542 2747 1481 2747 1480 2747 1457 2748 1543 2748 1436 2748 1436 2749 1543 2749 1446 2749 1436 2750 1446 2750 1437 2750 1437 2751 1446 2751 1447 2751 1437 2752 1447 2752 1464 2752 1525 2753 1533 2753 1526 2753 1526 2754 1533 2754 1544 2754 1526 2755 1544 2755 1545 2755 1545 2756 1501 2756 1526 2756 1526 2757 1501 2757 1503 2757 1526 2758 1503 2758 1524 2758 1524 2759 1503 2759 1505 2759 1524 2760 1505 2760 1522 2760 1522 2761 1505 2761 1506 2761 1522 2762 1506 2762 1529 2762 1529 2763 1506 2763 1507 2763 1529 2764 1507 2764 1520 2764 1520 2765 1507 2765 1508 2765 1520 2766 1508 2766 1518 2766 1518 2767 1508 2767 1509 2767 1518 2768 1509 2768 1516 2768 1516 2769 1509 2769 1510 2769 1516 2770 1510 2770 1425 2770 1425 2771 1510 2771 1511 2771 1425 2772 1511 2772 1426 2772 1426 2773 1511 2773 1512 2773 1426 2774 1512 2774 1546 2774 1546 2775 1512 2775 1513 2775 1546 2776 1513 2776 1547 2776 1548 2777 1549 2777 1547 2777 1547 2778 1549 2778 1550 2778 1547 2779 1550 2779 1546 2779 1546 2780 1550 2780 1551 2780 1546 2781 1551 2781 1426 2781 1426 2782 1551 2782 1552 2782 1426 2783 1552 2783 1427 2783 1448 2784 1548 2784 1447 2784 1447 2785 1548 2785 1547 2785 1447 2786 1547 2786 1464 2786 1464 2787 1547 2787 1513 2787 1464 2788 1513 2788 1463 2788 1463 2789 1513 2789 1431 2789 1463 2790 1431 2790 1462 2790 1462 2791 1431 2791 1433 2791 1462 2792 1433 2792 1461 2792 1461 2793 1433 2793 1496 2793 1553 2794 1554 2794 1555 2794 1556 2795 1557 2795 1558 2795 1559 2796 1560 2796 1561 2796 1562 2797 1563 2797 1564 2797 1565 2798 1566 2798 1567 2798 1566 2799 1565 2799 1568 2799 1569 2800 1570 2800 1571 2800 1572 2801 1573 2801 1574 2801 1575 2802 1576 2802 1577 2802 1578 2803 1579 2803 1580 2803 1580 2804 1579 2804 1581 2804 1582 2805 1579 2805 1583 2805 1583 2806 1579 2806 1584 2806 1582 2807 1585 2807 1579 2807 1579 2808 1585 2808 1586 2808 1579 2809 1586 2809 1581 2809 1587 2810 1588 2810 1589 2810 1589 2811 1588 2811 1590 2811 1589 2812 1590 2812 1591 2812 1591 2813 1590 2813 1592 2813 1591 2814 1592 2814 1579 2814 1593 2815 1589 2815 1594 2815 1594 2816 1589 2816 1591 2816 1594 2817 1591 2817 1595 2817 1595 2818 1591 2818 1579 2818 1595 2819 1579 2819 1596 2819 1596 2820 1579 2820 1578 2820 1597 2821 1598 2821 1599 2821 1599 2822 1598 2822 1600 2822 1599 2823 1600 2823 1601 2823 1602 2824 1603 2824 1604 2824 1604 2825 1603 2825 1605 2825 1606 2826 1607 2826 1608 2826 1608 2827 1607 2827 1609 2827 1608 2828 1609 2828 1610 2828 1610 2829 1609 2829 1611 2829 1612 2830 1611 2830 1613 2830 1613 2831 1611 2831 1609 2831 1613 2832 1609 2832 1614 2832 1614 2833 1609 2833 1607 2833 1615 2834 1612 2834 1616 2834 1616 2835 1612 2835 1613 2835 1616 2836 1613 2836 1617 2836 1617 2837 1613 2837 1614 2837 1617 2838 1614 2838 1618 2838 1618 2839 1614 2839 1607 2839 1618 2840 1607 2840 1619 2840 1619 2841 1607 2841 1606 2841 1619 2842 1606 2842 1620 2842 1621 2843 1622 2843 1605 2843 1605 2844 1622 2844 1623 2844 1571 2845 1624 2845 1625 2845 1625 2846 1624 2846 1626 2846 1625 2847 1626 2847 1627 2847 1574 2848 1628 2848 1572 2848 1572 2849 1628 2849 1629 2849 1572 2850 1629 2850 1630 2850 1630 2851 1629 2851 1631 2851 1630 2852 1631 2852 1632 2852 1573 2853 1572 2853 1633 2853 1633 2854 1572 2854 1630 2854 1633 2855 1630 2855 1634 2855 1634 2856 1630 2856 1632 2856 1634 2857 1632 2857 1635 2857 1571 2858 1570 2858 1624 2858 1624 2859 1570 2859 1636 2859 1624 2860 1636 2860 1626 2860 1637 2861 1638 2861 1639 2861 1637 2862 1639 2862 1640 2862 1639 2863 1641 2863 1640 2863 1640 2864 1641 2864 1642 2864 1640 2865 1642 2865 1643 2865 1643 2866 1642 2866 1644 2866 1643 2867 1644 2867 1567 2867 1554 2868 1562 2868 1555 2868 1555 2869 1562 2869 1564 2869 1555 2870 1564 2870 1645 2870 1645 2871 1564 2871 1646 2871 1645 2872 1646 2872 1647 2872 1647 2873 1646 2873 1637 2873 1647 2874 1637 2874 1648 2874 1648 2875 1637 2875 1640 2875 1648 2876 1640 2876 1649 2876 1649 2877 1640 2877 1643 2877 1649 2878 1643 2878 1650 2878 1650 2879 1643 2879 1567 2879 1650 2880 1567 2880 1651 2880 1651 2881 1567 2881 1566 2881 1651 2882 1566 2882 1652 2882 1652 2883 1566 2883 1568 2883 1652 2884 1568 2884 1653 2884 1653 2885 1568 2885 1654 2885 1653 2886 1654 2886 1655 2886 1644 2887 1656 2887 1567 2887 1567 2888 1656 2888 1657 2888 1567 2889 1657 2889 1565 2889 1565 2890 1657 2890 1658 2890 1565 2891 1658 2891 1659 2891 1628 2892 1655 2892 1629 2892 1629 2893 1655 2893 1654 2893 1629 2894 1654 2894 1631 2894 1631 2895 1654 2895 1568 2895 1631 2896 1568 2896 1632 2896 1632 2897 1568 2897 1565 2897 1632 2898 1565 2898 1635 2898 1635 2899 1565 2899 1659 2899 1635 2900 1659 2900 1660 2900 1496 2901 1497 2901 1661 2901 1661 2902 1497 2902 1498 2902 1661 2903 1498 2903 1662 2903 1663 2904 1664 2904 1460 2904 1626 2905 1665 2905 1664 2905 1664 2906 1665 2906 1459 2906 1664 2907 1459 2907 1460 2907 1602 2908 1665 2908 1603 2908 1603 2909 1665 2909 1626 2909 1603 2910 1626 2910 1605 2910 1605 2911 1626 2911 1666 2911 1605 2912 1666 2912 1667 2912 1667 2913 1666 2913 1576 2913 1667 2914 1576 2914 1605 2914 1605 2915 1576 2915 1575 2915 1605 2916 1575 2916 1621 2916 1560 2917 1559 2917 1668 2917 1668 2918 1559 2918 1669 2918 1668 2919 1669 2919 1670 2919 1669 2920 1671 2920 1670 2920 1670 2921 1671 2921 1672 2921 1670 2922 1672 2922 1663 2922 1663 2923 1672 2923 1673 2923 1663 2924 1673 2924 1664 2924 1664 2925 1673 2925 1674 2925 1664 2926 1674 2926 1626 2926 1498 2927 1499 2927 1662 2927 1662 2928 1499 2928 1500 2928 1662 2929 1500 2929 1675 2929 1460 2930 1461 2930 1663 2930 1663 2931 1461 2931 1496 2931 1663 2932 1496 2932 1670 2932 1670 2933 1496 2933 1661 2933 1670 2934 1661 2934 1668 2934 1668 2935 1661 2935 1662 2935 1668 2936 1662 2936 1560 2936 1560 2937 1662 2937 1675 2937 1560 2938 1675 2938 1561 2938 1676 2939 1475 2939 1465 2939 1676 2940 1465 2940 1677 2940 1475 2941 1676 2941 1476 2941 1476 2942 1676 2942 1678 2942 1476 2943 1678 2943 1478 2943 1539 2944 1679 2944 1468 2944 1468 2945 1679 2945 1680 2945 1465 2946 1474 2946 1677 2946 1677 2947 1474 2947 1473 2947 1677 2948 1473 2948 1681 2948 1681 2949 1473 2949 1471 2949 1681 2950 1471 2950 1680 2950 1680 2951 1471 2951 1469 2951 1680 2952 1469 2952 1468 2952 1500 2953 1478 2953 1675 2953 1675 2954 1478 2954 1678 2954 1675 2955 1678 2955 1561 2955 1561 2956 1678 2956 1682 2956 1561 2957 1682 2957 1559 2957 1559 2958 1682 2958 1620 2958 1559 2959 1620 2959 1669 2959 1669 2960 1620 2960 1606 2960 1669 2961 1606 2961 1671 2961 1671 2962 1606 2962 1608 2962 1671 2963 1608 2963 1672 2963 1672 2964 1608 2964 1610 2964 1672 2965 1610 2965 1673 2965 1673 2966 1610 2966 1611 2966 1673 2967 1611 2967 1674 2967 1674 2968 1611 2968 1612 2968 1674 2969 1612 2969 1626 2969 1626 2970 1612 2970 1615 2970 1596 2971 1683 2971 1595 2971 1595 2972 1683 2972 1684 2972 1595 2973 1684 2973 1685 2973 1593 2974 1451 2974 1449 2974 1449 2975 1599 2975 1593 2975 1593 2976 1599 2976 1601 2976 1593 2977 1601 2977 1589 2977 1589 2978 1601 2978 1686 2978 1589 2979 1686 2979 1587 2979 1451 2980 1593 2980 1456 2980 1456 2981 1593 2981 1594 2981 1456 2982 1594 2982 1455 2982 1455 2983 1594 2983 1595 2983 1455 2984 1595 2984 1454 2984 1454 2985 1595 2985 1685 2985 1454 2986 1685 2986 1453 2986 1638 2987 1637 2987 1687 2987 1687 2988 1637 2988 1646 2988 1687 2989 1646 2989 1688 2989 1688 2990 1646 2990 1564 2990 1688 2991 1564 2991 1558 2991 1558 2992 1564 2992 1563 2992 1558 2993 1563 2993 1556 2993 1623 2994 1689 2994 1605 2994 1605 2995 1689 2995 1690 2995 1605 2996 1690 2996 1604 2996 1604 2997 1690 2997 1691 2997 1604 2998 1691 2998 1597 2998 1597 2999 1691 2999 1692 2999 1597 3000 1692 3000 1598 3000 1679 3001 1553 3001 1680 3001 1680 3002 1553 3002 1555 3002 1680 3003 1555 3003 1681 3003 1681 3004 1555 3004 1645 3004 1681 3005 1645 3005 1677 3005 1677 3006 1645 3006 1647 3006 1677 3007 1647 3007 1676 3007 1676 3008 1647 3008 1648 3008 1676 3009 1648 3009 1678 3009 1678 3010 1648 3010 1649 3010 1678 3011 1649 3011 1682 3011 1682 3012 1649 3012 1650 3012 1682 3013 1650 3013 1620 3013 1620 3014 1650 3014 1651 3014 1620 3015 1651 3015 1619 3015 1619 3016 1651 3016 1652 3016 1619 3017 1652 3017 1618 3017 1618 3018 1652 3018 1653 3018 1618 3019 1653 3019 1617 3019 1617 3020 1653 3020 1655 3020 1617 3021 1655 3021 1616 3021 1616 3022 1655 3022 1628 3022 1616 3023 1628 3023 1615 3023 1615 3024 1628 3024 1574 3024 1615 3025 1574 3025 1626 3025 1626 3026 1574 3026 1573 3026 1626 3027 1573 3027 1627 3027 1627 3028 1573 3028 1633 3028 1627 3029 1633 3029 1625 3029 1625 3030 1633 3030 1634 3030 1625 3031 1634 3031 1571 3031 1571 3032 1634 3032 1635 3032 1571 3033 1635 3033 1569 3033 1569 3034 1635 3034 1660 3034 1449 3035 1439 3035 1599 3035 1599 3036 1439 3036 1438 3036 1599 3037 1438 3037 1597 3037 1597 3038 1438 3038 1446 3038 1597 3039 1446 3039 1604 3039 1604 3040 1446 3040 1543 3040 1604 3041 1543 3041 1602 3041 1602 3042 1543 3042 1457 3042 1602 3043 1457 3043 1665 3043 1665 3044 1457 3044 1458 3044 1665 3045 1458 3045 1459 3045 1693 3046 1694 3046 1695 3046 1696 3047 1697 3047 1698 3047 1699 3048 1700 3048 1701 3048 1702 3049 1703 3049 1704 3049 1705 3050 1584 3050 1579 3050 1706 3051 1707 3051 1708 3051 1709 3052 1710 3052 1711 3052 1709 3053 1711 3053 1712 3053 1713 3054 1714 3054 1715 3054 1715 3055 1714 3055 1716 3055 1715 3056 1716 3056 1717 3056 1718 3057 1712 3057 1719 3057 1719 3058 1712 3058 1711 3058 1719 3059 1711 3059 1720 3059 1720 3060 1711 3060 1721 3060 1720 3061 1721 3061 1722 3061 1722 3062 1721 3062 1717 3062 1722 3063 1717 3063 1723 3063 1723 3064 1717 3064 1716 3064 1724 3065 1725 3065 1726 3065 1726 3066 1725 3066 1727 3066 1727 3067 1725 3067 1728 3067 1727 3068 1728 3068 1729 3068 1726 3069 1730 3069 1724 3069 1724 3070 1730 3070 1731 3070 1724 3071 1731 3071 1732 3071 1732 3072 1731 3072 1733 3072 1732 3073 1733 3073 1734 3073 1733 3074 1735 3074 1734 3074 1734 3075 1735 3075 1736 3075 1734 3076 1736 3076 1737 3076 1737 3077 1736 3077 1738 3077 1737 3078 1738 3078 1739 3078 1739 3079 1738 3079 1740 3079 1739 3080 1740 3080 1741 3080 1689 3081 1623 3081 1742 3081 1742 3082 1623 3082 1622 3082 1622 3083 1621 3083 1743 3083 1621 3084 1575 3084 1743 3084 1743 3085 1575 3085 1577 3085 1743 3086 1577 3086 1576 3086 1622 3087 1743 3087 1742 3087 1742 3088 1743 3088 1744 3088 1742 3089 1744 3089 1689 3089 1666 3090 1745 3090 1746 3090 1666 3091 1626 3091 1745 3091 1745 3092 1626 3092 1636 3092 1745 3093 1636 3093 1747 3093 1747 3094 1636 3094 1570 3094 1748 3095 1749 3095 1750 3095 1750 3096 1749 3096 1751 3096 1752 3097 1569 3097 1753 3097 1753 3098 1569 3098 1660 3098 1753 3099 1660 3099 1659 3099 1754 3100 1755 3100 1656 3100 1749 3101 1752 3101 1751 3101 1751 3102 1752 3102 1753 3102 1751 3103 1753 3103 1756 3103 1756 3104 1753 3104 1659 3104 1756 3105 1659 3105 1757 3105 1757 3106 1659 3106 1658 3106 1757 3107 1658 3107 1755 3107 1755 3108 1658 3108 1657 3108 1755 3109 1657 3109 1656 3109 1656 3110 1644 3110 1754 3110 1754 3111 1644 3111 1642 3111 1754 3112 1642 3112 1758 3112 1758 3113 1642 3113 1641 3113 1758 3114 1641 3114 1639 3114 1759 3115 1760 3115 1638 3115 1638 3116 1687 3116 1759 3116 1759 3117 1687 3117 1688 3117 1759 3118 1688 3118 1761 3118 1761 3119 1688 3119 1558 3119 1761 3120 1558 3120 1557 3120 1557 3121 1762 3121 1761 3121 1761 3122 1762 3122 1763 3122 1761 3123 1763 3123 1764 3123 1765 3124 1766 3124 1579 3124 1579 3125 1766 3125 1767 3125 1579 3126 1767 3126 1705 3126 1768 3127 1769 3127 1579 3127 1579 3128 1769 3128 1770 3128 1579 3129 1770 3129 1765 3129 1771 3130 1772 3130 1768 3130 1768 3131 1772 3131 1773 3131 1768 3132 1773 3132 1769 3132 1587 3133 1774 3133 1588 3133 1588 3134 1774 3134 1775 3134 1588 3135 1775 3135 1590 3135 1590 3136 1775 3136 1776 3136 1777 3137 1778 3137 1779 3137 1703 3138 1771 3138 1704 3138 1704 3139 1771 3139 1768 3139 1704 3140 1768 3140 1780 3140 1587 3141 1686 3141 1774 3141 1774 3142 1686 3142 1601 3142 1774 3143 1601 3143 1781 3143 1776 3144 1775 3144 1778 3144 1778 3145 1775 3145 1774 3145 1778 3146 1774 3146 1779 3146 1779 3147 1774 3147 1781 3147 1779 3148 1781 3148 1782 3148 1783 3149 1600 3149 1598 3149 1783 3150 1598 3150 1784 3150 1598 3151 1692 3151 1784 3151 1784 3152 1692 3152 1691 3152 1784 3153 1691 3153 1744 3153 1744 3154 1691 3154 1690 3154 1744 3155 1690 3155 1689 3155 1601 3156 1600 3156 1781 3156 1781 3157 1600 3157 1783 3157 1781 3158 1783 3158 1782 3158 1782 3159 1783 3159 1784 3159 1782 3160 1784 3160 1785 3160 1785 3161 1784 3161 1744 3161 1785 3162 1744 3162 1786 3162 1786 3163 1744 3163 1743 3163 1786 3164 1743 3164 1746 3164 1746 3165 1743 3165 1576 3165 1746 3166 1576 3166 1666 3166 1777 3167 1779 3167 1787 3167 1787 3168 1779 3168 1782 3168 1787 3169 1782 3169 1788 3169 1788 3170 1782 3170 1785 3170 1788 3171 1785 3171 1789 3171 1789 3172 1785 3172 1786 3172 1789 3173 1786 3173 1790 3173 1790 3174 1786 3174 1746 3174 1790 3175 1746 3175 1748 3175 1748 3176 1746 3176 1745 3176 1748 3177 1745 3177 1749 3177 1749 3178 1745 3178 1747 3178 1749 3179 1747 3179 1752 3179 1752 3180 1747 3180 1570 3180 1752 3181 1570 3181 1569 3181 1788 3182 1791 3182 1787 3182 1787 3183 1791 3183 1780 3183 1787 3184 1780 3184 1777 3184 1777 3185 1780 3185 1768 3185 1777 3186 1768 3186 1778 3186 1778 3187 1768 3187 1579 3187 1778 3188 1579 3188 1776 3188 1776 3189 1579 3189 1592 3189 1776 3190 1592 3190 1590 3190 1750 3191 1792 3191 1748 3191 1748 3192 1792 3192 1793 3192 1748 3193 1793 3193 1790 3193 1790 3194 1793 3194 1794 3194 1790 3195 1794 3195 1789 3195 1789 3196 1794 3196 1795 3196 1789 3197 1795 3197 1788 3197 1788 3198 1795 3198 1796 3198 1788 3199 1796 3199 1791 3199 1700 3200 1702 3200 1701 3200 1701 3201 1702 3201 1704 3201 1701 3202 1704 3202 1797 3202 1797 3203 1704 3203 1780 3203 1797 3204 1780 3204 1798 3204 1798 3205 1780 3205 1791 3205 1798 3206 1791 3206 1799 3206 1799 3207 1791 3207 1796 3207 1799 3208 1796 3208 1800 3208 1800 3209 1796 3209 1795 3209 1800 3210 1795 3210 1801 3210 1801 3211 1795 3211 1794 3211 1801 3212 1794 3212 1802 3212 1802 3213 1794 3213 1793 3213 1802 3214 1793 3214 1803 3214 1803 3215 1793 3215 1792 3215 1803 3216 1792 3216 1804 3216 1804 3217 1792 3217 1750 3217 1804 3218 1750 3218 1805 3218 1805 3219 1750 3219 1751 3219 1805 3220 1751 3220 1806 3220 1806 3221 1751 3221 1756 3221 1806 3222 1756 3222 1807 3222 1807 3223 1756 3223 1757 3223 1807 3224 1757 3224 1808 3224 1808 3225 1757 3225 1755 3225 1808 3226 1755 3226 1809 3226 1809 3227 1755 3227 1754 3227 1809 3228 1754 3228 1810 3228 1810 3229 1754 3229 1758 3229 1810 3230 1758 3230 1760 3230 1760 3231 1758 3231 1639 3231 1760 3232 1639 3232 1638 3232 1729 3233 1728 3233 1811 3233 1811 3234 1728 3234 1708 3234 1811 3235 1708 3235 1812 3235 1812 3236 1708 3236 1707 3236 1812 3237 1707 3237 1813 3237 1740 3238 1814 3238 1741 3238 1741 3239 1814 3239 1815 3239 1741 3240 1815 3240 1816 3240 1816 3241 1815 3241 1817 3241 1816 3242 1817 3242 1818 3242 1818 3243 1817 3243 1819 3243 1818 3244 1819 3244 1820 3244 1820 3245 1819 3245 1821 3245 1820 3246 1821 3246 1696 3246 1696 3247 1821 3247 1822 3247 1696 3248 1822 3248 1697 3248 1694 3249 1706 3249 1695 3249 1695 3250 1706 3250 1708 3250 1695 3251 1708 3251 1823 3251 1823 3252 1708 3252 1728 3252 1823 3253 1728 3253 1824 3253 1824 3254 1728 3254 1725 3254 1824 3255 1725 3255 1825 3255 1825 3256 1725 3256 1724 3256 1825 3257 1724 3257 1826 3257 1826 3258 1724 3258 1732 3258 1826 3259 1732 3259 1827 3259 1827 3260 1732 3260 1734 3260 1827 3261 1734 3261 1828 3261 1828 3262 1734 3262 1737 3262 1828 3263 1737 3263 1829 3263 1829 3264 1737 3264 1739 3264 1829 3265 1739 3265 1830 3265 1830 3266 1739 3266 1741 3266 1830 3267 1741 3267 1831 3267 1831 3268 1741 3268 1816 3268 1831 3269 1816 3269 1832 3269 1832 3270 1816 3270 1818 3270 1832 3271 1818 3271 1833 3271 1833 3272 1818 3272 1820 3272 1833 3273 1820 3273 1834 3273 1834 3274 1820 3274 1696 3274 1834 3275 1696 3275 1713 3275 1713 3276 1696 3276 1698 3276 1713 3277 1698 3277 1714 3277 1764 3278 1693 3278 1761 3278 1761 3279 1693 3279 1695 3279 1761 3280 1695 3280 1759 3280 1759 3281 1695 3281 1823 3281 1759 3282 1823 3282 1760 3282 1760 3283 1823 3283 1824 3283 1760 3284 1824 3284 1810 3284 1810 3285 1824 3285 1825 3285 1810 3286 1825 3286 1809 3286 1809 3287 1825 3287 1826 3287 1809 3288 1826 3288 1808 3288 1808 3289 1826 3289 1827 3289 1808 3290 1827 3290 1807 3290 1807 3291 1827 3291 1828 3291 1807 3292 1828 3292 1806 3292 1806 3293 1828 3293 1829 3293 1806 3294 1829 3294 1805 3294 1805 3295 1829 3295 1830 3295 1805 3296 1830 3296 1804 3296 1804 3297 1830 3297 1831 3297 1804 3298 1831 3298 1803 3298 1803 3299 1831 3299 1832 3299 1803 3300 1832 3300 1802 3300 1802 3301 1832 3301 1833 3301 1802 3302 1833 3302 1801 3302 1801 3303 1833 3303 1834 3303 1801 3304 1834 3304 1800 3304 1800 3305 1834 3305 1713 3305 1800 3306 1713 3306 1799 3306 1799 3307 1713 3307 1715 3307 1799 3308 1715 3308 1798 3308 1798 3309 1715 3309 1717 3309 1798 3310 1717 3310 1797 3310 1797 3311 1717 3311 1721 3311 1797 3312 1721 3312 1701 3312 1701 3313 1721 3313 1711 3313 1701 3314 1711 3314 1699 3314 1699 3315 1711 3315 1710 3315 1835 3316 1836 3316 1837 3316 1453 3317 1685 3317 1838 3317 1585 3318 1582 3318 1839 3318 1840 3319 1836 3319 1841 3319 1842 3320 1843 3320 1844 3320 1845 3321 1846 3321 1847 3321 1847 3322 1846 3322 1848 3322 1847 3323 1848 3323 1849 3323 1850 3324 1851 3324 1852 3324 1852 3325 1851 3325 1853 3325 1843 3326 1842 3326 1854 3326 1849 3327 1855 3327 1847 3327 1847 3328 1855 3328 1856 3328 1847 3329 1856 3329 1845 3329 1845 3330 1856 3330 1857 3330 1858 3331 1853 3331 1857 3331 1857 3332 1853 3332 1851 3332 1857 3333 1851 3333 1845 3333 1845 3334 1851 3334 1850 3334 1845 3335 1850 3335 1846 3335 1840 3336 1841 3336 1859 3336 1860 3337 1859 3337 1861 3337 1861 3338 1859 3338 1841 3338 1861 3339 1841 3339 1862 3339 1862 3340 1841 3340 1863 3340 1862 3341 1863 3341 1864 3341 1835 3342 1865 3342 1858 3342 1858 3343 1865 3343 1866 3343 1858 3344 1866 3344 1853 3344 1442 3345 1441 3345 1867 3345 1867 3346 1441 3346 1868 3346 1839 3347 1582 3347 1869 3347 1869 3348 1582 3348 1583 3348 1869 3349 1583 3349 1584 3349 1684 3350 1683 3350 1870 3350 1870 3351 1683 3351 1596 3351 1578 3352 1580 3352 1871 3352 1871 3353 1580 3353 1581 3353 1871 3354 1581 3354 1839 3354 1839 3355 1581 3355 1586 3355 1839 3356 1586 3356 1585 3356 1872 3357 1870 3357 1871 3357 1871 3358 1870 3358 1596 3358 1871 3359 1596 3359 1578 3359 1685 3360 1684 3360 1838 3360 1838 3361 1684 3361 1870 3361 1838 3362 1870 3362 1854 3362 1854 3363 1870 3363 1872 3363 1854 3364 1872 3364 1843 3364 1842 3365 1864 3365 1854 3365 1854 3366 1864 3366 1873 3366 1854 3367 1873 3367 1838 3367 1838 3368 1873 3368 1868 3368 1838 3369 1868 3369 1453 3369 1453 3370 1868 3370 1441 3370 1835 3371 1874 3371 1865 3371 1865 3372 1874 3372 1875 3372 1865 3373 1875 3373 1866 3373 1866 3374 1875 3374 1876 3374 1866 3375 1876 3375 1853 3375 1853 3376 1876 3376 1877 3376 1853 3377 1877 3377 1852 3377 1855 3378 1863 3378 1856 3378 1856 3379 1863 3379 1841 3379 1856 3380 1841 3380 1857 3380 1857 3381 1841 3381 1836 3381 1857 3382 1836 3382 1858 3382 1858 3383 1836 3383 1835 3383 1445 3384 1444 3384 1878 3384 1878 3385 1444 3385 1849 3385 1878 3386 1849 3386 1879 3386 1879 3387 1849 3387 1848 3387 1864 3388 1863 3388 1873 3388 1873 3389 1863 3389 1855 3389 1873 3390 1855 3390 1868 3390 1868 3391 1855 3391 1849 3391 1868 3392 1849 3392 1867 3392 1867 3393 1849 3393 1444 3393 1867 3394 1444 3394 1442 3394 1880 3395 1881 3395 1882 3395 1872 3396 1871 3396 1883 3396 1884 3397 1885 3397 1886 3397 1887 3398 1888 3398 1889 3398 1889 3399 1888 3399 1890 3399 1891 3400 1835 3400 1892 3400 1893 3401 1894 3401 1895 3401 1836 3402 1896 3402 1835 3402 1862 3403 1864 3403 1897 3403 1898 3404 1899 3404 1900 3404 1900 3405 1899 3405 1901 3405 1900 3406 1901 3406 1275 3406 1864 3407 1842 3407 1902 3407 1902 3408 1842 3408 1844 3408 1902 3409 1844 3409 1843 3409 1859 3410 1861 3410 1840 3410 1840 3411 1861 3411 1903 3411 1840 3412 1903 3412 1836 3412 1836 3413 1903 3413 1904 3413 1836 3414 1904 3414 1896 3414 1905 3415 1906 3415 1907 3415 1907 3416 1906 3416 1904 3416 1907 3417 1904 3417 1897 3417 1897 3418 1904 3418 1903 3418 1897 3419 1903 3419 1862 3419 1862 3420 1903 3420 1861 3420 1908 3421 1909 3421 1910 3421 1910 3422 1909 3422 1911 3422 1835 3423 1896 3423 1911 3423 1911 3424 1896 3424 1912 3424 1911 3425 1912 3425 1910 3425 1885 3426 1913 3426 1886 3426 1886 3427 1913 3427 1914 3427 1886 3428 1914 3428 1915 3428 1915 3429 1914 3429 1916 3429 1915 3430 1916 3430 1917 3430 1918 3431 1916 3431 1919 3431 1919 3432 1916 3432 1914 3432 1919 3433 1914 3433 1920 3433 1920 3434 1914 3434 1913 3434 1917 3435 1916 3435 1921 3435 1921 3436 1916 3436 1918 3436 1921 3437 1918 3437 1922 3437 1922 3438 1918 3438 1923 3438 1922 3439 1923 3439 1924 3439 1925 3440 1926 3440 1927 3440 1927 3441 1926 3441 1923 3441 1927 3442 1923 3442 1928 3442 1928 3443 1923 3443 1918 3443 1928 3444 1918 3444 1929 3444 1929 3445 1918 3445 1919 3445 1930 3446 1917 3446 1931 3446 1931 3447 1917 3447 1921 3447 1931 3448 1921 3448 1932 3448 1932 3449 1921 3449 1922 3449 1932 3450 1922 3450 1933 3450 1933 3451 1922 3451 1924 3451 1933 3452 1924 3452 1934 3452 1891 3453 1892 3453 1935 3453 1936 3454 1937 3454 1938 3454 1938 3455 1937 3455 1939 3455 1938 3456 1939 3456 1940 3456 1940 3457 1939 3457 1941 3457 1940 3458 1941 3458 1942 3458 1943 3459 1944 3459 1945 3459 1946 3460 1947 3460 1948 3460 1948 3461 1947 3461 1949 3461 1950 3462 1941 3462 1951 3462 1951 3463 1941 3463 1939 3463 1951 3464 1939 3464 1952 3464 1952 3465 1939 3465 1937 3465 1952 3466 1937 3466 1953 3466 1953 3467 1937 3467 1936 3467 1953 3468 1936 3468 1954 3468 1946 3469 1955 3469 1947 3469 1947 3470 1955 3470 1945 3470 1947 3471 1945 3471 1949 3471 1949 3472 1945 3472 1944 3472 1906 3473 1956 3473 1904 3473 1904 3474 1956 3474 1954 3474 1904 3475 1954 3475 1896 3475 1896 3476 1954 3476 1936 3476 1896 3477 1936 3477 1912 3477 1912 3478 1936 3478 1938 3478 1912 3479 1938 3479 1910 3479 1910 3480 1938 3480 1940 3480 1910 3481 1940 3481 1908 3481 1908 3482 1940 3482 1942 3482 1935 3483 1957 3483 1891 3483 1891 3484 1957 3484 1958 3484 1891 3485 1958 3485 1835 3485 1959 3486 1960 3486 1961 3486 1961 3487 1960 3487 1962 3487 1961 3488 1962 3488 1963 3488 1957 3489 1964 3489 1958 3489 1958 3490 1964 3490 1835 3490 1935 3491 1961 3491 1957 3491 1957 3492 1961 3492 1963 3492 1957 3493 1963 3493 1964 3493 1964 3494 1963 3494 1965 3494 1964 3495 1965 3495 1966 3495 1966 3496 1965 3496 1967 3496 1950 3497 1968 3497 1941 3497 1941 3498 1968 3498 1893 3498 1941 3499 1893 3499 1942 3499 1942 3500 1893 3500 1895 3500 1942 3501 1895 3501 1969 3501 1925 3502 1970 3502 1926 3502 1926 3503 1970 3503 1944 3503 1926 3504 1944 3504 1923 3504 1923 3505 1944 3505 1943 3505 1923 3506 1943 3506 1924 3506 1924 3507 1943 3507 1971 3507 1924 3508 1971 3508 1934 3508 1972 3509 1973 3509 1900 3509 1900 3510 1973 3510 1974 3510 1900 3511 1974 3511 1898 3511 1975 3512 1976 3512 1977 3512 1977 3513 1978 3513 1975 3513 1975 3514 1978 3514 1979 3514 1975 3515 1979 3515 1980 3515 1889 3516 1981 3516 1887 3516 1887 3517 1981 3517 1982 3517 1887 3518 1982 3518 1976 3518 1976 3519 1982 3519 1983 3519 1976 3520 1983 3520 1977 3520 1984 3521 1975 3521 1900 3521 1900 3522 1975 3522 1980 3522 1900 3523 1980 3523 1972 3523 1930 3524 1888 3524 1917 3524 1917 3525 1888 3525 1887 3525 1917 3526 1887 3526 1915 3526 1915 3527 1887 3527 1976 3527 1915 3528 1976 3528 1886 3528 1886 3529 1976 3529 1975 3529 1886 3530 1975 3530 1884 3530 1884 3531 1975 3531 1984 3531 1934 3532 1985 3532 1933 3532 1933 3533 1985 3533 1986 3533 1933 3534 1986 3534 1932 3534 1932 3535 1986 3535 1987 3535 1932 3536 1987 3536 1931 3536 1931 3537 1987 3537 1988 3537 1931 3538 1988 3538 1930 3538 1930 3539 1988 3539 1989 3539 1930 3540 1989 3540 1888 3540 1888 3541 1989 3541 1882 3541 1888 3542 1882 3542 1890 3542 1890 3543 1882 3543 1881 3543 1584 3544 1705 3544 1869 3544 1869 3545 1705 3545 1839 3545 1705 3546 1767 3546 1839 3546 1839 3547 1767 3547 1766 3547 1839 3548 1766 3548 1871 3548 1871 3549 1766 3549 1765 3549 1765 3550 1770 3550 1871 3550 1871 3551 1770 3551 1769 3551 1871 3552 1769 3552 1883 3552 1883 3553 1769 3553 1773 3553 1883 3554 1773 3554 1772 3554 1772 3555 1771 3555 1883 3555 1883 3556 1771 3556 1703 3556 1883 3557 1703 3557 1990 3557 1699 3558 1991 3558 1700 3558 1700 3559 1991 3559 1990 3559 1700 3560 1990 3560 1702 3560 1702 3561 1990 3561 1703 3561 1991 3562 1992 3562 1990 3562 1990 3563 1992 3563 1993 3563 1990 3564 1993 3564 1883 3564 1883 3565 1993 3565 1902 3565 1883 3566 1902 3566 1872 3566 1872 3567 1902 3567 1843 3567 1864 3568 1902 3568 1897 3568 1897 3569 1902 3569 1993 3569 1897 3570 1993 3570 1907 3570 1907 3571 1993 3571 1992 3571 1907 3572 1992 3572 1905 3572 1905 3573 1992 3573 1991 3573 1905 3574 1991 3574 1994 3574 1994 3575 1991 3575 1699 3575 1994 3576 1699 3576 1710 3576 1710 3577 1709 3577 1994 3577 1994 3578 1709 3578 1712 3578 1994 3579 1712 3579 1718 3579 1967 3580 1995 3580 1966 3580 1966 3581 1995 3581 1996 3581 1966 3582 1996 3582 1964 3582 1964 3583 1996 3583 1835 3583 1969 3584 1959 3584 1942 3584 1942 3585 1959 3585 1961 3585 1942 3586 1961 3586 1908 3586 1908 3587 1961 3587 1935 3587 1908 3588 1935 3588 1909 3588 1909 3589 1935 3589 1892 3589 1909 3590 1892 3590 1911 3590 1911 3591 1892 3591 1835 3591 1955 3592 1968 3592 1945 3592 1945 3593 1968 3593 1950 3593 1945 3594 1950 3594 1943 3594 1943 3595 1950 3595 1951 3595 1943 3596 1951 3596 1971 3596 1971 3597 1951 3597 1952 3597 1971 3598 1952 3598 1934 3598 1934 3599 1952 3599 1953 3599 1934 3600 1953 3600 1985 3600 1985 3601 1953 3601 1954 3601 1985 3602 1954 3602 1986 3602 1986 3603 1954 3603 1956 3603 1986 3604 1956 3604 1987 3604 1987 3605 1956 3605 1906 3605 1987 3606 1906 3606 1988 3606 1988 3607 1906 3607 1905 3607 1988 3608 1905 3608 1989 3608 1989 3609 1905 3609 1994 3609 1989 3610 1994 3610 1882 3610 1882 3611 1994 3611 1718 3611 1882 3612 1718 3612 1880 3612 1997 3613 1998 3613 1999 3613 2000 3614 2001 3614 2002 3614 2003 3615 2004 3615 2005 3615 2006 3616 2007 3616 2008 3616 2008 3617 2007 3617 2003 3617 2003 3618 2005 3618 2008 3618 2008 3619 2005 3619 2009 3619 2008 3620 2009 3620 2010 3620 2011 3621 2012 3621 2013 3621 2013 3622 2012 3622 2014 3622 2013 3623 2014 3623 2015 3623 2011 3624 2016 3624 2012 3624 2012 3625 2016 3625 2017 3625 2012 3626 2017 3626 2009 3626 2009 3627 2017 3627 2018 3627 2009 3628 2018 3628 2010 3628 2002 3629 2001 3629 2019 3629 2001 3630 2020 3630 2019 3630 2019 3631 2020 3631 2021 3631 2019 3632 2021 3632 2014 3632 2014 3633 2021 3633 2022 3633 2014 3634 2022 3634 2015 3634 2000 3635 2002 3635 2023 3635 2023 3636 2002 3636 2024 3636 2023 3637 2024 3637 2025 3637 2026 3638 2027 3638 2024 3638 2024 3639 2027 3639 2028 3639 2024 3640 2028 3640 2025 3640 2029 3641 2030 3641 2031 3641 2030 3642 2029 3642 2032 3642 2032 3643 2029 3643 2033 3643 2032 3644 2033 3644 2034 3644 2034 3645 2033 3645 2035 3645 2035 3646 2033 3646 2036 3646 2035 3647 2036 3647 2037 3647 2038 3648 2039 3648 2040 3648 2040 3649 2039 3649 2041 3649 2040 3650 2041 3650 2042 3650 2037 3651 2036 3651 2043 3651 2043 3652 2036 3652 2041 3652 2043 3653 2041 3653 2044 3653 2044 3654 2041 3654 2039 3654 2044 3655 2039 3655 2045 3655 2046 3656 2047 3656 2048 3656 2048 3657 2047 3657 2049 3657 2050 3658 2051 3658 2052 3658 2052 3659 2051 3659 2053 3659 2052 3660 2053 3660 2054 3660 2054 3661 2053 3661 2055 3661 2050 3662 2056 3662 2051 3662 2051 3663 2056 3663 2057 3663 2051 3664 2057 3664 2058 3664 2057 3665 2059 3665 2058 3665 2058 3666 2059 3666 2060 3666 2058 3667 2060 3667 2046 3667 2046 3668 2060 3668 2061 3668 2046 3669 2061 3669 2047 3669 2055 3670 2053 3670 2062 3670 2062 3671 2053 3671 2063 3671 2062 3672 2063 3672 2064 3672 2064 3673 2063 3673 2065 3673 2064 3674 2065 3674 2066 3674 2031 3675 2027 3675 2029 3675 2029 3676 2027 3676 2026 3676 2029 3677 2026 3677 2033 3677 2033 3678 2026 3678 2067 3678 2033 3679 2067 3679 2036 3679 2036 3680 2067 3680 2068 3680 2036 3681 2068 3681 2041 3681 2041 3682 2068 3682 1999 3682 2041 3683 1999 3683 2042 3683 2042 3684 1999 3684 1998 3684 1539 3685 2069 3685 1679 3685 1679 3686 2069 3686 2070 3686 2071 3687 1554 3687 2070 3687 2070 3688 1554 3688 1553 3688 2070 3689 1553 3689 1679 3689 1556 3690 1563 3690 2071 3690 2071 3691 1563 3691 1562 3691 2071 3692 1562 3692 1554 3692 2072 3693 1763 3693 1762 3693 2072 3694 1762 3694 2071 3694 2071 3695 1762 3695 1557 3695 2071 3696 1557 3696 1556 3696 1763 3697 2072 3697 1764 3697 1764 3698 2072 3698 2073 3698 1764 3699 2073 3699 1693 3699 2049 3700 1813 3700 2048 3700 2048 3701 1813 3701 1707 3701 2048 3702 1707 3702 2074 3702 2074 3703 1707 3703 1706 3703 2074 3704 1706 3704 2073 3704 2073 3705 1706 3705 1694 3705 2073 3706 1694 3706 1693 3706 2004 3707 2065 3707 2005 3707 2005 3708 2065 3708 2063 3708 2005 3709 2063 3709 2009 3709 2009 3710 2063 3710 2053 3710 2009 3711 2053 3711 2012 3711 2012 3712 2053 3712 2051 3712 2012 3713 2051 3713 2014 3713 2014 3714 2051 3714 2058 3714 2014 3715 2058 3715 2019 3715 2019 3716 2058 3716 2046 3716 2019 3717 2046 3717 2002 3717 2002 3718 2046 3718 2048 3718 2002 3719 2048 3719 2024 3719 2024 3720 2048 3720 2074 3720 2024 3721 2074 3721 2026 3721 2026 3722 2074 3722 2073 3722 2026 3723 2073 3723 2067 3723 2067 3724 2073 3724 2072 3724 2067 3725 2072 3725 2068 3725 2068 3726 2072 3726 2071 3726 2068 3727 2071 3727 1999 3727 1999 3728 2071 3728 2070 3728 1999 3729 2070 3729 1997 3729 1997 3730 2070 3730 2069 3730 1997 3731 2069 3731 2075 3731 2065 3732 2004 3732 2076 3732 2077 3733 2078 3733 2079 3733 2040 3734 2042 3734 2080 3734 2081 3735 2082 3735 2083 3735 2084 3736 2085 3736 2086 3736 2086 3737 2085 3737 2087 3737 2086 3738 2087 3738 2088 3738 2088 3739 2087 3739 2089 3739 2088 3740 2089 3740 2090 3740 2091 3741 2092 3741 2093 3741 2093 3742 2092 3742 2094 3742 2093 3743 2094 3743 2095 3743 2095 3744 2094 3744 2083 3744 2095 3745 2083 3745 2096 3745 2096 3746 2083 3746 2082 3746 2097 3747 2098 3747 2099 3747 2099 3748 2098 3748 2081 3748 2100 3749 2101 3749 2097 3749 2003 3750 2007 3750 2102 3750 2102 3751 2007 3751 2103 3751 2101 3752 2100 3752 2104 3752 2104 3753 2100 3753 2102 3753 2104 3754 2102 3754 2105 3754 2105 3755 2102 3755 2103 3755 2105 3756 2103 3756 2106 3756 2038 3757 2040 3757 2107 3757 2107 3758 2040 3758 2108 3758 2040 3759 2080 3759 2108 3759 2108 3760 2080 3760 2109 3760 2108 3761 2109 3761 2110 3761 2079 3762 2078 3762 2109 3762 2109 3763 2078 3763 2111 3763 2109 3764 2111 3764 2110 3764 2112 3765 2113 3765 2114 3765 2114 3766 2113 3766 2115 3766 2114 3767 2115 3767 2079 3767 2079 3768 2115 3768 2116 3768 2079 3769 2116 3769 2077 3769 1480 3770 2117 3770 1542 3770 1542 3771 2117 3771 2075 3771 1542 3772 2075 3772 1541 3772 1480 3773 1429 3773 2117 3773 2117 3774 1429 3774 1428 3774 2117 3775 1428 3775 2118 3775 1501 3776 2119 3776 1502 3776 1502 3777 2119 3777 2118 3777 1502 3778 2118 3778 1504 3778 1504 3779 2118 3779 1428 3779 1533 3780 2120 3780 1544 3780 1544 3781 2120 3781 2119 3781 1544 3782 2119 3782 1545 3782 1545 3783 2119 3783 1501 3783 1541 3784 2075 3784 1540 3784 1540 3785 2075 3785 2069 3785 1540 3786 2069 3786 1539 3786 2042 3787 1998 3787 2080 3787 2080 3788 1998 3788 2121 3788 2080 3789 2121 3789 2109 3789 2109 3790 2121 3790 2122 3790 2109 3791 2122 3791 2079 3791 2079 3792 2122 3792 2123 3792 2079 3793 2123 3793 2114 3793 2114 3794 2123 3794 2124 3794 2114 3795 2124 3795 2112 3795 2112 3796 2124 3796 2088 3796 2112 3797 2088 3797 2125 3797 2125 3798 2088 3798 2090 3798 2100 3799 2126 3799 2102 3799 2102 3800 2126 3800 2076 3800 2102 3801 2076 3801 2003 3801 2003 3802 2076 3802 2004 3802 2127 3803 1339 3803 1338 3803 2097 3804 2099 3804 2100 3804 2100 3805 2099 3805 2127 3805 2100 3806 2127 3806 2126 3806 2126 3807 2127 3807 1338 3807 2126 3808 1338 3808 1340 3808 1340 3809 2128 3809 2126 3809 2126 3810 2128 3810 2129 3810 2126 3811 2129 3811 2076 3811 2076 3812 2129 3812 2130 3812 2076 3813 2130 3813 2065 3813 2065 3814 2130 3814 2131 3814 2065 3815 2131 3815 2066 3815 1333 3816 1331 3816 2092 3816 2092 3817 1331 3817 1330 3817 2092 3818 1330 3818 2094 3818 2094 3819 1330 3819 1335 3819 2094 3820 1335 3820 1336 3820 2081 3821 2083 3821 2099 3821 2099 3822 2083 3822 2094 3822 2099 3823 2094 3823 2127 3823 2127 3824 2094 3824 1336 3824 2127 3825 1336 3825 1339 3825 1998 3826 1997 3826 2121 3826 2121 3827 1997 3827 2075 3827 2121 3828 2075 3828 2122 3828 2122 3829 2075 3829 2117 3829 2122 3830 2117 3830 2123 3830 2123 3831 2117 3831 2118 3831 2123 3832 2118 3832 2124 3832 2124 3833 2118 3833 2119 3833 2124 3834 2119 3834 2088 3834 2088 3835 2119 3835 2120 3835 2088 3836 2120 3836 2086 3836 2086 3837 2120 3837 2132 3837 2091 3838 2084 3838 2092 3838 2092 3839 2084 3839 2086 3839 2092 3840 2086 3840 1333 3840 1333 3841 2086 3841 2132 3841 1333 3842 2132 3842 1323 3842 1323 3843 2132 3843 1324 3843 1533 3844 1532 3844 2120 3844 2120 3845 1532 3845 2133 3845 2120 3846 2133 3846 2132 3846 2132 3847 2133 3847 1329 3847 2132 3848 1329 3848 1324 3848 1288 3849 1287 3849 1538 3849 1298 3850 1297 3850 1550 3850 1550 3851 1297 3851 1551 3851 1514 3852 1427 3852 1305 3852 1297 3853 1295 3853 1551 3853 1551 3854 1295 3854 1294 3854 1551 3855 1294 3855 1552 3855 1552 3856 1294 3856 1301 3856 1552 3857 1301 3857 1427 3857 1427 3858 1301 3858 1300 3858 1427 3859 1300 3859 1305 3859 1517 3860 1311 3860 1519 3860 1519 3861 1311 3861 1309 3861 1519 3862 1309 3862 1521 3862 1521 3863 1309 3863 1307 3863 1521 3864 1307 3864 1527 3864 1315 3865 1531 3865 1313 3865 1313 3866 1531 3866 1530 3866 1265 3867 1525 3867 1266 3867 1266 3868 1525 3868 1523 3868 1266 3869 1523 3869 1321 3869 1321 3870 1523 3870 1531 3870 1321 3871 1531 3871 1317 3871 1317 3872 1531 3872 1315 3872 1307 3873 1306 3873 1527 3873 1527 3874 1306 3874 1320 3874 1527 3875 1320 3875 1528 3875 1528 3876 1320 3876 1319 3876 1528 3877 1319 3877 1530 3877 1530 3878 1319 3878 1318 3878 1530 3879 1318 3879 1313 3879 1305 3880 1304 3880 1514 3880 1514 3881 1304 3881 1303 3881 1514 3882 1303 3882 1515 3882 1515 3883 1303 3883 1302 3883 1515 3884 1302 3884 1517 3884 1517 3885 1302 3885 1312 3885 1517 3886 1312 3886 1311 3886 1445 3887 2134 3887 1535 3887 1535 3888 2134 3888 1536 3888 2134 3889 1277 3889 1536 3889 1536 3890 1277 3890 1276 3890 1536 3891 1276 3891 1281 3891 1538 3892 1287 3892 1534 3892 1534 3893 1287 3893 1285 3893 1534 3894 1285 3894 1448 3894 1281 3895 1282 3895 1536 3895 1536 3896 1282 3896 1269 3896 1536 3897 1269 3897 1537 3897 1537 3898 1269 3898 1268 3898 1537 3899 1268 3899 1538 3899 1538 3900 1268 3900 1289 3900 1538 3901 1289 3901 1288 3901 1329 3902 2133 3902 1328 3902 1328 3903 2133 3903 1327 3903 2133 3904 1532 3904 1327 3904 1327 3905 1532 3905 1525 3905 1327 3906 1525 3906 1325 3906 1325 3907 1525 3907 1265 3907 1285 3908 1284 3908 1448 3908 1448 3909 1284 3909 1293 3909 1448 3910 1293 3910 1548 3910 1548 3911 1293 3911 1549 3911 1549 3912 1293 3912 1291 3912 1549 3913 1291 3913 1550 3913 1550 3914 1291 3914 1290 3914 1550 3915 1290 3915 1298 3915 2049 3916 2047 3916 2135 3916 1880 3917 1718 3917 1719 3917 2136 3918 1736 3918 2137 3918 2137 3919 1736 3919 1735 3919 2137 3920 1735 3920 2138 3920 2138 3921 1735 3921 2139 3921 1735 3922 1733 3922 2139 3922 2139 3923 1733 3923 1731 3923 2139 3924 1731 3924 2140 3924 2140 3925 1731 3925 1730 3925 2140 3926 1730 3926 2141 3926 2141 3927 1730 3927 2142 3927 2143 3928 1819 3928 2144 3928 2144 3929 1819 3929 1817 3929 2144 3930 1817 3930 2145 3930 2145 3931 1817 3931 1815 3931 2145 3932 1815 3932 2146 3932 2146 3933 1815 3933 1814 3933 2146 3934 1814 3934 2147 3934 2147 3935 1814 3935 1740 3935 2147 3936 1740 3936 2136 3936 2136 3937 1740 3937 1738 3937 2136 3938 1738 3938 1736 3938 2148 3939 2149 3939 1719 3939 1719 3940 2149 3940 1881 3940 1719 3941 1881 3941 1880 3941 2150 3942 2151 3942 1714 3942 1714 3943 2151 3943 1716 3943 1716 3944 2151 3944 2152 3944 1716 3945 2152 3945 1723 3945 1719 3946 1720 3946 2148 3946 2148 3947 1720 3947 1722 3947 2148 3948 1722 3948 2153 3948 2153 3949 1722 3949 1723 3949 2153 3950 1723 3950 2154 3950 2154 3951 1723 3951 2152 3951 1813 3952 2049 3952 1812 3952 1812 3953 2049 3953 2135 3953 1812 3954 2135 3954 1811 3954 1811 3955 2135 3955 2155 3955 1811 3956 2155 3956 1729 3956 1729 3957 2155 3957 2156 3957 1729 3958 2156 3958 1727 3958 1727 3959 2156 3959 2142 3959 1727 3960 2142 3960 1726 3960 1726 3961 2142 3961 1730 3961 1714 3962 1698 3962 2150 3962 2150 3963 1698 3963 1697 3963 2150 3964 1697 3964 2157 3964 2157 3965 1697 3965 1822 3965 2157 3966 1822 3966 2143 3966 2143 3967 1822 3967 1821 3967 2143 3968 1821 3968 1819 3968 2158 3969 2159 3969 2160 3969 2161 3970 2162 3970 2163 3970 1348 3971 1347 3971 2164 3971 2165 3972 1367 3972 1365 3972 2166 3973 2167 3973 2168 3973 2169 3974 2170 3974 2171 3974 2172 3975 2173 3975 2171 3975 1380 3976 1379 3976 1901 3976 1901 3977 1379 3977 1414 3977 1901 3978 1414 3978 1275 3978 1380 3979 2174 3979 1382 3979 1382 3980 2174 3980 1383 3980 2175 3981 1972 3981 1980 3981 1898 3982 1974 3982 2175 3982 2175 3983 1974 3983 1973 3983 2175 3984 1973 3984 1972 3984 1380 3985 1901 3985 2174 3985 2174 3986 1901 3986 1899 3986 2174 3987 1899 3987 1383 3987 1422 3988 1257 3988 2176 3988 2176 3989 1257 3989 2175 3989 2176 3990 2175 3990 2160 3990 2160 3991 2175 3991 1980 3991 1899 3992 1898 3992 1383 3992 1383 3993 1898 3993 2175 3993 1383 3994 2175 3994 1256 3994 1256 3995 2175 3995 1257 3995 2177 3996 2178 3996 2179 3996 2179 3997 2178 3997 1373 3997 2179 3998 1373 3998 2180 3998 2170 3999 2180 3999 2171 3999 2171 4000 2180 4000 1373 4000 2171 4001 1373 4001 2172 4001 2172 4002 1373 4002 1372 4002 2181 4003 2169 4003 2182 4003 2182 4004 2169 4004 2171 4004 2182 4005 2171 4005 2183 4005 2183 4006 2171 4006 2173 4006 2183 4007 2173 4007 2184 4007 1372 4008 1370 4008 2172 4008 2172 4009 1370 4009 1369 4009 2172 4010 1369 4010 1378 4010 2185 4011 2186 4011 2187 4011 2187 4012 2186 4012 2188 4012 2167 4013 2189 4013 2185 4013 2167 4014 2166 4014 2189 4014 2189 4015 2166 4015 2190 4015 2189 4016 2190 4016 2191 4016 2191 4017 2190 4017 2192 4017 2191 4018 2192 4018 2193 4018 2194 4019 2195 4019 2196 4019 2194 4020 2164 4020 2197 4020 2197 4021 2164 4021 2198 4021 2197 4022 2198 4022 2199 4022 2168 4023 2200 4023 2166 4023 2166 4024 2200 4024 2201 4024 2166 4025 2201 4025 2190 4025 2190 4026 2201 4026 2202 4026 2190 4027 2202 4027 2192 4027 2192 4028 2202 4028 2203 4028 2192 4029 2203 4029 2193 4029 2193 4030 2203 4030 2204 4030 2177 4031 2179 4031 2205 4031 2205 4032 2179 4032 2180 4032 2205 4033 2180 4033 2206 4033 2206 4034 2180 4034 2170 4034 2206 4035 2170 4035 2207 4035 2207 4036 2170 4036 2169 4036 2207 4037 2169 4037 2188 4037 2188 4038 2169 4038 2181 4038 2188 4039 2181 4039 2187 4039 2208 4040 2209 4040 2210 4040 2210 4041 2209 4041 2211 4041 2212 4042 2213 4042 2214 4042 2214 4043 2213 4043 2215 4043 2214 4044 2215 4044 2216 4044 2217 4045 2165 4045 2218 4045 2208 4046 2210 4046 2219 4046 2219 4047 2210 4047 2220 4047 2219 4048 2220 4048 2221 4048 1368 4049 2222 4049 1362 4049 1362 4050 2222 4050 2223 4050 2224 4051 2225 4051 2226 4051 2226 4052 2225 4052 2227 4052 1357 4053 1356 4053 2228 4053 1351 4054 1350 4054 2198 4054 2198 4055 1350 4055 1358 4055 2198 4056 1358 4056 2226 4056 2226 4057 1358 4057 1357 4057 2226 4058 1357 4058 2224 4058 2224 4059 1357 4059 2228 4059 2224 4060 2228 4060 2225 4060 2225 4061 2228 4061 2229 4061 1348 4062 2164 4062 1402 4062 2194 4063 2196 4063 2164 4063 2164 4064 2196 4064 1407 4064 2164 4065 1407 4065 1402 4065 1347 4066 1345 4066 2164 4066 2164 4067 1345 4067 1344 4067 2164 4068 1344 4068 2198 4068 2198 4069 1344 4069 1353 4069 2198 4070 1353 4070 1351 4070 2222 4071 2221 4071 2223 4071 2223 4072 2221 4072 2220 4072 2223 4073 2220 4073 2229 4073 2229 4074 2220 4074 2210 4074 2229 4075 2210 4075 2225 4075 2225 4076 2210 4076 2211 4076 2225 4077 2211 4077 2227 4077 1356 4078 1260 4078 2228 4078 2228 4079 1260 4079 1259 4079 2228 4080 1259 4080 2229 4080 2229 4081 1259 4081 1360 4081 2229 4082 1360 4082 2223 4082 2223 4083 1360 4083 1363 4083 2223 4084 1363 4084 1362 4084 2230 4085 2231 4085 2232 4085 2232 4086 2231 4086 2233 4086 2232 4087 2233 4087 2234 4087 2162 4088 2235 4088 2163 4088 2163 4089 2235 4089 2236 4089 2163 4090 2236 4090 2233 4090 2233 4091 2236 4091 2237 4091 2233 4092 2237 4092 2234 4092 2238 4093 2239 4093 2240 4093 2240 4094 2239 4094 2241 4094 2231 4095 2242 4095 2233 4095 2233 4096 2242 4096 2238 4096 2233 4097 2238 4097 2163 4097 2163 4098 2238 4098 2240 4098 2163 4099 2240 4099 2161 4099 2161 4100 2240 4100 2241 4100 2161 4101 2241 4101 2243 4101 2244 4102 2245 4102 2246 4102 2066 4103 2131 4103 2247 4103 2244 4104 2246 4104 2247 4104 2247 4105 2246 4105 2248 4105 2247 4106 2248 4106 2066 4106 2243 4107 2245 4107 2161 4107 2161 4108 2245 4108 2244 4108 2161 4109 2244 4109 2162 4109 2162 4110 2244 4110 2249 4110 2162 4111 2249 4111 2235 4111 2235 4112 2249 4112 2250 4112 2235 4113 2250 4113 2236 4113 2236 4114 2250 4114 2251 4114 2236 4115 2251 4115 2237 4115 2237 4116 2251 4116 2252 4116 2237 4117 2252 4117 2234 4117 1983 4118 1982 4118 2158 4118 1980 4119 1979 4119 2160 4119 2160 4120 1979 4120 1978 4120 2160 4121 1978 4121 2158 4121 2158 4122 1978 4122 1977 4122 2158 4123 1977 4123 1983 4123 2159 4124 2253 4124 2160 4124 2160 4125 2253 4125 2184 4125 2160 4126 2184 4126 2176 4126 2176 4127 2184 4127 2173 4127 2176 4128 2173 4128 1422 4128 1422 4129 2173 4129 2172 4129 1422 4130 2172 4130 1376 4130 1376 4131 2172 4131 1378 4131 1376 4132 1378 4132 1377 4132 1342 4133 1343 4133 2196 4133 2128 4134 1340 4134 1341 4134 2130 4135 2129 4135 2195 4135 2195 4136 2129 4136 2128 4136 2195 4137 2128 4137 2196 4137 2196 4138 2128 4138 1341 4138 2196 4139 1341 4139 1342 4139 1343 4140 1263 4140 2196 4140 2196 4141 1263 4141 1262 4141 2196 4142 1262 4142 1407 4142 2203 4143 2216 4143 2204 4143 2204 4144 2216 4144 2215 4144 2204 4145 2215 4145 2254 4145 2254 4146 2215 4146 2213 4146 2254 4147 2213 4147 2255 4147 2255 4148 2213 4148 2212 4148 2255 4149 2212 4149 2256 4149 2256 4150 2212 4150 2217 4150 2256 4151 2217 4151 2257 4151 2257 4152 2217 4152 2218 4152 2257 4153 2218 4153 1375 4153 2165 4154 1365 4154 2218 4154 2218 4155 1365 4155 1364 4155 2218 4156 1364 4156 1375 4156 2185 4157 2189 4157 2186 4157 2186 4158 2189 4158 2191 4158 2186 4159 2191 4159 2188 4159 2188 4160 2191 4160 2193 4160 2188 4161 2193 4161 2207 4161 2207 4162 2193 4162 2204 4162 2207 4163 2204 4163 2206 4163 2206 4164 2204 4164 2254 4164 2206 4165 2254 4165 2205 4165 2205 4166 2254 4166 2255 4166 2205 4167 2255 4167 2177 4167 2177 4168 2255 4168 2256 4168 2177 4169 2256 4169 2178 4169 2178 4170 2256 4170 2257 4170 2178 4171 2257 4171 1373 4171 1373 4172 2257 4172 1375 4172 1373 4173 1375 4173 1374 4173 2131 4174 2130 4174 2247 4174 2247 4175 2130 4175 2195 4175 2247 4176 2195 4176 2244 4176 2244 4177 2195 4177 2194 4177 2244 4178 2194 4178 2249 4178 2249 4179 2194 4179 2197 4179 2249 4180 2197 4180 2250 4180 2250 4181 2197 4181 2199 4181 2250 4182 2199 4182 2251 4182 2251 4183 2199 4183 2258 4183 2251 4184 2258 4184 2252 4184 2252 4185 2258 4185 2259 4185 2252 4186 2259 4186 2234 4186 2234 4187 2259 4187 2260 4187 2234 4188 2260 4188 2232 4188 2232 4189 2260 4189 2261 4189 2232 4190 2261 4190 2230 4190 2230 4191 2261 4191 2262 4191 2253 4192 2263 4192 2184 4192 2184 4193 2263 4193 2264 4193 2184 4194 2264 4194 2183 4194 2183 4195 2264 4195 2265 4195 2183 4196 2265 4196 2182 4196 2182 4197 2265 4197 2266 4197 2182 4198 2266 4198 2267 4198 2267 4199 2262 4199 2182 4199 2182 4200 2262 4200 2261 4200 2182 4201 2261 4201 2181 4201 2181 4202 2261 4202 2260 4202 2181 4203 2260 4203 2187 4203 2187 4204 2260 4204 2259 4204 2187 4205 2259 4205 2185 4205 2185 4206 2259 4206 2258 4206 2185 4207 2258 4207 2167 4207 2167 4208 2258 4208 2199 4208 2167 4209 2199 4209 2168 4209 2168 4210 2199 4210 2198 4210 2168 4211 2198 4211 2200 4211 2200 4212 2198 4212 2226 4212 2200 4213 2226 4213 2201 4213 2201 4214 2226 4214 2227 4214 2201 4215 2227 4215 2202 4215 2202 4216 2227 4216 2211 4216 2202 4217 2211 4217 2203 4217 2203 4218 2211 4218 2209 4218 2203 4219 2209 4219 2216 4219 2216 4220 2209 4220 2208 4220 2216 4221 2208 4221 2214 4221 2214 4222 2208 4222 2219 4222 2214 4223 2219 4223 2212 4223 2212 4224 2219 4224 2221 4224 2212 4225 2221 4225 2217 4225 2217 4226 2221 4226 2222 4226 2217 4227 2222 4227 2165 4227 2165 4228 2222 4228 1368 4228 2165 4229 1368 4229 1367 4229 2059 4230 2057 4230 2268 4230 2269 4231 1890 4231 1881 4231 2061 4232 2060 4232 2270 4232 2271 4233 2272 4233 2273 4233 2253 4234 2159 4234 2269 4234 1890 4235 2269 4235 1889 4235 2158 4236 1982 4236 1981 4236 1889 4237 2269 4237 1981 4237 1981 4238 2269 4238 2159 4238 1981 4239 2159 4239 2158 4239 2274 4240 2275 4240 2276 4240 2276 4241 2275 4241 2277 4241 2276 4242 2277 4242 2278 4242 2278 4243 2277 4243 2279 4243 2278 4244 2279 4244 2280 4244 2281 4245 2275 4245 2263 4245 2263 4246 2275 4246 2274 4246 2263 4247 2274 4247 2264 4247 2264 4248 2274 4248 2265 4248 2242 4249 2231 4249 2282 4249 2282 4250 2231 4250 2230 4250 2282 4251 2230 4251 2283 4251 2283 4252 2230 4252 2262 4252 2283 4253 2262 4253 2267 4253 2248 4254 2246 4254 2284 4254 2284 4255 2246 4255 2285 4255 2284 4256 2285 4256 2286 4256 2052 4257 2054 4257 2286 4257 2050 4258 2052 4258 2287 4258 2287 4259 2052 4259 2286 4259 2287 4260 2286 4260 2288 4260 2288 4261 2286 4261 2289 4261 2288 4262 2289 4262 2290 4262 2290 4263 2289 4263 2291 4263 2290 4264 2291 4264 2292 4264 2292 4265 2291 4265 2293 4265 2292 4266 2293 4266 2294 4266 2294 4267 2293 4267 2295 4267 2294 4268 2295 4268 2273 4268 2246 4269 2245 4269 2285 4269 2285 4270 2245 4270 2243 4270 2285 4271 2243 4271 2296 4271 2296 4272 2243 4272 2241 4272 2296 4273 2241 4273 2297 4273 2297 4274 2241 4274 2239 4274 2297 4275 2239 4275 2238 4275 2286 4276 2285 4276 2289 4276 2289 4277 2285 4277 2296 4277 2289 4278 2296 4278 2291 4278 2291 4279 2296 4279 2297 4279 2291 4280 2297 4280 2293 4280 2293 4281 2297 4281 2238 4281 2293 4282 2238 4282 2295 4282 2273 4283 2272 4283 2294 4283 2294 4284 2272 4284 2298 4284 2294 4285 2298 4285 2292 4285 2292 4286 2298 4286 2299 4286 2292 4287 2299 4287 2290 4287 2290 4288 2299 4288 2300 4288 2290 4289 2300 4289 2288 4289 2288 4290 2300 4290 2301 4290 2288 4291 2301 4291 2287 4291 2287 4292 2301 4292 2302 4292 2287 4293 2302 4293 2268 4293 2268 4294 2057 4294 2287 4294 2287 4295 2057 4295 2056 4295 2287 4296 2056 4296 2050 4296 2303 4297 2145 4297 2304 4297 2304 4298 2145 4298 2146 4298 2304 4299 2146 4299 2305 4299 2305 4300 2146 4300 2147 4300 2305 4301 2147 4301 2306 4301 2306 4302 2147 4302 2136 4302 2306 4303 2136 4303 2307 4303 2307 4304 2136 4304 2137 4304 2308 4305 2141 4305 2142 4305 2308 4306 2142 4306 2309 4306 2137 4307 2138 4307 2307 4307 2307 4308 2138 4308 2139 4308 2307 4309 2139 4309 2308 4309 2308 4310 2139 4310 2140 4310 2308 4311 2140 4311 2141 4311 2047 4312 2061 4312 2135 4312 2135 4313 2061 4313 2270 4313 2135 4314 2270 4314 2155 4314 2155 4315 2270 4315 2309 4315 2155 4316 2309 4316 2156 4316 2156 4317 2309 4317 2142 4317 1881 4318 2149 4318 2269 4318 2269 4319 2149 4319 2281 4319 2269 4320 2281 4320 2253 4320 2253 4321 2281 4321 2263 4321 2066 4322 2248 4322 2064 4322 2064 4323 2248 4323 2284 4323 2064 4324 2284 4324 2062 4324 2062 4325 2284 4325 2286 4325 2062 4326 2286 4326 2055 4326 2055 4327 2286 4327 2054 4327 2265 4328 2274 4328 2266 4328 2266 4329 2274 4329 2276 4329 2266 4330 2276 4330 2267 4330 2267 4331 2276 4331 2278 4331 2267 4332 2278 4332 2283 4332 2283 4333 2278 4333 2280 4333 2283 4334 2280 4334 2282 4334 2060 4335 2059 4335 2270 4335 2270 4336 2059 4336 2268 4336 2270 4337 2268 4337 2309 4337 2309 4338 2268 4338 2302 4338 2309 4339 2302 4339 2308 4339 2308 4340 2302 4340 2301 4340 2308 4341 2301 4341 2307 4341 2307 4342 2301 4342 2300 4342 2307 4343 2300 4343 2306 4343 2306 4344 2300 4344 2299 4344 2306 4345 2299 4345 2305 4345 2305 4346 2299 4346 2298 4346 2305 4347 2298 4347 2304 4347 2304 4348 2298 4348 2272 4348 2304 4349 2272 4349 2303 4349 2303 4350 2272 4350 2271 4350 2303 4351 2271 4351 2310 4351 2149 4352 2148 4352 2281 4352 2281 4353 2148 4353 2153 4353 2281 4354 2153 4354 2275 4354 2275 4355 2153 4355 2154 4355 2275 4356 2154 4356 2277 4356 2277 4357 2154 4357 2152 4357 2277 4358 2152 4358 2151 4358 2150 4359 2157 4359 2310 4359 2310 4360 2157 4360 2143 4360 2310 4361 2143 4361 2303 4361 2303 4362 2143 4362 2144 4362 2303 4363 2144 4363 2145 4363 2151 4364 2150 4364 2277 4364 2277 4365 2150 4365 2310 4365 2277 4366 2310 4366 2279 4366 2279 4367 2310 4367 2271 4367 2279 4368 2271 4368 2280 4368 2280 4369 2271 4369 2273 4369 2280 4370 2273 4370 2282 4370 2282 4371 2273 4371 2295 4371 2282 4372 2295 4372 2242 4372 2242 4373 2295 4373 2238 4373

+
+
+
+
+ + + + + 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_forward_deck.dae b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_forward_deck.dae new file mode 100644 index 00000000..b9fcc4a0 --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_forward_deck.dae @@ -0,0 +1,89 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-04T12:20:31 + 2023-07-04T12:20:31 + + Z_UP + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + + + + + + + 0.02449995 0.01499998 0 0 0.01299995 0 0 0.01849997 0 0.06199997 0.01299995 0 0.05899995 0.002999961 0 0.05899995 0.01299995 0 0 0 0 0.05899995 0 0 0 0.002999961 0 -0.002999961 0.002999961 0 -0.002999961 0.01299995 0 0.0345 0.01499998 0 0.05899995 0.01849997 0 0.0345 0.01199996 0 0.02449995 0.01199996 0 0.06199997 0.002999961 0 0 0 0.002499997 0 0.002999961 0.002499997 0 0.002999961 0 0 0 0 0 0.002999961 0.002499997 -0.002999961 0.002999961 0.002499997 -0.002999961 0.002999961 0 0 0.002999961 0 -0.002999961 0.002999961 0 -0.002999961 0.01299995 0.002499997 -0.002999961 0.01299995 0 -0.002999961 0.002999961 0.002499997 -0.002999961 0.01299995 0 0 0.01299995 0.002499997 0 0.01299995 0 -0.002999961 0.01299995 0.002499997 0 0.01299995 0 0 0.01849997 0.002499997 0 0.01849997 0 0 0.01299995 0.002499997 0 0.01849997 0 0.05899995 0.01849997 0.002499997 0.05899995 0.01849997 0 0 0.01849997 0.002499997 0.05899995 0.01849997 0 0.05899995 0.01849997 0.002499997 0.05899995 0.01299995 0.002499997 0.05899995 0.01299995 0 0.05899995 0.01299995 0 0.06199997 0.01299995 0.002499997 0.06199997 0.01299995 0 0.05899995 0.01299995 0.002499997 0.06199997 0.01299995 0 0.06199997 0.01299995 0.002499997 0.06199997 0.002999961 0.002499997 0.06199997 0.002999961 0 0.06199997 0.002999961 0 0.06199997 0.002999961 0.002499997 0.05899995 0.002999961 0.002499997 0.05899995 0.002999961 0 0.05899995 0.002999961 0 0.05899995 0.002999961 0.002499997 0.05899995 0 0.002499997 0.05899995 0 0 0.05899995 0 0 0.05899995 0 0.002499997 0 0 0.002499997 0 0 0 0.0345 0.01199996 0.002499997 0.0345 0.01199996 0 0.02449995 0.01199996 0 0.02449995 0.01199996 0.002499997 0.0345 0.01199996 0.002499997 0.0345 0.01499998 0.002499997 0.0345 0.01499998 0 0.0345 0.01199996 0 0.0345 0.01499998 0.002499997 0.02449995 0.01499998 0 0.0345 0.01499998 0 0.02449995 0.01499998 0.002499997 0.02449995 0.01499998 0.002499997 0.02449995 0.01199996 0 0.02449995 0.01499998 0 0.02449995 0.01199996 0.002499997 0.05899995 0.002999961 0.002499997 0 0.002999961 0.002499997 0 0 0.002499997 0 0.01299995 0.002499997 -0.002999961 0.002999961 0.002499997 -0.002999961 0.01299995 0.002499997 0 0.01849997 0.002499997 0.02449995 0.01499998 0.002499997 0.05899995 0.01849997 0.002499997 0.02449995 0.01199996 0.002499997 0.05899995 0.01299995 0.002499997 0.0345 0.01499998 0.002499997 0.06199997 0.002999961 0.002499997 0.06199997 0.01299995 0.002499997 0.05899995 0 0.002499997 0.0345 0.01199996 0.002499997 0.00999999 0.01249998 0.07799994 0.04899996 0.01249998 0.07799994 0.04899996 0.01249998 0.06299996 0 0.01249998 0.08349996 0.006999969 0.01249998 0.07799994 0 0.01249998 0.06749999 0.06199997 0.01249998 0.05749994 0.05899995 0.01249998 0.05749994 0.05899995 0.01249998 0.06749999 0.06199997 0.01249998 0.06749999 0.06199997 0.01249998 0.04749995 0.06199997 0.01249998 0.03749996 0.05899995 0.01249998 0.04749995 0.06199997 0.01249998 0.01749998 0.05899995 0.01249998 0.02749997 0.06199997 0.01249998 0.02749997 0.00999999 0.01249998 0.06299996 0.00999999 0.01249998 0.023 0 0.01249998 0.04749995 0.04899996 0.01249998 0.023 0.05899995 0.01249998 0.03749996 0.02449995 0.01249998 0.002499997 0.0345 0.01249998 0.002499997 0.00999999 0.01249998 0.007999956 0.05899995 0.01249998 0.01749998 0.04899996 0.01249998 0.007999956 0.0345 0.01249998 -5.00008e-4 0.02449995 0.01249998 -5.00008e-4 0 0.01249998 0.01749998 0.006999969 0.01249998 0.007999956 0 0.01249998 0.002499997 0.006999969 0.01249998 0.06299996 -0.002999961 0.01249998 0.02749997 0 0.01249998 0.02749997 0.006999969 0.01249998 0.023 -0.002999961 0.01249998 0.01749998 -0.002999961 0.01249998 0.04749995 0 0.01249998 0.03749996 -0.002999961 0.01249998 0.03749996 0 0.01249998 0.05749994 -0.002999961 0.01249998 0.06749999 -0.002999961 0.01249998 0.05749994 0.05199998 0.01249998 0.023 0.05899995 0.01249998 0.002499997 0.05199998 0.01249998 0.007999956 0.05899995 0.01249998 0.08349996 0.05199998 0.01249998 0.06299996 0.05199998 0.01249998 0.07799994 0 0.01499998 0.08349996 0 0.01249998 0.06749999 0 0.01499998 0.06749999 0 0.01249998 0.08349996 0.05899995 0.01499998 0.08349996 0 0.01249998 0.08349996 0 0.01499998 0.08349996 0.05899995 0.01249998 0.08349996 0.05899995 0.01499998 0.06749999 0.05899995 0.01249998 0.08349996 0.05899995 0.01499998 0.08349996 0.05899995 0.01249998 0.06749999 0.06199997 0.01499998 0.06749999 0.05899995 0.01249998 0.06749999 0.05899995 0.01499998 0.06749999 0.06199997 0.01249998 0.06749999 0.06199997 0.01499998 0.05749994 0.06199997 0.01249998 0.06749999 0.06199997 0.01499998 0.06749999 0.06199997 0.01249998 0.05749994 0.05899995 0.01499998 0.05749994 0.06199997 0.01249998 0.05749994 0.06199997 0.01499998 0.05749994 0.05899995 0.01249998 0.05749994 0.05899995 0.01499998 0.04749995 0.05899995 0.01249998 0.05749994 0.05899995 0.01499998 0.05749994 0.05899995 0.01249998 0.04749995 0.06199997 0.01499998 0.04749995 0.05899995 0.01249998 0.04749995 0.05899995 0.01499998 0.04749995 0.06199997 0.01249998 0.04749995 0.06199997 0.01499998 0.03749996 0.06199997 0.01249998 0.04749995 0.06199997 0.01499998 0.04749995 0.06199997 0.01249998 0.03749996 0.05899995 0.01499998 0.03749996 0.06199997 0.01249998 0.03749996 0.06199997 0.01499998 0.03749996 0.05899995 0.01249998 0.03749996 0.05899995 0.01499998 0.02749997 0.05899995 0.01249998 0.03749996 0.05899995 0.01499998 0.03749996 0.05899995 0.01249998 0.02749997 0.06199997 0.01499998 0.02749997 0.05899995 0.01249998 0.02749997 0.05899995 0.01499998 0.02749997 0.06199997 0.01249998 0.02749997 0.06199997 0.01499998 0.01749998 0.06199997 0.01249998 0.02749997 0.06199997 0.01499998 0.02749997 0.06199997 0.01249998 0.01749998 0.05899995 0.01499998 0.01749998 0.06199997 0.01249998 0.01749998 0.06199997 0.01499998 0.01749998 0.05899995 0.01249998 0.01749998 0.05899995 0.01499998 0.002499997 0.05899995 0.01249998 0.01749998 0.05899995 0.01499998 0.01749998 0.05899995 0.01249998 0.002499997 0.0345 0.01499998 0.002499997 0.05899995 0.01249998 0.002499997 0.05899995 0.01499998 0.002499997 0.0345 0.01249998 0.002499997 0.0345 0.01499998 -5.00008e-4 0.0345 0.01249998 0.002499997 0.0345 0.01499998 0.002499997 0.0345 0.01249998 -5.00008e-4 0.02449995 0.01499998 -5.00008e-4 0.0345 0.01249998 -5.00008e-4 0.0345 0.01499998 -5.00008e-4 0.02449995 0.01249998 -5.00008e-4 0.02449995 0.01499998 0.002499997 0.02449995 0.01249998 -5.00008e-4 0.02449995 0.01499998 -5.00008e-4 0.02449995 0.01249998 0.002499997 0 0.01499998 0.002499997 0.02449995 0.01249998 0.002499997 0.02449995 0.01499998 0.002499997 0 0.01249998 0.002499997 0 0.01499998 0.01749998 0 0.01249998 0.002499997 0 0.01499998 0.002499997 0 0.01249998 0.01749998 -0.002999961 0.01499998 0.01749998 0 0.01249998 0.01749998 0 0.01499998 0.01749998 -0.002999961 0.01249998 0.01749998 -0.002999961 0.01499998 0.02749997 -0.002999961 0.01249998 0.01749998 -0.002999961 0.01499998 0.01749998 -0.002999961 0.01249998 0.02749997 0 0.01499998 0.02749997 -0.002999961 0.01249998 0.02749997 -0.002999961 0.01499998 0.02749997 0 0.01249998 0.02749997 0 0.01499998 0.03749996 0 0.01249998 0.02749997 0 0.01499998 0.02749997 0 0.01249998 0.03749996 -0.002999961 0.01499998 0.03749996 0 0.01249998 0.03749996 0 0.01499998 0.03749996 -0.002999961 0.01249998 0.03749996 -0.002999961 0.01499998 0.04749995 -0.002999961 0.01249998 0.03749996 -0.002999961 0.01499998 0.03749996 -0.002999961 0.01249998 0.04749995 0 0.01499998 0.04749995 -0.002999961 0.01249998 0.04749995 -0.002999961 0.01499998 0.04749995 0 0.01249998 0.04749995 0 0.01499998 0.05749994 0 0.01249998 0.04749995 0 0.01499998 0.04749995 0 0.01249998 0.05749994 -0.002999961 0.01499998 0.05749994 0 0.01249998 0.05749994 0 0.01499998 0.05749994 -0.002999961 0.01249998 0.05749994 -0.002999961 0.01499998 0.06749999 -0.002999961 0.01249998 0.05749994 -0.002999961 0.01499998 0.05749994 -0.002999961 0.01249998 0.06749999 0 0.01499998 0.06749999 -0.002999961 0.01249998 0.06749999 -0.002999961 0.01499998 0.06749999 0 0.01249998 0.06749999 0.00999999 0.01499998 0.07799994 0.006999969 0.01249998 0.07799994 0.00999999 0.01249998 0.07799994 0.006999969 0.01499998 0.07799994 0.006999969 0.01499998 0.07799994 0.006999969 0.01249998 0.06299996 0.006999969 0.01249998 0.07799994 0.006999969 0.01499998 0.06299996 0.006999969 0.01499998 0.06299996 0.00999999 0.01249998 0.06299996 0.006999969 0.01249998 0.06299996 0.00999999 0.01499998 0.06299996 0.00999999 0.01499998 0.06299996 0.00999999 0.01249998 0.07799994 0.00999999 0.01249998 0.06299996 0.00999999 0.01499998 0.07799994 0.00999999 0.01499998 0.023 0.006999969 0.01249998 0.023 0.00999999 0.01249998 0.023 0.006999969 0.01499998 0.023 0.006999969 0.01499998 0.023 0.006999969 0.01249998 0.007999956 0.006999969 0.01249998 0.023 0.006999969 0.01499998 0.007999956 0.006999969 0.01499998 0.007999956 0.00999999 0.01249998 0.007999956 0.006999969 0.01249998 0.007999956 0.00999999 0.01499998 0.007999956 0.00999999 0.01499998 0.007999956 0.00999999 0.01249998 0.023 0.00999999 0.01249998 0.007999956 0.00999999 0.01499998 0.023 0.05199998 0.01499998 0.023 0.04899996 0.01249998 0.023 0.05199998 0.01249998 0.023 0.04899996 0.01499998 0.023 0.04899996 0.01499998 0.023 0.04899996 0.01249998 0.007999956 0.04899996 0.01249998 0.023 0.04899996 0.01499998 0.007999956 0.04899996 0.01499998 0.007999956 0.05199998 0.01249998 0.007999956 0.04899996 0.01249998 0.007999956 0.05199998 0.01499998 0.007999956 0.05199998 0.01499998 0.007999956 0.05199998 0.01249998 0.023 0.05199998 0.01249998 0.007999956 0.05199998 0.01499998 0.023 0.05199998 0.01499998 0.07799994 0.04899996 0.01249998 0.07799994 0.05199998 0.01249998 0.07799994 0.04899996 0.01499998 0.07799994 0.04899996 0.01499998 0.07799994 0.04899996 0.01249998 0.06299996 0.04899996 0.01249998 0.07799994 0.04899996 0.01499998 0.06299996 0.04899996 0.01499998 0.06299996 0.05199998 0.01249998 0.06299996 0.04899996 0.01249998 0.06299996 0.05199998 0.01499998 0.06299996 0.05199998 0.01499998 0.06299996 0.05199998 0.01249998 0.07799994 0.05199998 0.01249998 0.06299996 0.05199998 0.01499998 0.07799994 0 0.01499998 0.05749994 0 0.01499998 0.06749999 -0.002999961 0.01499998 0.06749999 0.06199997 0.01499998 0.05749994 0.05899995 0.01499998 0.06749999 0.05899995 0.01499998 0.05749994 0.05199998 0.01499998 0.07799994 0.05199998 0.01499998 0.06299996 0.05899995 0.01499998 0.08349996 0.06199997 0.01499998 0.06749999 0.05899995 0.01499998 0.04749995 0.06199997 0.01499998 0.03749996 0.06199997 0.01499998 0.04749995 0.05899995 0.01499998 0.03749996 0.04899996 0.01499998 0.023 0.05199998 0.01499998 0.023 0 0.01499998 0.04749995 0.006999969 0.01499998 0.06299996 0.04899996 0.01499998 0.06299996 0.06199997 0.01499998 0.02749997 0.05899995 0.01499998 0.02749997 0.06199997 0.01499998 0.01749998 0.05899995 0.01499998 0.01749998 0.00999999 0.01499998 0.023 0.00999999 0.01499998 0.06299996 0.04899996 0.01499998 0.007999956 0.0345 0.01499998 0.002499997 0.05899995 0.01499998 0.002499997 0.05199998 0.01499998 0.007999956 0.0345 0.01499998 -5.00008e-4 0.02449995 0.01499998 0.002499997 0.02449995 0.01499998 -5.00008e-4 0.00999999 0.01499998 0.007999956 0 0.01499998 0.002499997 0.006999969 0.01499998 0.007999956 0 0.01499998 0.01749998 0 0.01499998 0.02749997 -0.002999961 0.01499998 0.02749997 -0.002999961 0.01499998 0.01749998 -0.002999961 0.01499998 0.05749994 0 0.01499998 0.03749996 -0.002999961 0.01499998 0.04749995 -0.002999961 0.01499998 0.03749996 0.006999969 0.01499998 0.07799994 0 0.01499998 0.08349996 0.04899996 0.01499998 0.07799994 0.00999999 0.01499998 0.07799994 0.006999969 0.01499998 0.023 0 0.005991578 0.08850622 0 0 0.06349992 0 0 0.08049994 0 0.009581387 0.09830993 0 0.01198327 0.09651243 0 0 0.01349997 0 -0.002999961 0.02849996 0 0 0.02849996 0 0.003589749 0.09030371 0 0.01299995 -5.00023e-4 0 0.01832854 -0.004035174 0 0.01407486 -0.008590102 0 0.02156466 0.1143226 0 0.01797485 0.1045188 0 0.01557296 0.1063163 0 0.03374266 0.08728843 0 0.031479 0.05027693 0 0.01499998 0.06749993 0 0.02396649 0.1125251 0 0.01199996 0.05749994 0 0.01199996 0.06749993 0 0.03295397 0.1245344 0 0.01499998 0.01749992 0 0.01499998 0.02749997 0 0.02437257 0.007009863 0 0.02176117 0.001164734 0 0 0.04849994 0 0.01299995 0.002499938 0 0.01199996 0.03749996 0 0.01199996 0.02749997 0 0.00767523 -0.01222711 0 0.002999961 -5.00023e-4 0 0.002999961 0.002499938 0 0.01199996 0.01749992 0 0.006378293 -0.01184332 0 0.00288105 -0.009832918 0 0.003949463 -0.01066237 0 0.00512731 -0.01132827 0 6.65358e-4 -0.006481885 0 0 -0.002499997 0 2.91941e-4 -0.005183696 0 7.69764e-5 -0.003850221 0 0.001961052 -0.008842706 0 0.001218914 -0.007713913 0 -0.002999961 0.01349997 0 -0.002999961 0.06349992 0 -0.002999961 0.04849994 0 0.01499998 0.05749994 0 0.01499998 0.04749995 0 0.02616298 0.01349997 0 0.01499998 0.03749996 0 0.008999943 -0.01249998 0 0.01199996 0.04749995 0 0 0.08049994 -0.002499938 0 0.06349992 -0.002499938 0 0.08049994 0 0 0.06349992 -0.002499997 0.005991578 0.08850622 0 0 0.08049994 -0.002499938 0 0.08049994 0 0.005991578 0.08850622 -0.002499997 0.003589749 0.09030371 0 0.005991578 0.08850622 -0.002499997 0.005991578 0.08850622 0 0.003589749 0.09030371 -0.002499997 0.009581387 0.09830993 0 0.003589749 0.09030371 -0.002499997 0.003589749 0.09030371 0 0.009581387 0.09830993 -0.002499997 0.01198327 0.09651243 0 0.009581387 0.09830993 -0.002499997 0.009581387 0.09830993 0 0.01198327 0.09651243 -0.002499997 0.01797485 0.1045188 0 0.01198327 0.09651243 -0.002499997 0.01198327 0.09651243 0 0.01797485 0.1045188 -0.002499997 0.01557296 0.1063163 0 0.01797485 0.1045188 -0.002499997 0.01797485 0.1045188 0 0.01557296 0.1063163 -0.002499997 0.02156466 0.1143226 0 0.01557296 0.1063163 -0.002499997 0.01557296 0.1063163 0 0.02156466 0.1143226 -0.002499997 0.02396649 0.1125251 0 0.02156466 0.1143226 -0.002499997 0.02156466 0.1143226 0 0.02396649 0.1125251 -0.002499997 0.03295397 0.1245344 0 0.02396649 0.1125251 -0.002499997 0.02396649 0.1125251 0 0.03295397 0.1245344 0 0.03374266 0.08728843 0 0.03295397 0.1245344 -0.002499997 0.03374266 0.08728843 -0.002499997 0.031479 0.05027693 -0.002499997 0.03295397 0.1245344 0 0.031479 0.05027693 -0.002499938 0.02616298 0.01349997 0 0.02616298 0.01349997 0 0.02437257 0.007009863 -0.002499938 0.02176117 0.001164734 0 0.02176117 0.001164734 -0.002499938 0.01832854 -0.004035174 0 0.02616298 0.01349997 -0.002499938 0.02616298 0.01349997 -0.002499938 0.02437257 0.007009863 0 0.01832854 -0.004035174 -0.002499938 0.01407486 -0.008590102 0 0.01407486 -0.008590102 -0.002499938 0.008999943 -0.01249998 0 0.008999943 -0.01249998 0 0.003949463 -0.01066237 -0.002499938 0.002887427 -0.009835004 0 0.00288105 -0.009832918 -0.002499938 0.001964688 -0.008847773 0 0.00512731 -0.01132827 -0.002499938 0.003955721 -0.01066148 -0.002499938 0.005131661 -0.01132619 0 0.006378293 -0.01184332 -0.002499938 0.006380617 -0.01184141 0 0.00767523 -0.01222711 -0.002499938 0.007675468 -0.01222711 0 0.008999943 -0.01249998 -0.002499938 0.008999943 -0.01249998 0 0.001961052 -0.008842706 -0.002499938 0.001218676 -0.007719814 0 0.001218914 -0.007713913 0 6.65358e-4 -0.006481885 -0.002499938 6.63035e-4 -0.006486475 -0.002499938 2.89589e-4 -0.0051862 0 2.91941e-4 -0.005183696 -0.002499938 7.69971e-5 -0.0038504 0 7.69764e-5 -0.003850221 -0.002499938 0 -0.002499997 0 0 -0.002499997 -0.002499938 0 0.01349997 0 0 -0.002499997 -0.002499938 0 -0.002499997 0 0 0.01349997 0 -0.002999961 0.01349997 0 0 0.01349997 -0.002499938 0 0.01349997 -0.002499938 -0.002999961 0.01349997 -0.002499938 -0.002999961 0.02849996 0 -0.002999961 0.01349997 -0.002499938 -0.002999961 0.01349997 0 -0.002999961 0.02849996 0 0 0.02849996 -0.002499938 -0.002999961 0.02849996 -0.002499938 0 0.02849996 0 -0.002999961 0.02849996 -0.002499938 0 0.04849994 0 0 0.02849996 -0.002499938 0 0.02849996 0 0 0.04849994 0 -0.002999961 0.04849994 0 0 0.04849994 -0.002499938 0 0.04849994 -0.002499938 -0.002999961 0.04849994 -0.002499938 -0.002999961 0.06349992 0 -0.002999961 0.04849994 -0.002499938 -0.002999961 0.04849994 0 -0.002999961 0.06349992 0 0 0.06349992 -0.002499938 -0.002999961 0.06349992 -0.002499938 0 0.06349992 0 -0.002999961 0.06349992 -0.002499938 0.01199996 0.01749992 0 0.01199996 0.02749997 -0.002499938 0.01199996 0.02749997 0 0.01199996 0.01749992 -0.002499938 0.01499998 0.01749992 0 0.01499998 0.01749992 0 0.01199996 0.01749992 -0.002499938 0.01199996 0.01749992 -0.002499938 0.01499998 0.01749992 0 0.01499998 0.02749997 0 0.01499998 0.01749992 -0.002499938 0.01499998 0.02749997 -0.002499938 0.01199996 0.02749997 0 0.01499998 0.02749997 -0.002499938 0.01499998 0.02749997 0 0.01199996 0.02749997 -0.002499938 0.01199996 0.03749996 0 0.01199996 0.04749995 -0.002499938 0.01199996 0.04749995 0 0.01199996 0.03749996 -0.002499938 0.01499998 0.03749996 0 0.01499998 0.03749996 0 0.01199996 0.03749996 -0.002499938 0.01199996 0.03749996 -0.002499938 0.01499998 0.03749996 0 0.01499998 0.04749995 0 0.01499998 0.03749996 -0.002499938 0.01499998 0.04749995 -0.002499938 0.01199996 0.04749995 0 0.01499998 0.04749995 -0.002499938 0.01499998 0.04749995 0 0.01199996 0.04749995 -0.002499938 0.01199996 0.05749994 0 0.01199996 0.06749993 -0.002499938 0.01199996 0.06749993 0 0.01199996 0.05749994 -0.002499938 0.01499998 0.05749994 0 0.01499998 0.05749994 0 0.01199996 0.05749994 -0.002499938 0.01199996 0.05749994 -0.002499938 0.01499998 0.05749994 0 0.01499998 0.06749993 0 0.01499998 0.05749994 -0.002499997 0.01499998 0.06749993 -0.002499938 0.01199996 0.06749993 0 0.01499998 0.06749993 -0.002499997 0.01499998 0.06749993 0 0.01199996 0.06749993 -0.002499938 0.002999961 0.002499938 0 0.002999961 -5.00023e-4 0 0.002999961 0.002499938 -0.002499938 0.002999961 -5.00023e-4 -0.002499938 0.01299995 -5.00023e-4 0 0.01299995 -5.00023e-4 0 0.002999961 -5.00023e-4 -0.002499938 0.002999961 -5.00023e-4 -0.002499938 0.01299995 0.002499938 0 0.01299995 0.002499938 0 0.01299995 -5.00023e-4 -0.002499938 0.01299995 -5.00023e-4 -0.002499938 0.002999961 0.002499938 0 0.01299995 0.002499938 -0.002499938 0.01299995 0.002499938 0 0.002999961 0.002499938 -0.002499938 0 0.04849994 -0.002499938 0 0.06349992 -0.002499938 -0.002999961 0.06349992 -0.002499938 0.01499998 0.01749992 -0.002499938 0.02176117 0.001164734 -0.002499938 0.02437257 0.007009863 -0.002499997 0.009581387 0.09830993 -0.002499997 0.005991578 0.08850622 -0.002499997 0.01198327 0.09651243 -0.002499938 0 0.08049994 -0.002499997 0.003589749 0.09030371 -0.002499938 0.01499998 0.02749997 -0.002499938 0.02616298 0.01349997 -0.002499938 0.01499998 0.03749996 -0.002499997 0.02156466 0.1143226 -0.002499997 0.01557296 0.1063163 -0.002499997 0.01797485 0.1045188 -0.002499997 0.03374266 0.08728843 -0.002499997 0.01499998 0.06749993 -0.002499997 0.031479 0.05027693 -0.002499997 0.02396649 0.1125251 -0.002499997 0.03295397 0.1245344 -0.002499938 0.01832854 -0.004035174 -0.002499938 0.01299995 -5.00023e-4 -0.002499938 0.008999943 -0.01249998 -0.002499938 0.01407486 -0.008590102 -0.002499938 0.002999961 -5.00023e-4 -0.002499938 0.005131661 -0.01132619 -0.002499938 0.006380617 -0.01184141 -0.002499938 0.01199996 0.06749993 -0.002499938 0.002999961 0.002499938 -0.002499938 0.01199996 0.01749992 -0.002499938 0 0.02849996 -0.002499938 0.01199996 0.02749997 -0.002499938 0 -0.002499997 -0.002499938 0 0.01349997 -0.002499938 2.89589e-4 -0.0051862 -0.002499938 6.63035e-4 -0.006486475 -0.002499938 7.69971e-5 -0.0038504 -0.002499938 0.001218676 -0.007719814 -0.002499938 0.001964688 -0.008847773 -0.002499938 0.003955721 -0.01066148 -0.002499938 -0.002999961 0.04849994 -0.002499938 -0.002999961 0.02849996 -0.002499938 -0.002999961 0.01349997 -0.002499938 0.007675468 -0.01222711 -0.002499938 0.01499998 0.04749995 -0.002499938 0.01299995 0.002499938 -0.002499938 0.01199996 0.03749996 -0.002499938 0.01199996 0.04749995 -0.002499938 0.01499998 0.05749994 -0.002499938 0.01199996 0.05749994 -0.002499938 0.002887427 -0.009835004 0.07899999 0 0.08049994 -0.01899999 -0.002499938 0.08049994 -0.01899999 0 0.08049994 0.07899999 -0.002499938 0.08049994 0.07560378 -0.002499938 0.04990947 0.07899999 -0.002499938 0.08049994 0.07560378 0 0.04990947 0.06927049 0 0.01990944 0.07899999 0 0.08049994 0.06927049 -0.002499938 0.01990944 0.06 0 -0.009499967 0.06 -0.002499938 -0.009499967 5.00005e-4 0 0.06349992 -0.002499938 -0.002499938 0.06349992 5.00005e-4 -0.002499938 0.06349992 -0.002499938 0 0.06349992 -0.002499938 0 0.06349992 -0.002499938 -0.002499938 0.04849994 -0.002499938 -0.002499938 0.06349992 -0.002499938 0 0.04849994 -0.002499938 0 0.04849994 5.00005e-4 -0.002499938 0.04849994 -0.002499938 -0.002499938 0.04849994 5.00005e-4 0 0.04849994 5.00005e-4 0 0.04849994 5.00005e-4 -0.002499938 0.06349992 5.00005e-4 -0.002499938 0.04849994 5.00005e-4 0 0.06349992 0.0625 0 0.02849996 0.05949997 -0.002499938 0.02849996 0.0625 -0.002499938 0.02849996 0.05949997 0 0.02849996 0.05949997 0 0.02849996 0.05949997 -0.002499938 0.01349997 0.05949997 -0.002499938 0.02849996 0.05949997 0 0.01349997 0.05949997 0 0.01349997 0.0625 -0.002499938 0.01349997 0.05949997 -0.002499938 0.01349997 0.0625 0 0.01349997 0.0625 0 0.01349997 0.0625 -0.002499938 0.02849996 0.0625 -0.002499938 0.01349997 0.0625 0 0.02849996 0.0625 0 0.06349992 0.05949997 -0.002499938 0.06349992 0.0625 -0.002499938 0.06349992 0.05949997 0 0.06349992 0.05949997 0 0.06349992 0.05949997 -0.002499938 0.04849994 0.05949997 -0.002499938 0.06349992 0.05949997 0 0.04849994 0.05949997 0 0.04849994 0.0625 -0.002499938 0.04849994 0.05949997 -0.002499938 0.04849994 0.0625 0 0.04849994 0.0625 0 0.04849994 0.0625 -0.002499938 0.06349992 0.0625 -0.002499938 0.04849994 0.0625 0 0.06349992 5.00005e-4 0 0.02849996 -0.002499938 -0.002499938 0.02849996 5.00005e-4 -0.002499938 0.02849996 -0.002499938 0 0.02849996 -0.002499938 0 0.02849996 -0.002499938 -0.002499938 0.01349997 -0.002499938 -0.002499938 0.02849996 -0.002499938 0 0.01349997 -0.002499938 0 0.01349997 5.00005e-4 -0.002499938 0.01349997 -0.002499938 -0.002499938 0.01349997 5.00005e-4 0 0.01349997 5.00005e-4 0 0.01349997 5.00005e-4 -0.002499938 0.02849996 5.00005e-4 -0.002499938 0.01349997 5.00005e-4 0 0.02849996 -0.009270489 0 0.01990944 0 -0.002499938 -0.009499967 0 0 -0.009499967 -0.009270489 -0.002499938 0.01990944 -0.01560384 0 0.04990947 -0.01560384 -0.002499938 0.04990947 -0.01899999 0 0.08049994 -0.01899999 -0.002499938 0.08049994 0.0625 -0.002499938 0.01349997 0.0625 -0.002499938 0.02849996 0.06927049 -0.002499938 0.01990944 5.00005e-4 -0.002499938 0.04849994 5.00005e-4 -0.002499938 0.02849996 -0.002499938 -0.002499938 0.04849994 5.00005e-4 -0.002499938 0.06349992 0.05949997 -0.002499938 0.04849994 5.00005e-4 -0.002499938 0.01349997 0.02474015 -0.002499938 -0.02739799 0.01960897 -0.002499938 -0.02617096 0.05379086 -0.002499938 -0.01799178 0.05949997 -0.002499938 0.01349997 0.0572285 -0.002499938 -0.01398938 0.0497713 -0.002499938 -0.02140897 0.03525978 -0.002499938 -0.02739799 0.04039096 -0.002499938 -0.02617096 0.04526787 -0.002499938 -0.024158 0.02999997 -0.002499938 -0.02781099 0.01473206 -0.002499938 -0.024158 0.006209075 -0.002499938 -0.01799178 0.01022869 -0.002499938 -0.02140897 0.002771496 -0.002499938 -0.01398938 0 -0.002499938 -0.009499967 -0.002499938 -0.002499938 0.01349997 -0.01899999 -0.002499938 0.08049994 0.07899999 -0.002499938 0.08049994 0.05949997 -0.002499938 0.06349992 0.07560378 -0.002499938 0.04990947 0.0625 -0.002499938 0.04849994 0.0625 -0.002499938 0.06349992 -0.01560384 -0.002499938 0.04990947 -0.002499938 -0.002499938 0.06349992 -0.002499938 -0.002499938 0.02849996 0.06 -0.002499938 -0.009499967 0.05949997 -0.002499938 0.02849996 -0.009270489 -0.002499938 0.01990944 0.04526787 -0.002499938 -0.024158 0.0497713 -0.002499938 -0.02140897 0.0497713 0 -0.02140897 0.05379086 -0.002499938 -0.01799178 0.05379086 0 -0.01799178 0.0572285 0 -0.01398938 0.0572285 -0.002499938 -0.01398938 0.06 0 -0.009499967 0.06 -0.002499938 -0.009499967 0.04526787 0 -0.024158 0.04039096 -0.002499938 -0.02617096 0.04039096 0 -0.02617096 0.03525978 0 -0.02739799 0.03525978 -0.002499938 -0.02739799 0.02999997 -0.002499938 -0.02781099 0.02999997 0 -0.02781099 0.0572285 0 -0.01398938 0.05949997 0 0.01349997 0.05379086 0 -0.01799178 0.07899999 0 0.08049994 -0.01899999 0 0.08049994 0.05949997 0 0.06349992 0.0497713 0 -0.02140897 0.04526787 0 -0.024158 0.04039096 0 -0.02617096 5.00005e-4 0 0.01349997 0.02474015 0 -0.02739799 0.02999997 0 -0.02781099 0.03525978 0 -0.02739799 0 0 -0.009499967 -0.002499938 0 0.01349997 0.01022869 0 -0.02140897 0.006209075 0 -0.01799178 0.002771496 0 -0.01398938 0.01473206 0 -0.024158 0.01960897 0 -0.02617096 -0.01560384 0 0.04990947 -0.002499938 0 0.02849996 -0.002499938 0 0.04849994 0.05949997 0 0.02849996 0.0625 0 0.02849996 0.05949997 0 0.04849994 -0.002499938 0 0.06349992 5.00005e-4 0 0.06349992 5.00005e-4 0 0.02849996 5.00005e-4 0 0.04849994 0.0625 0 0.01349997 0.06927049 0 0.01990944 0.0625 0 0.06349992 0.07560378 0 0.04990947 0.0625 0 0.04849994 0.06 0 -0.009499967 -0.009270489 0 0.01990944 0.01960897 -0.002499938 -0.02617096 0.02474015 0 -0.02739799 0.01960897 0 -0.02617096 0.02999997 0 -0.02781099 0.02474015 -0.002499938 -0.02739799 0.02999997 -0.002499938 -0.02781099 0.01022869 0 -0.02140897 0.006209075 0 -0.01799178 0.006209075 -0.002499938 -0.01799178 0.01022869 -0.002499938 -0.02140897 0.01473206 -0.002499938 -0.024158 0.01473206 0 -0.024158 0.002771496 0 -0.01398938 0 -0.002499938 -0.009499967 0.002771496 -0.002499938 -0.01398938 0 0 -0.009499967 0.06149995 0.005991578 0.08850622 0.06149995 0 0.06349992 0.06149995 0 0.08049994 0.06149995 0.009581387 0.09830993 0.06149995 0.01198327 0.09651243 0.06150001 0 0.01349997 0.06150001 -0.002999961 0.02849996 0.06150001 0 0.02849996 0.06149995 0.003589749 0.09030371 0.06150001 0.01299995 -5.00023e-4 0.06150001 0.01832854 -0.004035174 0.06150001 0.01407486 -0.008590102 0.06149995 0.02156466 0.1143226 0.06149995 0.01797485 0.1045188 0.06149995 0.01557296 0.1063163 0.06149995 0.03374266 0.08728843 0.06149995 0.031479 0.05027693 0.06149995 0.01499998 0.06749993 0.06149995 0.02396649 0.1125251 0.06149995 0.01199996 0.05749994 0.06149995 0.01199996 0.06749993 0.06149995 0.03295397 0.1245344 0.06150001 0.01499998 0.01749992 0.06150001 0.01499998 0.02749997 0.06150001 0.02437257 0.007009863 0.06150001 0.02176117 0.001164734 0.06150001 0 0.04849994 0.06150001 0.01299995 0.002499938 0.06150001 0.01199996 0.03749996 0.06150001 0.01199996 0.02749997 0.06150001 0.00767523 -0.01222711 0.06150001 0.002999961 -5.00023e-4 0.06150001 0.002999961 0.002499938 0.06150001 0.01199996 0.01749992 0.06150001 0.006378293 -0.01184332 0.06150001 0.00288105 -0.009832918 0.06150001 0.003949463 -0.01066237 0.06150001 0.00512731 -0.01132827 0.06150001 6.65358e-4 -0.006481885 0.06150001 0 -0.002499997 0.06150001 2.91941e-4 -0.005183696 0.06150001 7.69764e-5 -0.003850221 0.06150001 0.001961052 -0.008842706 0.06150001 0.001218914 -0.007713913 0.06150001 -0.002999961 0.01349997 0.06150001 -0.002999961 0.06349992 0.06150001 -0.002999961 0.04849994 0.06149995 0.01499998 0.05749994 0.06149995 0.01499998 0.04749995 0.06150001 0.02616298 0.01349997 0.06150001 0.01499998 0.03749996 0.06150001 0.008999943 -0.01249998 0.06149995 0.01199996 0.04749995 0.06149995 0 0.08049994 0.05899995 0 0.06349992 0.05899995 0 0.08049994 0.06149995 0 0.06349992 0.05899995 0.005991578 0.08850622 0.06149995 0 0.08049994 0.05899995 0 0.08049994 0.06149995 0.005991578 0.08850622 0.05899995 0.003589749 0.09030371 0.06149995 0.005991578 0.08850622 0.05899995 0.005991578 0.08850622 0.06149995 0.003589749 0.09030371 0.05899995 0.009581387 0.09830993 0.06149995 0.003589749 0.09030371 0.05899995 0.003589749 0.09030371 0.06149995 0.009581387 0.09830993 0.05899995 0.01198327 0.09651243 0.06149995 0.009581387 0.09830993 0.05899995 0.009581387 0.09830993 0.06149995 0.01198327 0.09651243 0.05899995 0.01797485 0.1045188 0.06149995 0.01198327 0.09651243 0.05899995 0.01198327 0.09651243 0.06149995 0.01797485 0.1045188 0.05899995 0.01557296 0.1063163 0.06149995 0.01797485 0.1045188 0.05899995 0.01797485 0.1045188 0.06149995 0.01557296 0.1063163 0.05899995 0.02156466 0.1143226 0.06149995 0.01557296 0.1063163 0.05899995 0.01557296 0.1063163 0.06149995 0.02156466 0.1143226 0.05899995 0.02396649 0.1125251 0.06149995 0.02156466 0.1143226 0.05899995 0.02156466 0.1143226 0.06149995 0.02396649 0.1125251 0.05899995 0.03295397 0.1245344 0.06149995 0.02396649 0.1125251 0.05899995 0.02396649 0.1125251 0.06149995 0.03295397 0.1245344 0.06149995 0.03374266 0.08728843 0.06149995 0.03295397 0.1245344 0.05899995 0.03374266 0.08728843 0.05899995 0.031479 0.05027693 0.05899995 0.03295397 0.1245344 0.06149995 0.031479 0.05027693 0.05899995 0.02616298 0.01349997 0.06150001 0.02616298 0.01349997 0.06150001 0.02437257 0.007009863 0.05900001 0.02176117 0.001164734 0.06150001 0.02176117 0.001164734 0.05900001 0.01832854 -0.004035174 0.06150001 0.02616298 0.01349997 0.05899995 0.02616298 0.01349997 0.05899995 0.02437257 0.007009863 0.06150001 0.01832854 -0.004035174 0.05900001 0.01407486 -0.008590102 0.06150001 0.01407486 -0.008590102 0.05900001 0.008999943 -0.01249998 0.06150001 0.008999943 -0.01249998 0.06150001 0.003949463 -0.01066237 0.05900001 0.002887427 -0.009835004 0.06150001 0.00288105 -0.009832918 0.05900001 0.001964688 -0.008847773 0.06150001 0.00512731 -0.01132827 0.05900001 0.003955721 -0.01066148 0.05900001 0.005131661 -0.01132619 0.06150001 0.006378293 -0.01184332 0.05900001 0.006380617 -0.01184141 0.06150001 0.00767523 -0.01222711 0.05900001 0.007675468 -0.01222711 0.06150001 0.008999943 -0.01249998 0.05900001 0.008999943 -0.01249998 0.06150001 0.001961052 -0.008842706 0.05900001 0.001218676 -0.007719814 0.06150001 0.001218914 -0.007713913 0.06150001 6.65358e-4 -0.006481885 0.05900001 6.63035e-4 -0.006486475 0.05900001 2.89589e-4 -0.0051862 0.06150001 2.91941e-4 -0.005183696 0.05900001 7.69971e-5 -0.0038504 0.06150001 7.69764e-5 -0.003850221 0.05900001 0 -0.002499997 0.06150001 0 -0.002499997 0.05900001 0 0.01349997 0.06150001 0 -0.002499997 0.05900001 0 -0.002499997 0.06150001 0 0.01349997 0.06150001 -0.002999961 0.01349997 0.06150001 0 0.01349997 0.05900001 0 0.01349997 0.05900001 -0.002999961 0.01349997 0.05900001 -0.002999961 0.02849996 0.06150001 -0.002999961 0.01349997 0.05900001 -0.002999961 0.01349997 0.06150001 -0.002999961 0.02849996 0.06150001 0 0.02849996 0.05900001 -0.002999961 0.02849996 0.05900001 0 0.02849996 0.06150001 -0.002999961 0.02849996 0.05899995 0 0.04849994 0.06150001 0 0.02849996 0.05900001 0 0.02849996 0.06150001 0 0.04849994 0.06150001 -0.002999961 0.04849994 0.06150001 0 0.04849994 0.05899995 0 0.04849994 0.05899995 -0.002999961 0.04849994 0.05899995 -0.002999961 0.06349992 0.06150001 -0.002999961 0.04849994 0.05899995 -0.002999961 0.04849994 0.06150001 -0.002999961 0.06349992 0.06149995 0 0.06349992 0.05899995 -0.002999961 0.06349992 0.05899995 0 0.06349992 0.06150001 -0.002999961 0.06349992 0.05900001 0.01199996 0.01749992 0.06150001 0.01199996 0.02749997 0.05899995 0.01199996 0.02749997 0.06150001 0.01199996 0.01749992 0.05900001 0.01499998 0.01749992 0.06150001 0.01499998 0.01749992 0.06150001 0.01199996 0.01749992 0.05900001 0.01199996 0.01749992 0.05900001 0.01499998 0.01749992 0.06150001 0.01499998 0.02749997 0.06150001 0.01499998 0.01749992 0.05899995 0.01499998 0.02749997 0.05899995 0.01199996 0.02749997 0.06150001 0.01499998 0.02749997 0.05899995 0.01499998 0.02749997 0.06150001 0.01199996 0.02749997 0.05899995 0.01199996 0.03749996 0.06149995 0.01199996 0.04749995 0.05899995 0.01199996 0.04749995 0.06150001 0.01199996 0.03749996 0.05899995 0.01499998 0.03749996 0.06150001 0.01499998 0.03749996 0.06150001 0.01199996 0.03749996 0.05899995 0.01199996 0.03749996 0.05899995 0.01499998 0.03749996 0.06149995 0.01499998 0.04749995 0.06150001 0.01499998 0.03749996 0.05899995 0.01499998 0.04749995 0.05899995 0.01199996 0.04749995 0.06149995 0.01499998 0.04749995 0.05899995 0.01499998 0.04749995 0.06149995 0.01199996 0.04749995 0.05899995 0.01199996 0.05749994 0.06149995 0.01199996 0.06749993 0.05899995 0.01199996 0.06749993 0.06149995 0.01199996 0.05749994 0.05899995 0.01499998 0.05749994 0.06149995 0.01499998 0.05749994 0.06149995 0.01199996 0.05749994 0.05899995 0.01199996 0.05749994 0.05899995 0.01499998 0.05749994 0.06149995 0.01499998 0.06749993 0.06149995 0.01499998 0.05749994 0.05899995 0.01499998 0.06749993 0.05899995 0.01199996 0.06749993 0.06149995 0.01499998 0.06749993 0.05899995 0.01499998 0.06749993 0.06149995 0.01199996 0.06749993 0.05900001 0.002999961 0.002499938 0.06150001 0.002999961 -5.00023e-4 0.06150001 0.002999961 0.002499938 0.05900001 0.002999961 -5.00023e-4 0.05900001 0.01299995 -5.00023e-4 0.06150001 0.01299995 -5.00023e-4 0.06150001 0.002999961 -5.00023e-4 0.05900001 0.002999961 -5.00023e-4 0.05900001 0.01299995 0.002499938 0.06150001 0.01299995 0.002499938 0.06150001 0.01299995 -5.00023e-4 0.05900001 0.01299995 -5.00023e-4 0.05900001 0.002999961 0.002499938 0.06150001 0.01299995 0.002499938 0.05900001 0.01299995 0.002499938 0.06150001 0.002999961 0.002499938 0.05899995 0 0.04849994 0.05899995 0 0.06349992 0.05899995 -0.002999961 0.06349992 0.05900001 0.01499998 0.01749992 0.05900001 0.02176117 0.001164734 0.05899995 0.02437257 0.007009863 0.05899995 0.009581387 0.09830993 0.05899995 0.005991578 0.08850622 0.05899995 0.01198327 0.09651243 0.05899995 0 0.08049994 0.05899995 0.003589749 0.09030371 0.05899995 0.01499998 0.02749997 0.05899995 0.02616298 0.01349997 0.05899995 0.01499998 0.03749996 0.05899995 0.02156466 0.1143226 0.05899995 0.01557296 0.1063163 0.05899995 0.01797485 0.1045188 0.05899995 0.03374266 0.08728843 0.05899995 0.01499998 0.06749993 0.05899995 0.031479 0.05027693 0.05899995 0.02396649 0.1125251 0.05899995 0.03295397 0.1245344 0.05900001 0.01832854 -0.004035174 0.05900001 0.01299995 -5.00023e-4 0.05900001 0.008999943 -0.01249998 0.05900001 0.01407486 -0.008590102 0.05900001 0.002999961 -5.00023e-4 0.05900001 0.005131661 -0.01132619 0.05900001 0.006380617 -0.01184141 0.05899995 0.01199996 0.06749993 0.05900001 0.002999961 0.002499938 0.05900001 0.01199996 0.01749992 0.05900001 0 0.02849996 0.05899995 0.01199996 0.02749997 0.05900001 0 -0.002499997 0.05900001 0 0.01349997 0.05900001 2.89589e-4 -0.0051862 0.05900001 6.63035e-4 -0.006486475 0.05900001 7.69971e-5 -0.0038504 0.05900001 0.001218676 -0.007719814 0.05900001 0.001964688 -0.008847773 0.05900001 0.003955721 -0.01066148 0.05899995 -0.002999961 0.04849994 0.05900001 -0.002999961 0.02849996 0.05900001 -0.002999961 0.01349997 0.05900001 0.007675468 -0.01222711 0.05899995 0.01499998 0.04749995 0.05900001 0.01299995 0.002499938 0.05899995 0.01199996 0.03749996 0.05899995 0.01199996 0.04749995 0.05899995 0.01499998 0.05749994 0.05899995 0.01199996 0.05749994 0.05900001 0.002887427 -0.009835004 0.07899999 0 0.08049994 -0.01899999 -0.002001523 0.08199787 0.07899999 -0.002001523 0.08199787 -0.01899999 0 0.08049994 0.07902771 0.009837031 0.09364467 0.07899999 0 0.08049994 0.07902771 0.007835447 0.09514254 0.0766943 0.01742208 0.1079526 0.07899999 -0.002001523 0.08199787 0.0766943 0.01942366 0.1064547 0.07199996 0.02675825 0.120428 0.07199996 0.02875977 0.1189301 0.06685727 0.03272497 0.1242285 0.0651822 0.03141599 0.1266519 0.0651822 0.03341758 0.125154 0.06685757 0.03072333 0.1257262 0.06829196 0.03190541 0.1231333 0.06829226 0.02990359 0.1246309 0.06959241 0.03094989 0.1218565 0.06959271 0.02894806 0.1233541 0.07082396 0.02987742 0.1204234 0.07082426 0.0278756 0.121921 0.07199996 0.02875977 0.1189301 0.07199996 0.02675825 0.120428 0.06336659 0.03196197 0.1273814 0.06336629 0.03396368 0.1258836 0.06142008 0.03239995 0.1279667 0.05937957 0.03275614 0.1284427 0.0614196 0.03440165 0.1264689 0.0572077 0.03306698 0.128858 0.0593791 0.03475779 0.1269448 0.05720716 0.03506863 0.1273602 0.055 0.03334903 0.1292349 0.055 0.03535062 0.1277369 0.004999995 0.03535062 0.1277369 0.055 0.03535062 0.1277369 0.055 0.03334903 0.1292349 0.004999995 0.03334903 0.1292349 -0.003966748 0.03188592 0.1272798 -0.003966748 0.0338875 0.1257819 -0.001257956 0.0346021 0.1267368 -0.001257956 0.03260058 0.1282347 -0.006395339 0.0309444 0.1260217 0.001730859 0.03508985 0.1273885 0.001730859 0.03308826 0.1288864 0.004999995 0.03535062 0.1277369 0.004999995 0.03334903 0.1292349 -0.006395339 0.03294599 0.1245238 -0.008543789 0.02977591 0.1244603 -0.008543789 0.0317775 0.1229624 -0.01041191 0.02838051 0.1225957 -0.01041191 0.03038209 0.1210978 -0.01199996 0.02675825 0.120428 -0.01199996 0.02875977 0.1189301 -0.0166943 0.01942366 0.1064547 -0.01199996 0.02875977 0.1189301 -0.0166943 0.01742208 0.1079526 -0.01902765 0.007835447 0.09514254 -0.01199996 0.02675825 0.120428 -0.01902765 0.009837031 0.09364467 -0.01899999 -0.002001523 0.08199787 -0.01899999 0 0.08049994 0.0625 0.009981691 0.09801042 0.0625 0.01198321 0.09651249 0.05949997 0.01198321 0.09651249 0.05949997 0.009981691 0.09801042 0.0625 0.003990054 0.09000414 0.0625 0.01198321 0.09651249 0.0625 0.009981691 0.09801042 0.0625 0.005991578 0.08850622 0.05949997 0.003990054 0.09000414 0.0625 0.005991578 0.08850622 0.0625 0.003990054 0.09000414 0.05949997 0.005991578 0.08850622 0.05949997 0.009981691 0.09801042 0.05949997 0.01198321 0.09651249 0.05949997 0.005991578 0.08850622 0.05949997 0.003990054 0.09000414 5.00005e-4 0.009981691 0.09801042 5.00005e-4 0.01198321 0.09651249 -0.002499938 0.01198321 0.09651249 -0.002499938 0.009981691 0.09801042 5.00005e-4 0.003990054 0.09000414 5.00005e-4 0.01198321 0.09651249 5.00005e-4 0.009981691 0.09801042 5.00005e-4 0.005991578 0.08850622 -0.002499938 0.003990054 0.09000414 5.00005e-4 0.005991578 0.08850622 5.00005e-4 0.003990054 0.09000414 -0.002499938 0.005991578 0.08850622 -0.002499938 0.009981691 0.09801042 -0.002499938 0.01198321 0.09651249 -0.002499938 0.005991578 0.08850622 -0.002499938 0.003990054 0.09000414 0.0625 0.0219649 0.1140229 0.0625 0.02396649 0.1125251 0.05949997 0.02396649 0.1125251 0.05949997 0.0219649 0.1140229 0.0625 0.01597332 0.1060166 0.0625 0.02396649 0.1125251 0.0625 0.0219649 0.1140229 0.0625 0.01797485 0.1045188 0.05949997 0.01597332 0.1060166 0.0625 0.01797485 0.1045188 0.0625 0.01597332 0.1060166 0.05949997 0.01797485 0.1045188 0.05949997 0.0219649 0.1140229 0.05949997 0.02396649 0.1125251 0.05949997 0.01797485 0.1045188 0.05949997 0.01597332 0.1060166 5.00005e-4 0.0219649 0.1140229 5.00005e-4 0.02396649 0.1125251 -0.002499938 0.02396649 0.1125251 -0.002499938 0.0219649 0.1140229 5.00005e-4 0.01597332 0.1060166 5.00005e-4 0.02396649 0.1125251 5.00005e-4 0.0219649 0.1140229 5.00005e-4 0.01797485 0.1045188 -0.002499938 0.01597332 0.1060166 5.00005e-4 0.01797485 0.1045188 5.00005e-4 0.01597332 0.1060166 -0.002499938 0.01797485 0.1045188 -0.002499938 0.0219649 0.1140229 -0.002499938 0.02396649 0.1125251 -0.002499938 0.01797485 0.1045188 -0.002499938 0.01597332 0.1060166 -0.003966748 0.03188592 0.1272798 -0.001257956 0.03260058 0.1282347 0.01645439 0.02419054 0.1169969 0.07082426 0.0278756 0.121921 0.05949997 0.0219649 0.1140229 0.06959271 0.02894806 0.1233541 -0.006395339 0.0309444 0.1260217 -0.01041191 0.02838051 0.1225957 5.00005e-4 0.0219649 0.1140229 -0.01199996 0.02675825 0.120428 -0.008543789 0.02977591 0.1244603 0.01108425 0.01148217 0.1000154 5.00005e-4 0.009981691 0.09801042 0.01027286 0.01340121 0.1025797 0.01108366 0.01926511 0.1104153 5.00005e-4 0.01597332 0.1060166 0.0625 0.009981691 0.09801042 0.0625 0.01597332 0.1060166 0.0766943 0.01742208 0.1079526 0.0102728 0.0173465 0.1078516 0.00999999 0.01537412 0.105216 0.05949997 0.01597332 0.1060166 0.05949997 0.009981691 0.09801042 0.03165817 0.003432393 0.08925902 0.07899999 -0.002001523 0.08199787 0.02835488 0.003431737 0.08925807 -0.002499938 0.0219649 0.1140229 0.02834838 0.02731645 0.1211739 0.02509027 0.02699071 0.1207386 0.004999995 0.03334903 0.1292349 0.06336659 0.03196197 0.1273814 0.0651822 0.03141599 0.1266519 0.0435456 0.02419054 0.1169969 0.05937957 0.03275614 0.1284427 0.04093897 0.02540612 0.1186212 0.0572077 0.03306698 0.128858 0.03165155 0.02731645 0.1211739 0.055 0.03334903 0.1292349 0.03490966 0.02699071 0.1207386 0.06142008 0.03239995 0.1279667 0.0380339 0.02634811 0.1198799 5.00005e-4 0.003990054 0.09000414 0.0219714 0.004398941 0.09055054 0.02509629 0.00375688 0.08969253 0.0625 0.0219649 0.1140229 0.01421946 0.008012235 0.09537875 0.05949997 0.003990054 0.09000414 0.04354959 0.006560444 0.0934388 0.0457856 0.008016526 0.09538453 0.07902771 0.007835447 0.09514254 0.0625 0.003990054 0.09000414 0.0380398 0.004402101 0.09055471 0.04094398 0.005344569 0.0918141 0.03491616 0.003758847 0.08969521 -0.01899999 -0.002001523 0.08199787 0.01906538 0.005340635 0.09180885 0.01645767 0.006556093 0.09343296 0.01241189 0.009669303 0.097593 -0.0166943 0.01742208 0.1079526 -0.002499938 0.009981691 0.09801042 -0.01902765 0.007835447 0.09514254 0.01241046 0.02107751 0.1128371 0.06829226 0.02990359 0.1246309 0.06685757 0.03072333 0.1257262 0.01421719 0.02273446 0.1150512 0.01906096 0.02540612 0.1186212 0.001730859 0.03308826 0.1288864 0.02196609 0.02634811 0.1198799 0.04758948 0.02107751 0.1128371 0.0457828 0.02273446 0.1150512 0.07199996 0.02675825 0.120428 0.04891628 0.01926511 0.1104153 -0.002499938 0.003990054 0.09000414 0.0497272 0.0173465 0.1078516 0.04891699 0.01148504 0.1000192 0.04972708 0.01340121 0.1025797 0.05000001 0.01537412 0.105216 0.04759109 0.009673178 0.09759813 -0.002499938 0.01597332 0.1060166 0.04093456 0.007342159 0.09031093 0.03802859 0.006400525 0.08905267 0.05949997 0.005991578 0.08850622 0.0625 0.005991578 0.08850622 0.07899999 0 0.08049994 0.07902771 0.009837031 0.09364467 5.00005e-4 0.005991578 0.08850622 0.01421439 0.01001811 0.09388661 5.00005e-4 0.01198321 0.09651249 0.01240885 0.0116747 0.09610027 0.011083 0.01348662 0.09852135 0.05720716 0.03506863 0.1273602 0.055 0.03535062 0.1277369 0.04093897 0.02740764 0.1171233 0.0651822 0.03341758 0.125154 0.06336629 0.03396368 0.1258836 0.0435456 0.02619206 0.115499 0.0614196 0.03440165 0.1264689 0.0593791 0.03475779 0.1269448 0.03165155 0.02931803 0.119676 0.03490966 0.02899229 0.1192407 0.0380339 0.02834969 0.118382 0.02834838 0.02931803 0.119676 0.004999995 0.03535062 0.1277369 0.02509027 0.02899229 0.1192407 0.04972708 0.01540279 0.1010819 0.05949997 0.01198321 0.09651249 0.05949997 0.01797485 0.1045188 -0.001257956 0.0346021 0.1267368 -0.003966748 0.0338875 0.1257819 0.01645439 0.02619206 0.115499 5.00005e-4 0.01797485 0.1045188 0.01027286 0.01540279 0.1010819 -0.008543789 0.0317775 0.1229624 -0.006395339 0.03294599 0.1245238 5.00005e-4 0.02396649 0.1125251 -0.01041191 0.03038209 0.1210978 -0.01199996 0.02875977 0.1189301 0.01241046 0.02307909 0.1113392 0.01108366 0.02126669 0.1089174 0.0766943 0.01942366 0.1064547 0.0625 0.01198321 0.09651249 0.04891568 0.0134837 0.09851747 0.05949997 0.02396649 0.1125251 0.07082396 0.02987742 0.1204234 0.06959241 0.03094989 0.1218565 -0.002499938 0.01198321 0.09651249 -0.01902765 0.009837031 0.09364467 -0.002499938 0.005991578 0.08850622 0.0625 0.02396649 0.1125251 0.07199996 0.02875977 0.1189301 -0.01899999 0 0.08049994 0.0349037 0.005758404 0.08819466 -0.0166943 0.01942366 0.1064547 0.0475881 0.01167088 0.09609514 -0.002499938 0.02396649 0.1125251 0.02508378 0.005760431 0.08819729 0.01905596 0.007346153 0.09031617 0.0164504 0.008562028 0.09194093 0.04578047 0.01001381 0.09388083 0.04354226 0.008557617 0.09193509 0.03164505 0.00543332 0.08776021 0.02834177 0.005433976 0.0877611 0.02196019 0.006403625 0.08905678 0.00999999 0.0173757 0.1037181 0.0102728 0.01934808 0.1063537 -0.002499938 0.01797485 0.1045188 0.06829196 0.03190541 0.1231333 0.06685727 0.03272497 0.1242285 0.01421719 0.02473598 0.1135533 0.01906096 0.02740764 0.1171233 0.001730859 0.03508985 0.1273885 0.02196609 0.02834969 0.118382 0.04758948 0.02307909 0.1113392 0.0457828 0.02473598 0.1135533 0.04891628 0.02126669 0.1089174 0.0497272 0.01934808 0.1063537 0.05000001 0.0173757 0.1037181 0.0625 0.01797485 0.1045188 0.0102728 0.0173465 0.1078516 0.00999999 0.0173757 0.1037181 0.00999999 0.01537412 0.105216 0.01421719 0.02273446 0.1150512 0.01241046 0.02307909 0.1113392 0.01241046 0.02107751 0.1128371 0.01108366 0.01926511 0.1104153 0.01108366 0.02126669 0.1089174 0.0102728 0.01934808 0.1063537 0.01906096 0.02740764 0.1171233 0.01906096 0.02540612 0.1186212 0.02196609 0.02634811 0.1198799 0.01421719 0.02473598 0.1135533 0.01645439 0.02419054 0.1169969 0.01645439 0.02619206 0.115499 0.02834838 0.02731645 0.1211739 0.03165155 0.02731645 0.1211739 0.02834838 0.02931803 0.119676 0.02509027 0.02699071 0.1207386 0.02509027 0.02899229 0.1192407 0.02196609 0.02834969 0.118382 0.04093897 0.02540612 0.1186212 0.0380339 0.02834969 0.118382 0.0380339 0.02634811 0.1198799 0.03490966 0.02899229 0.1192407 0.03165155 0.02931803 0.119676 0.03490966 0.02699071 0.1207386 0.0457828 0.02473598 0.1135533 0.0457828 0.02273446 0.1150512 0.04758948 0.02107751 0.1128371 0.04093897 0.02740764 0.1171233 0.0435456 0.02419054 0.1169969 0.0435456 0.02619206 0.115499 0.0497272 0.0173465 0.1078516 0.05000001 0.01537412 0.105216 0.0497272 0.01934808 0.1063537 0.04891628 0.01926511 0.1104153 0.04891628 0.02126669 0.1089174 0.04758948 0.02307909 0.1113392 0.04759109 0.009673178 0.09759813 0.04891568 0.0134837 0.09851747 0.04891699 0.01148504 0.1000192 0.04972708 0.01540279 0.1010819 0.05000001 0.0173757 0.1037181 0.04972708 0.01340121 0.1025797 0.04354226 0.008557617 0.09193509 0.04354959 0.006560444 0.0934388 0.04094398 0.005344569 0.0918141 0.0475881 0.01167088 0.09609514 0.0457856 0.008016526 0.09538453 0.04578047 0.01001381 0.09388083 0.03491616 0.003758847 0.08969521 0.03165817 0.003432393 0.08925902 0.0349037 0.005758404 0.08819466 0.0380398 0.004402101 0.09055471 0.03802859 0.006400525 0.08905267 0.04093456 0.007342159 0.09031093 0.02835488 0.003431737 0.08925807 0.02509629 0.00375688 0.08969253 0.02834177 0.005433976 0.0877611 0.03164505 0.00543332 0.08776021 0.02508378 0.005760431 0.08819729 0.0219714 0.004398941 0.09055054 0.01906538 0.005340635 0.09180885 0.02196019 0.006403625 0.08905678 0.01645767 0.006556093 0.09343296 0.01905596 0.007346153 0.09031617 0.0164504 0.008562028 0.09194093 0.01421946 0.008012235 0.09537875 0.01241189 0.009669303 0.097593 0.01421439 0.01001811 0.09388661 0.01108425 0.01148217 0.1000154 0.01240885 0.0116747 0.09610027 0.011083 0.01348662 0.09852135 0.01027286 0.01340121 0.1025797 0.01027286 0.01540279 0.1010819 + + + + + + + + + + 0 0 -1 -1 0 0 0 -1 0 0 1 0 1 0 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 -1 3.12944e-7 0 -1 -2.15984e-7 0 -1 -4.40965e-7 0 -1 -1.79376e-7 0 -1 -8.81934e-7 0 -1 8.81934e-7 0 -1 0 0 -1 4.40965e-7 0 1 2.15984e-7 0 1 -1.4197e-7 0 1 -1.35682e-7 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.6292e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.6292e-7 0 1 1.62919e-7 0 1 1.6292e-7 0 1 1.6292e-7 0 1 1.62921e-7 0 1 1.62909e-7 0 1 1.62917e-7 0 1 1.6292e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62922e-7 0 1 1.6292e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.62921e-7 0 1 1.6292e-7 0 1 1.6292e-7 0 1.62921e-7 -1 0 1.6292e-7 -1 0 2.03359e-6 -0.800627 0.5991632 -1.3595e-6 -0.800627 0.5991631 6.51151e-7 -0.5991636 -0.8006267 -4.27945e-7 -0.5991634 -0.8006268 1.29254e-6 -0.8006257 0.599165 0 -0.8006257 0.5991649 0 0.59916 0.8006293 0 0.5991602 0.8006293 0 -0.8006296 0.5991597 0 -0.8006293 0.59916 0 -0.5991612 -0.8006286 0 -0.5991621 -0.8006279 0 -0.8006247 0.5991662 0 0.599177 0.8006168 0 0.5991783 0.8006156 0 -0.800625 0.5991658 0 -0.8006251 0.5991657 0 0.9998014 -0.01992887 0 0.9997764 0.02114975 0 0.9947724 -0.1021171 0 0.9897162 -0.1430448 0 0.9411889 -0.3378807 0 0.8767161 -0.4810082 0 0.7854714 -0.6188979 0 0.9639977 -0.2659104 0 0.6728187 -0.7398076 0 0.6103212 -0.7921541 -0.00137335 -0.5540164 -0.8325048 -5.18831e-4 -0.674877 -0.7379302 -0.001403868 -0.6735042 -0.7391822 -4.27265e-4 -0.7852826 -0.6191375 -0.001678526 -0.5533747 -0.8329308 -0.00149542 -0.4372732 -0.8993276 -0.001373291 -0.4373959 -0.899268 -6.7142e-4 -0.3335431 -0.9427347 -0.00112915 -0.3327784 -0.9430044 -3.35713e-4 -0.2432392 -0.9699662 0 -0.2438495 -0.9698132 0 -0.2017588 -0.9794353 0 -0.2017941 -0.979428 6.10388e-4 -0.7866677 -0.6173766 0.001403868 -0.8766298 -0.4811636 7.01946e-4 -0.8759062 -0.4824809 0.001403868 -0.9390096 -0.3438884 0.001312315 -0.9388966 -0.344197 0.001190185 -0.9761526 -0.2170822 7.62964e-4 -0.9759839 -0.2178415 0 -0.9941335 -0.1081601 3.66224e-4 -0.9942065 -0.1074867 0 -0.9983789 -0.0569185 1.62921e-7 -1 0 1.62921e-7 -1 0 4.73972e-7 0 -1 1.86265e-7 -1 0 1.86265e-7 -1 0 3.88051e-6 0 1 -1.94026e-6 0 1 1.60566e-7 -1 0 1.62921e-7 -1 0 2.49325e-6 0 -1 1.86265e-7 -1 0 1.86264e-7 -1 0 0 1 -1.56816e-7 0 -1 1.2326e-7 0 1 -1.56816e-7 0 -1 1.2326e-7 0 1 -1.56816e-7 0 -1 -1.67778e-7 -1.86265e-7 1 -1.36217e-7 -1.86264e-7 1 1.21266e-7 0 0 1 0 -1 1.45632e-7 0 -1 1.62982e-7 1.45519e-7 0 -1 -1 0 0 -1 -1.54944e-7 0 -1 -1.21265e-7 0 -1 -2.50014e-7 0 -1 -2.42532e-7 0 -1 -1.95538e-7 0 -1 -2.12213e-7 0 -1 -1.68191e-7 0 -1 -1.74678e-7 0 -1 -1.21268e-7 0 -1 -1.49228e-7 0 -1 -1.37394e-7 0 -1 -1.5526e-7 0 -1 -1.59507e-7 0 -1 -1.20571e-7 0 -1 -1.85097e-7 0 -1 -2.3793e-7 -1.33581e-7 -1 -1.58111e-7 0 -1 0 0 -1 -1.7053e-7 0 -1 -1.67191e-7 0 -1 -4.0422e-7 0 -1 0 0 -1 0 0 -1 -4.93675e-6 -2.68675e-7 -1 -5.85942e-7 0 -1 0 -1.4001e-7 -1 -4.91948e-7 0 -1 0 0 -1 -3.23376e-7 0 -1 -1.61688e-7 0 -1 0 0 -1 -1.86132e-7 0 -1 0 0 -1 -2.27576e-7 0 -1 -1.95347e-7 0 -1 -1.44003e-7 0 -1 -2.42532e-7 0 -1 -1.54535e-7 0 -1 -1.76612e-7 0 -1 -1.81899e-7 0 -1 -2.0211e-7 0 -1 -1.51582e-7 0 -1 0 0 -1 0 0 -1 -1.47001e-7 0 -1 -1.47001e-7 0 -1 -1.81899e-7 0 -1 -1.25471e-7 0 -1 -1.81899e-7 0 -1 -2.42532e-7 0 -1 0 -1.2641e-7 -1 -2.3471e-7 0 -1 0 -1.634e-7 -1 -1.61688e-7 0 -1 -4.0422e-7 0 -1 -1.94026e-7 0 -1 -7.22855e-7 -1.20953e-7 -1 4.16949e-7 -1.23121e-7 0.9873372 0 -0.1586356 0.9938953 0 -0.1103277 0.9672341 0 -0.2538864 0.953738 0 -0.3006391 -0.9672341 0 -0.2538864 -0.953738 0 -0.3006391 -0.9873372 0 -0.1586356 -0.9938953 0 -0.1103277 0 -1 0 0 -1 0 0 -1 0 0 -1 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.24833e-7 0 -1 0 0 -1 0 0 -1 0 0.4526621 0 -0.8916822 0.5861556 0 -0.8101986 0.7053192 0 -0.70889 0.807229 0 -0.5902385 0.8509156 0 -0.5253025 0.3079942 0 -0.9513883 0.1558905 0 -0.9877743 0.0782507 0 -0.9969338 0 1 0 0 1 0 0 1 0 0 1 0 -0.3079942 0 -0.9513883 -0.1558905 0 -0.9877743 -0.0782507 0 -0.9969338 -0.5861556 0 -0.8101986 -0.7053192 0 -0.70889 -0.4526621 0 -0.8916822 -0.807229 0 -0.5902385 -0.8509156 0 -0.5253025 1 -9.70118e-7 2.98258e-7 1 0 2.48353e-7 1 3.88051e-6 2.98257e-7 1 9.70116e-7 2.98256e-7 1 3.58808e-7 0 1 0 0 1 0 2.98252e-7 1 4.85064e-7 0 1 6.764e-7 0 1 0 2.76086e-7 1 0 2.48353e-7 1 8.34518e-7 1.60228e-7 1 -8.67786e-6 0 1 4.67512e-6 0 1 4.38429e-6 0 1 7.90433e-6 0 1 0 1.28403e-7 1 8.43257e-7 0 1 2.58701e-6 2.48353e-7 1 0 3.72529e-7 1 0 0 1 5.88004e-7 0 1 0 1.28662e-7 1 6.85264e-6 0 1 1.04287e-6 0 1 9.70128e-7 3.72529e-7 1 0 1.74153e-7 1 -1.76612e-7 0 1 0 0 1 -3.23376e-6 0 1 0 2.48352e-7 1 1.25179e-6 2.13448e-7 1 -2.58701e-6 2.48353e-7 1 0 2.48353e-7 1.62921e-7 -1 0 1.62921e-7 -1 0 2.03359e-6 -0.8006272 0.5991629 -1.3595e-6 -0.8006263 0.599164 6.5115e-7 -0.5991641 -0.8006263 -4.27945e-7 -0.5991628 -0.8006273 1.29253e-6 -0.8006266 0.5991637 0 -0.8006268 0.5991634 0 0.5991589 0.8006302 0 0.5991603 0.8006291 0 -0.8006296 0.5991598 0 -0.8006294 0.59916 0 -0.5991603 -0.8006291 0 -0.599162 -0.800628 0 -0.8006247 0.5991663 0 0.5991778 0.8006161 0 0.5991771 0.8006167 0 -0.8006254 0.5991652 1.62921e-7 -1 0 1.6292e-7 -1 0 4.73972e-7 0 -1 1.86264e-7 -1 0 1.86265e-7 -1 0 3.88051e-6 0 1 -1.94025e-6 0 1 1.60566e-7 -1 0 1.6292e-7 -1 0 2.49325e-6 0 -1 1.86264e-7 -1 0 0 1 -1.45519e-7 0 -1 2.91037e-7 0 1 0 0 -1 -1.86264e-7 0 1 1.45519e-7 -1.86265e-7 1 0 -1.86264e-7 1 0 0 0 1 1.45519e-7 0 -1 -1 -7.08315e-7 -3.065e-7 -1 0 -2.98257e-7 -1 5.7146e-7 -2.19134e-7 -1 0 -2.98257e-7 -1 -1.45517e-6 -2.98256e-7 -1 -3.58808e-7 0 -1 3.49355e-7 -1.59412e-7 -1 0 -2.98252e-7 -1 6.764e-7 0 -1 -2.48416e-6 -3.72529e-7 -1 -2.57219e-6 0 -1 5.85673e-6 0 -1 -8.43257e-7 0 -1 0 -1.60228e-7 -1 -4.85064e-7 -3.72529e-7 -1 0 -1.28403e-7 -1 1.21266e-6 -2.32831e-7 -1 -7.8988e-5 0 -1 -9.37507e-6 0 -1 7.87118e-6 0 -1 0 -1.48525e-7 -1 -1.96885e-7 0 -1 -3.03165e-7 0 -1 0 -3.72529e-7 -1 7.06447e-7 0 -1 0 -1.86264e-7 -1 -6.46751e-7 0 -1 9.70127e-7 0 -1 0 0 -1 0 0 -1 0 -3.72529e-7 -1 0 -1.28662e-7 -1 0 -3.72529e-7 -1 -2.71864e-7 0 -1 1.92763e-6 -2.9049e-7 -1 0 0 -1 -7.76102e-7 0 -1 -1.33424e-5 0 0 -0.5991635 -0.8006267 0 -0.5991635 -0.8006268 0.9974429 0.04281771 0.05722254 0.9999987 -0.001007139 -0.001342833 0.9761807 0.1299804 0.1737141 0.9574964 0.1728278 0.2309356 0.6309616 0.4648436 0.6211344 0.5094933 0.5155667 0.6889178 0.5094826 0.5155558 0.6889337 0.630989 0.4648107 0.6211313 0.7340046 0.4069054 0.5437511 0.7339814 0.40694 0.5437566 0.8000907 0.3594243 0.4802803 0.8350393 0.3296697 0.4404854 0.8459309 0.3195359 0.4269635 0.4006255 0.5489489 0.7335901 0.3158705 0.5684754 0.7596458 0.2560837 0.5791868 0.7739275 0.3158431 0.5684809 0.7596531 0.2560552 0.5791913 0.7739337 0.2204428 0.5844193 0.7809348 0.2204389 0.5844393 0.7809209 0.2085064 0.5859969 0.7830281 0 0.599163 0.8006272 0 0.5991638 0.8006265 -0.4746044 0.5273721 0.7047193 -0.3337907 0.5647921 0.7547143 -0.6097047 0.4749031 0.634608 -0.1977978 0.5873202 0.7848128 -0.1319345 0.5939344 0.7936215 -0.7283518 0.4105505 0.548591 -0.8234945 0.3399208 0.4542145 -0.8625881 0.3031144 0.4050477 -0.9761807 0.1299804 0.1737141 -0.9574964 0.1728278 0.2309356 -0.9974429 0.04281771 0.05722254 -0.9999987 -0.001007139 -0.001342833 0 -0.5991623 -0.8006277 0 -0.5991616 -0.8006281 -1 1.16415e-6 0 0 0.5991644 0.800626 0 0.5991634 0.8006269 0 -0.5991618 -0.8006281 0 -0.5991613 -0.8006285 -1 0 0 0 0.5991635 0.8006267 0 0.5991636 0.8006266 1 -1.45519e-7 0 1 1.45519e-7 0 0 -0.5991628 -0.8006273 0 -0.5991618 -0.800628 -1 1.16415e-6 0 0 0.5991643 0.8006262 0 -0.5991626 -0.8006274 0 -0.5991608 -0.8006288 -1 0 0 0 0.5991631 0.800627 0 0.5991641 0.8006264 1 -1.45519e-7 0 1 1.45519e-7 0 -3.93647e-6 -0.8006275 0.5991625 0 -0.8006261 0.5991643 -1.83964e-6 -0.8006279 0.5991619 -2.50091e-6 -0.8006266 0.5991636 1.69261e-6 -0.8006252 0.5991656 4.81886e-7 -0.8006274 0.5991628 1.61992e-6 -0.8006274 0.5991627 0 -0.8006269 0.5991633 2.05039e-7 -0.800627 0.5991632 0 -0.8006272 0.5991629 0 -0.8006264 0.5991639 0 -0.8006277 0.5991622 0 -0.8006278 0.599162 0 -0.8006255 0.5991652 0 -0.8006271 0.5991631 0 -0.8006267 0.5991635 1.67775e-6 -0.800627 0.5991633 -3.2441e-6 -0.8006268 0.5991635 -2.8286e-6 -0.8006277 0.5991624 0 -0.8006284 0.5991615 0 -0.8006277 0.5991624 0 -0.8006269 0.5991632 8.20156e-7 -0.8006267 0.5991636 0 -0.8006271 0.5991632 -6.01877e-7 -0.8006273 0.5991627 -4.54596e-7 -0.8006271 0.599163 0 -0.8006269 0.5991632 0 -0.8006275 0.5991625 2.16934e-6 -0.8006259 0.5991647 0 -0.8006278 0.5991621 -1.71211e-6 -0.8006265 0.5991637 0 -0.800627 0.5991632 0 -0.8006271 0.5991631 2.03649e-7 -0.8006279 0.599162 9.18276e-7 -0.800627 0.5991631 -5.95602e-7 -0.8006272 0.5991629 -9.09426e-7 -0.8006264 0.5991639 4.54597e-7 -0.800627 0.5991632 0 -0.8006274 0.5991627 -2.44899e-6 -0.8006249 0.5991659 0 -0.8006259 0.5991648 1.60524e-6 -0.8006266 0.5991637 1.28164e-6 -0.8006275 0.5991624 0 -0.8006272 0.5991628 0 -0.8006277 0.5991623 -7.98079e-7 -0.8006276 0.5991623 0 -0.8006274 0.5991627 0 -0.8006272 0.5991629 7.72355e-6 -0.8006297 0.5991596 -5.21026e-7 -0.800627 0.5991631 2.24456e-6 -0.8006286 0.5991612 -4.0861e-7 -0.8006283 0.5991615 0 -0.8006268 0.5991634 0 -0.8006274 0.5991626 -7.66028e-7 -0.8006261 0.5991644 4.69285e-7 -0.8006271 0.599163 0 -0.8006271 0.5991629 0 -0.800627 0.5991631 0 -0.800627 0.5991631 0 -0.8006283 0.5991613 -9.88752e-7 -0.8006271 0.599163 0 -0.8006262 0.5991643 0 -0.8006269 0.5991633 -8.11186e-7 -0.8006272 0.5991628 5.95603e-7 -0.8006273 0.5991628 4.61295e-7 -0.8006271 0.599163 -4.69285e-7 -0.8006267 0.5991635 6.17832e-7 -0.8006273 0.5991627 -6.8218e-7 -0.8006262 0.5991642 0 -0.800628 0.599162 4.24427e-7 -0.8006271 0.5991629 2.88883e-7 -0.800627 0.5991632 -7.17942e-7 -0.8006271 0.5991632 0 -0.8006271 0.599163 -8.20154e-7 -0.800627 0.5991631 4.0861e-7 -0.8006286 0.5991611 0 -0.8006274 0.5991628 0 0.8006264 -0.5991639 0 0.8006267 -0.5991635 4.24427e-7 0.8006271 -0.5991629 0 0.800627 -0.5991631 3.24483e-6 0.8006254 -0.5991654 0 0.8006286 -0.599161 0 0.8006271 -0.599163 1.25832e-6 0.8006263 -0.599164 -3.21499e-6 0.8006285 -0.5991612 -1.50866e-6 0.8006265 -0.5991638 3.03845e-6 0.8006274 -0.5991625 0 0.8006269 -0.5991634 -2.55869e-6 0.8006269 -0.5991633 0 0.8006269 -0.5991632 -1.19121e-6 0.800627 -0.5991631 -3.93648e-6 0.8006262 -0.5991642 5.95603e-7 0.800627 -0.5991631 0 0.8006262 -0.5991642 4.59908e-7 0.8006274 -0.5991627 2.40943e-7 0.8006271 -0.5991631 1.87568e-6 0.8006272 -0.599163 0 0.8006278 -0.5991622 0 0.8006277 -0.5991622 0 0.8006266 -0.5991638 0 0.8006272 -0.5991628 1.25459e-6 0.8006272 -0.5991629 0 0.8006272 -0.5991629 0 0.800628 -0.599162 0 0.800627 -0.5991632 -2.89381e-7 0.8006276 -0.5991623 0 0.8006271 -0.5991632 -8.2334e-7 0.8006265 -0.5991638 0 0.8006269 -0.5991632 0 0.8006268 -0.5991634 0 0.8006268 -0.5991635 0 0.8006273 -0.5991628 -1.00251e-6 0.800628 -0.5991618 -4.2427e-7 0.8006272 -0.5991628 0 0.8006274 -0.5991626 6.01723e-7 0.800627 -0.5991631 -1.94671e-6 0.8006287 -0.5991609 9.87754e-7 0.8006271 -0.5991632 -2.29569e-7 0.8006267 -0.5991636 8.54584e-7 0.800628 -0.5991618 0 0.8006271 -0.5991631 4.07e-7 0.8006274 -0.5991628 2.88885e-7 0.800625 -0.5991658 0 0.8006267 -0.5991635 0 0.8006266 -0.5991637 0 0.8006266 -0.5991637 0 0.8006261 -0.5991643 4.10077e-7 0.8006271 -0.599163 -2.44925e-6 0.8006266 -0.5991638 0 0.800628 -0.5991618 1.60525e-6 0.8006273 -0.5991628 -1.28164e-6 0.8006269 -0.5991632 -2.35388e-6 0.8006272 -0.5991629 -2.77555e-7 0.8006272 -0.5991629 -2.66027e-7 0.8006263 -0.599164 1.44034e-6 0.8006263 -0.599164 0 0.8006269 -0.5991633 -1.92045e-6 0.8006261 -0.5991644 -2.57497e-6 0.8006265 -0.5991637 2.24457e-6 0.8006262 -0.5991642 0 0.8006283 -0.5991616 -9.2259e-7 0.8006275 -0.5991626 0 0.8006262 -0.5991643 4.69285e-7 0.8006272 -0.5991629 0 0.8006283 -0.5991614 0 0.8006276 -0.5991623 -4.29127e-6 0.8006281 -0.5991617 0 0.8006263 -0.599164 4.10078e-7 0.8006269 -0.5991632 -8.20154e-7 0.8006271 -0.599163 0 0.8006271 -0.5991629 -6.27293e-7 0.800627 -0.5991631 9.22589e-7 0.8006274 -0.5991625 0.9863626 -0.09860569 -0.1317795 0.789142 -0.3680038 -0.4917603 0.8794888 -0.2851464 -0.3810396 0.9458212 -0.1945295 -0.2599627 0.5469415 -0.5015894 -0.670271 0.4016923 -0.5487028 -0.7331907 0.6772775 -0.4408163 -0.5890471 0.08255493 -0.5971118 -0.7978987 -0.08255493 -0.5971118 -0.7978987 0.2454642 -0.5808374 -0.7761284 -0.5469629 -0.501581 -0.6702599 -0.4016923 -0.5487028 -0.7331907 -0.2454642 -0.5808374 -0.7761284 -0.789142 -0.3680038 -0.4917603 -0.8794811 -0.2851744 -0.3810362 -0.5469415 -0.5015894 -0.670271 -0.6772775 -0.4408163 -0.5890471 -0.9863626 -0.09860569 -0.1317795 -0.9458212 -0.1945295 -0.2599627 -0.8796033 0.285205 0.3807311 -0.9458746 0.1945585 0.259747 -0.9457806 0.1946495 0.260021 -0.9863549 0.09863853 0.1318131 -0.6770766 0.4409467 0.5891803 -0.5472988 0.5017033 0.669894 -0.6775569 0.440911 0.5886545 -0.8793888 0.2852963 0.381158 -0.7889927 0.3681579 0.4918844 -0.7893469 0.3680608 0.4913886 -0.2458948 0.5809674 0.7758948 -0.2450997 0.5807803 0.7762863 -0.08298176 0.5972615 0.7977423 -0.4020624 0.5488302 0.7328925 -0.5466892 0.5016735 0.6704137 -0.401359 0.5487367 0.7333478 0.08215737 0.5972585 0.7978299 0.08298224 0.5969291 0.797991 0.2451027 0.5809705 0.7761431 -0.08215731 0.5970141 0.7980127 0.2458932 0.5805669 0.776195 0.4013658 0.5488376 0.7332686 0.5466921 0.5017067 0.6703867 0.4020644 0.5483751 0.7332319 0.5472771 0.5012231 0.670271 0.6770736 0.4409142 0.5892081 0.6775566 0.4404225 0.5890204 0.7889986 0.3680996 0.4919186 0.8793914 0.2852056 0.3812201 0.7893407 0.3676306 0.4917204 0.8796031 0.2848387 0.3810057 0.9457824 0.1945583 0.2600825 0.9458689 0.1943436 0.2599285 0.9863549 0.09863853 0.1318131 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + -4.37114e-8 -4.37114e-8 -1 0.37753 -1 1.91069e-15 4.37114e-8 0.0301379 0 1 -4.37114e-8 -0.00391909 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_fuselage.dae b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_fuselage.dae new file mode 100644 index 00000000..c1ea0b51 --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_fuselage.dae @@ -0,0 +1,385 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-04T12:35:32 + 2023-07-04T12:35:32 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.498039 0.498039 0.498039 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.772549 0.752941 0.733333 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + + + + 0.0177657 0.0213958 0.01899999 0.01770406 0.02104496 0.018 0.01827752 0.02227324 0.01899999 0.01821988 0.02223521 0.018 0.01916545 0.02274715 0.01899999 0.01895475 0.0226686 0.018 0.01983451 0.02274715 0.018 0.02004522 0.0226686 0.01899999 0.02072244 0.02227324 0.018 0.02078002 0.02223521 0.01899999 0.0212959 0.02104508 0.01899999 0.02123427 0.0213958 0.018 0.02091544 0.0199455 0.01899999 0.02111166 0.02024698 0.018 0.01998507 0.01927024 0.01899999 0.0203092 0.01941579 0.018 0.01882541 0.01936876 0.01899999 0.01916563 0.01925277 0.018 0.01794195 0.02010542 0.01899999 0.01816302 0.01982653 0.018 0.02298718 0.02099996 0.01899999 0.02293634 0.02037072 0.01899999 0.02124989 0.02114462 0.01899999 0.02006989 0.02266085 0.01899999 0.02111977 0.0240882 0.01899999 0.02057832 0.02238571 0.01899999 0.02073568 0.02426087 0.01899999 0.019499 0.02448719 0.01899999 0.01949995 0.02275586 0.01899999 0.01991975 0.02446186 0.01899999 0.01907885 0.02446156 0.01899999 0.01893007 0.02266085 0.01899999 0.02148067 0.02387017 0.01899999 0.01826268 0.02426028 0.01899999 0.01866525 0.02438586 0.01899999 0.02210944 0.02331316 0.01899999 0.02088099 0.02207487 0.01899999 0.01787847 0.02408725 0.01899999 0.02110809 0.02170521 0.01899999 0.0223695 0.02298158 0.01899999 0.01751846 0.02386945 0.01899999 0.01842164 0.02238571 0.01899999 0.02276027 0.0222373 0.01899999 0.02288556 0.0218355 0.01899999 0.02276068 0.01976358 0.01899999 0.02120214 0.02056914 0.01899999 0.01641207 0.02262026 0.01899999 0.01803004 0.02196049 0.01899999 0.01623916 0.02223604 0.01899999 0.02237045 0.01901996 0.01899999 0.02103918 0.02016735 0.01899999 0.02258819 0.01938027 0.01899999 0.01774996 0.02099996 0.01899999 0.01603829 0.02142095 0.01899999 0.01779788 0.02143132 0.01899999 0.01611447 0.02016425 0.01899999 0.01779782 0.02056884 0.01899999 0.01623958 0.01976299 0.01899999 0.02148187 0.01813077 0.01899999 0.02033644 0.01945614 0.01899999 0.02181297 0.01839029 0.01899999 0.02079206 0.01981109 0.01899999 0.02211046 0.0186879 0.01899999 0.01788026 0.01791179 0.01899999 0.01751995 0.01812946 0.01899999 0.01866453 0.01945555 0.01899999 0.0211212 0.01791244 0.01899999 0.02073699 0.01773959 0.01899999 0.01908075 0.01753807 0.01899999 0.01950061 0.01924413 0.01899999 0.01949995 0.01751279 0.01899999 0.01992118 0.01753824 0.01899999 0.01907086 0.01930338 0.01899999 0.01826357 0.01773929 0.01899999 0.01866638 0.01761388 0.01899999 0.01993018 0.01930367 0.01899999 0.02033567 0.01761448 0.01899999 0.01831495 0.01971215 0.01899999 0.01718789 0.01838946 0.01899999 0.01689028 0.01868695 0.01899999 0.01663076 0.01901805 0.01899999 0.01641249 0.01937878 0.01899999 0.01802992 0.02003967 0.01899999 0.01603829 0.0205788 0.01899999 0.01601278 0.02099996 0.01899999 0.01611387 0.02183359 0.01899999 0.01662957 0.02298009 0.01899999 0.01688915 0.02331179 0.01899999 0.02296167 0.02142095 0.01899999 0.01718729 0.02360999 0.01899999 0.02033436 0.02438586 0.01899999 0.02181208 0.02361047 0.01899999 0.02258765 0.02262079 0.01899999 0.01949995 0.01924407 0.018 0.01950007 0.01999664 0.018 0.02096992 0.02196049 0.018 0.0204187 0.02140325 0.018 0.01893007 0.01933908 0.018 0.0192548 0.02003049 0.018 0.02006989 0.01933908 0.018 0.01974576 0.02003067 0.018 0.01902276 0.02011734 0.018 0.01997804 0.02011781 0.018 0.02023845 0.02032071 0.018 0.02057826 0.01961421 0.018 0.02096992 0.02003943 0.018 0.01842164 0.01961421 0.018 0.02041864 0.02059656 0.018 0.02120208 0.02056866 0.018 0.01882284 0.02026408 0.018 0.01803004 0.02003943 0.018 0.01865988 0.02045142 0.018 0.01779788 0.02143132 0.018 0.01851356 0.02116459 0.018 0.01774996 0.02099996 0.018 0.02049994 0.02108323 0.018 0.02120208 0.02143126 0.018 0.01803004 0.02196049 0.018 0.01876193 0.02167969 0.018 0.01902252 0.02188253 0.018 0.01893007 0.02266085 0.018 0.02023798 0.02167969 0.018 0.01997739 0.02188253 0.018 0.02057832 0.02238571 0.018 0.019665 0.0219897 0.018 0.01933491 0.0219897 0.018 0.01949995 0.02275586 0.018 0.02006989 0.02266085 0.018 0.01842164 0.02238571 0.018 0.01858121 0.02140325 0.018 0.01850003 0.02091675 0.018 0.01779788 0.02056866 0.018 0.02048635 0.02083539 0.018 0.02124994 0.02099996 0.018 0.01855415 0.02067518 0.018 0.01986223 0.0174815 0.018 0.01955425 0.01749694 0.01899999 0.02079319 0.017744 0.01899999 0.02162092 0.018193 0.018 0.02186334 0.01841384 0.01899999 0.0226826 0.01950055 0.018 0.02262681 0.0194199 0.01899999 0.02300745 0.02099865 0.018 0.02303034 0.02099704 0.01899999 0.01811236 0.01776701 0.01899999 0.0182082 0.01774334 0.018 0.01713657 0.01841378 0.018 0.01691389 0.01863652 0.01899999 0.01637303 0.01942008 0.018 0.01624405 0.0197066 0.01899999 0.01596963 0.02099704 0.018 0.01599246 0.02099865 0.01899999 0.01608604 0.0217871 0.01899999 0.0159924 0.02100127 0.018 0.01638972 0.02264314 0.018 0.01601278 0.02099996 0.01899999 0.01681107 0.02329796 0.01899999 0.01639896 0.0226382 0.01699995 0.01738184 0.02380901 0.01699995 0.01859116 0.02441823 0.01899999 0.01892703 0.0244711 0.01699995 0.02033847 0.02440577 0.01899999 0.02033746 0.02439808 0.01699995 0.02189147 0.023606 0.01899999 0.02161902 0.02380824 0.01699995 0.02260106 0.02263826 0.01699995 0.02259027 0.02263152 0.018 0.02287608 0.02198988 0.01899999 0.02304416 0.0210039 0.018 0.02298718 0.02099996 0.01899999 0.02051651 0.02114337 0.01699995 0.02051651 0.02085679 0.018 0.02024585 0.0202769 0.01699995 0.02014327 0.02021294 0.018 0.01947599 0.01998376 0.01699995 0.01935571 0.01997119 0.018 0.01893079 0.02016723 0.01699995 0.01866239 0.020424 0.018 0.01855963 0.0206139 0.01699995 0.01855969 0.02144163 0.01699995 0.01848345 0.02114343 0.018 0.01891726 0.02184516 0.018 0.01935547 0.02202874 0.01699995 0.01972699 0.02200114 0.018 0.02014297 0.02178728 0.01699995 0.02033758 0.02157592 0.018 0.01641595 0.02262777 0.018 0.004999995 0.000999987 0.018 0.004999995 0.000999987 0.01699995 0.01641595 0.02262777 0.01699995 0.01611524 0.02183938 0.018 0.01603847 0.02142286 0.018 0.004999995 0.000999987 0.018 0.019499 0.01751279 0.018 0.01907885 0.01753836 0.018 0.01601278 0.02099996 0.018 0.01603829 0.02057898 0.018 0.01628011 0.02234715 0.018 0.01611387 0.02016639 0.018 0.01623916 0.01976388 0.018 0.01641207 0.01937967 0.018 0.01662957 0.0190199 0.018 0.01688915 0.0186882 0.018 0.01718729 0.01838999 0.018 0.01751846 0.01813048 0.018 0.01787847 0.01791268 0.018 0.01826268 0.01773965 0.018 0.01866525 0.01761406 0.018 0 0 0.018 0 0.000999987 0.018 0.01991975 0.01753807 0.018 0.02033436 0.01761406 0.018 0.03399997 0.000999987 0.018 0.02073568 0.01773905 0.018 0.02111977 0.01791179 0.018 0.02148067 0.01812976 0.018 0.02181208 0.01838946 0.018 0.02210944 0.01868677 0.018 0.0223695 0.01901835 0.018 0.02258765 0.01937919 0.018 0.02276027 0.01976269 0.018 0.02288556 0.02016448 0.018 0.02296167 0.02057898 0.018 0.02298718 0.02099996 0.018 0.02296149 0.02142286 0.018 0.02288508 0.02183759 0.018 0.02271997 0.02234685 0.018 0.03899997 0.000999987 0.018 0.03899997 0 0.018 0.03399997 0.000999987 0.018 0.02258396 0.02262777 0.018 0.02258396 0.02262777 0.01699995 0.03399997 0.000999987 0.01699995 0.01876193 0.02167969 0.01699995 0.01657021 0.02289694 0.01699995 0.01752299 0.02387267 0.01699995 0.01902252 0.02188253 0.01699995 0.01788336 0.02408987 0.01699995 0.01703411 0.02347469 0.01699995 0.01933491 0.0219897 0.01699995 0.01846373 0.02433627 0.01699995 0.01908105 0.02446198 0.01699995 0.01858121 0.02140325 0.01699995 0.01950097 0.02448719 0.01699995 0.019665 0.0219897 0.01699995 0.02012991 0.02443617 0.01699995 0.02073478 0.02426129 0.01699995 0.02130454 0.02399122 0.01699995 0.01850003 0.02108323 0.01699995 0.0204187 0.02059668 0.01699995 0.02242988 0.02289676 0.01699995 0.01933491 0.02001023 0.01699995 0.004999995 0.000999987 0.01699995 0.02023798 0.02167969 0.01699995 0.01997739 0.02188253 0.01699995 0.02180868 0.02361357 0.01699995 0.02210658 0.0233165 0.01699995 0.0204187 0.02140325 0.01699995 0.02049994 0.02108323 0.01699995 0.02048635 0.02083539 0.01699995 0.02023798 0.02032023 0.01699995 0.01997739 0.02011746 0.01699995 0.03399997 0.000999987 0.01699995 0.019665 0.02001023 0.01699995 0.01876193 0.02032023 0.01699995 0.01902252 0.02011746 0.01699995 0.01858121 0.02059668 0.01699995 0.01851356 0.02083539 0.01699995 0.03899997 0.000999987 0 0.03899997 0 0.018 0.03899997 0.000999987 0.018 0.03899997 0 0 0.03899997 0 0 0 0 0.018 0.03899997 0 0.018 0 0 0 0 0 0 0 0.000999987 0 0 0.000999987 0.018 0 0 0.018 0.03899997 0.000999987 0.018 0.03399997 0.000999987 0.01699995 0.03399997 0.000999987 0.000999987 0.004999995 0.000999987 0.01699995 0.004999995 0.000999987 0.018 0 0.000999987 0.018 0.004999995 0.000999987 0 0.004999995 0.000999987 0.000999987 0 0.000999987 0 0.03899997 0.000999987 0 0.03399997 0.000999987 0 0.03399997 0.000999987 0.018 0.02258396 0.02262777 0.000999987 0.03399997 0.000999987 0 0.03399997 0.000999987 0.000999987 0.02258396 0.02262777 0 0.004999995 0.000999987 0.000999987 0.01641595 0.02262777 0 0.01641595 0.02262777 0.000999987 0.004999995 0.000999987 0 0 0 0 0.03399997 0.000999987 0 0.004999995 0.000999987 0 0 0.000999987 0 0.03899997 0 0 0.03899997 0.000999987 0 0.01866638 0.01761388 0 0.01826357 0.01773929 0 0.01611489 0.02183759 0 0.01627999 0.02234685 0 0.01601278 0.02099996 0 0.01603847 0.02142286 0 0.01611447 0.02016425 0 0.01603829 0.0205788 0 0.01641249 0.01937878 0 0.01623958 0.01976299 0 0.01689028 0.01868695 0 0.01663076 0.01901805 0 0.01751995 0.01812946 0 0.01718789 0.01838946 0 0.01788026 0.01791179 0 0.01949995 0.01751279 0 0.01908075 0.01753807 0 0.01992118 0.01753824 0 0.02033567 0.01761448 0 0.02073699 0.01773959 0 0.0211212 0.01791244 0 0.02148187 0.01813077 0 0.02181297 0.01839029 0 0.02237045 0.01901996 0 0.02211046 0.0186879 0 0.02276068 0.01976358 0 0.02258819 0.01938027 0 0.02293634 0.02037072 0 0.02296149 0.02142286 0 0.02288466 0.02183938 0 0.02298718 0.02099996 0 0.0227198 0.02234715 0 0.01858121 0.02140325 0.000999987 0.01657009 0.02289676 0.000999987 0.01769536 0.02399122 0.000999987 0.01902252 0.02188253 0.000999987 0.01719129 0.02361357 0.000999987 0.01933491 0.0219897 0.000999987 0.01876193 0.02167969 0.000999987 0.01689338 0.0233165 0.000999987 0.01826518 0.02426129 0.000999987 0.01886999 0.02443617 0.000999987 0.01851356 0.02116459 0.000999987 0.019499 0.02448719 0.000999987 0.019665 0.0219897 0.000999987 0.01850003 0.02091675 0.000999987 0.01991885 0.02446198 0.000999987 0.02053618 0.02433627 0.000999987 0.02111655 0.02408987 0.000999987 0.01997739 0.02188253 0.000999987 0.01855415 0.02067518 0.000999987 0.01865988 0.02045142 0.000999987 0.004999995 0.000999987 0.000999987 0.01997804 0.02011781 0.000999987 0.02023845 0.02032071 0.000999987 0.03399997 0.000999987 0.000999987 0.02242976 0.02289694 0.000999987 0.02048635 0.02083539 0.000999987 0.02049994 0.02108323 0.000999987 0.0219658 0.02347469 0.000999987 0.02041864 0.02059656 0.000999987 0.01974576 0.02003067 0.000999987 0.01950007 0.01999664 0.000999987 0.0192548 0.02003049 0.000999987 0.01902276 0.02011734 0.000999987 0.01882284 0.02026408 0.000999987 0.02147698 0.02387267 0.000999987 0.02023798 0.02167969 0.000999987 0.0204187 0.02140325 0.000999987 0.02291387 0.0217871 -0.000999987 0.02300757 0.02100127 0 0.02261018 0.02264314 0 0.02298718 0.02099996 -0.000999987 0.0221889 0.02329796 -0.000999987 0.022601 0.0226382 9.99997e-4 0.02161812 0.02380901 9.99999e-4 0.02060407 0.02434033 -10e-4 0.01928925 0.02448898 -10e-4 0.02007287 0.0244711 9.99999e-4 0.01800197 0.02418321 -9.99999e-4 0.01866251 0.02439808 10e-4 0.01738089 0.02380824 0.000999987 0.0163989 0.02263826 9.99999e-4 0.01684355 0.02328407 -9.99999e-4 0.01640969 0.02263152 0 0.01612389 0.02198988 -9.99998e-4 0.01595574 0.0210039 0 0.01601278 0.02099996 -0.000999987 0.01955425 0.01749694 0 0.01986223 0.0174815 -0.000999987 0.01811236 0.01776701 0 0.0182082 0.01774334 -0.000999987 0.01691389 0.01863652 0 0.01713657 0.01841378 -9.99999e-4 0.01624405 0.0197066 0 0.01637303 0.01942008 -9.99999e-4 0.01599246 0.02099865 0 0.01596963 0.02099704 -9.99999e-4 0.02079319 0.017744 0 0.02162092 0.018193 -9.99999e-4 0.02186334 0.01841384 0 0.0226826 0.01950055 -9.99998e-4 0.02262681 0.0194199 0 0.02303034 0.02099704 0 0.02300745 0.02099865 -9.99999e-4 0.01855963 0.0206139 0 0.01866239 0.020424 0.000999987 0.01848345 0.02114343 0.000999987 0.01893079 0.02016723 0 0.01947599 0.01998376 0 0.01935571 0.01997119 10e-4 0.02014327 0.02021294 10e-4 0.02024585 0.0202769 0 0.02051651 0.02085679 10e-4 0.02051651 0.02114337 0 0.02033758 0.02157592 0.000999987 0.02008271 0.02184516 0 0.01964443 0.02202874 0.000999987 0.01927298 0.02200114 0 0.018857 0.02178728 0.000999987 0.01855969 0.02144163 0 0.01826268 0.01773965 -0.000999987 0.01906979 0.01930367 -0.000999987 0.01866352 0.01945614 -0.000999987 0.01803004 0.02196049 -0.000999987 0.01689046 0.02331316 -0.000999987 0.01663047 0.02298158 -0.000999987 0.01787847 0.01791268 -0.000999987 0.01907885 0.01753836 -0.000999987 0.01949936 0.01924413 -0.000999987 0.01991975 0.01753807 -0.000999987 0.01992905 0.01930338 -0.000999987 0.019499 0.01751279 -0.000999987 0.01820784 0.01981109 -0.000999987 0.01751846 0.01813048 -0.000999987 0.02033436 0.01761406 -0.000999987 0.02073568 0.01773905 -0.000999987 0.01688915 0.0186882 -0.000999987 0.01796078 0.02016735 -0.000999987 0.01662957 0.0190199 -0.000999987 0.02111977 0.01791179 -0.000999987 0.02033543 0.01945555 -0.000999987 0.01779776 0.02056914 -0.000999987 0.01623916 0.01976388 -0.000999987 0.02148067 0.01812976 -0.000999987 0.01606363 0.0203706 -0.000999987 0.02181208 0.01838946 -0.000999987 0.02210944 0.01868677 -0.000999987 0.0223695 0.01901835 -0.000999987 0.02097004 0.02003967 -0.000999987 0.02068495 0.01971215 -0.000999987 0.02120208 0.02056884 -0.000999987 0.02288556 0.02016448 -0.000999987 0.02296167 0.02057898 -0.000999987 0.01774996 0.02099996 -0.000999987 0.01779788 0.02143132 -0.000999987 0.01603829 0.02142095 -0.000999987 0.02296167 0.02142095 -0.000999987 0.02288609 0.02183359 -0.000999987 0.02124989 0.02114462 -0.000999987 0.0162397 0.0222373 -0.000999987 0.02110809 0.02170521 -0.000999987 0.02258789 0.02262026 -0.000999987 0.02237039 0.02298009 -0.000999987 0.02057832 0.02238571 -0.000999987 0.02181267 0.02360999 -0.000999987 0.02148145 0.02386945 -0.000999987 0.01718789 0.02361047 -0.000999987 0.01842164 0.02238571 -0.000999987 0.01751929 0.02387017 -0.000999987 0.0211215 0.02408725 -0.000999987 0.02073729 0.02426028 -0.000999987 0.02006989 0.02266085 -0.000999987 0.01992106 0.02446156 -0.000999987 0.01950097 0.02448719 -0.000999987 0.01949995 0.02275586 -0.000999987 0.01908016 0.02446186 -0.000999987 0.0203346 0.02438586 -0.000999987 0.01866555 0.02438586 -0.000999987 0.01826429 0.02426087 -0.000999987 0.01893007 0.02266085 -0.000999987 0.0178802 0.0240882 -0.000999987 0.02211076 0.02331179 -0.000999987 0.02088099 0.02207487 -0.000999987 0.02276074 0.02223604 -0.000999987 0.01641225 0.02262079 -0.000999987 0.02298718 0.02099996 -0.000999987 0.01611435 0.0218355 -0.000999987 0.02276027 0.01976269 -0.000999987 0.01601278 0.02099996 -0.000999987 0.02258765 0.01937919 -0.000999987 0.01866525 0.01761406 -0.000999987 0.01718729 0.01838999 -0.000999987 0.01641207 0.01937967 -0.000999987 0.02023798 0.02167969 0 0.02088099 0.02207487 0 0.01949995 0.02275586 0 0.01893007 0.02266085 0 0.01933491 0.0219897 0 0.01902252 0.02188253 0 0.019665 0.0219897 0 0.02006989 0.02266085 0 0.01842164 0.02238571 0 0.01876193 0.02167969 0 0.01997739 0.02188253 0 0.01803004 0.02196049 0 0.02057832 0.02238571 0 0.01858121 0.02140325 0 0.01779788 0.02143132 0 0.01851356 0.02083539 0 0.01779782 0.02056884 0 0.0204187 0.02140325 0 0.02110809 0.02170521 0 0.02124989 0.02114462 0 0.02048635 0.02083539 0 0.02120214 0.02056914 0 0.02103918 0.02016735 0 0.02023798 0.02032023 0 0.02079206 0.01981109 0 0.01858121 0.02059668 0 0.01802992 0.02003967 0 0.01997739 0.02011746 0 0.02033644 0.01945614 0 0.01876193 0.02032023 0 0.01831495 0.01971215 0 0.01902252 0.02011746 0 0.019665 0.02001023 0 0.01933491 0.02001023 0 0.01950061 0.01924413 0 0.01907086 0.01930338 0 0.01993018 0.01930367 0 0.01866453 0.01945555 0 0.0204187 0.02059668 0 0.02049994 0.02108323 0 0.01774996 0.02099996 0 0.01850003 0.02108323 0 0.02126473 0.02096295 -0.000999987 0.0212959 0.02104502 0 0.02094507 0.0220673 -0.000999987 0.02078002 0.02223521 0 0.01983451 0.02274715 -0.000999987 0.02004522 0.0226686 0 0.01916545 0.02274715 0 0.01895475 0.0226686 -0.000999987 0.0180549 0.0220673 0 0.01821988 0.02223521 -0.000999987 0.01770406 0.02104502 -9.99999e-4 0.01808446 0.01994556 -10e-4 0.01803416 0.01999205 0 0.01773524 0.02096301 0 0.01901507 0.01927018 -10e-4 0.01882529 0.01936882 0 0.02017462 0.01936882 -0.000999987 0.0199849 0.01927018 0 0.02096575 0.01999205 -10e-4 0.0209155 0.01994556 0 + + + + + + + + + + -0.6850261 0.7284238 0.01174974 -0.7304847 0.6829048 -0.005768179 -0.9743012 0.2240734 0.0229811 -0.212565 0.9770972 0.009857594 0.7304849 0.6829049 0.005737662 0.212565 0.9770972 -0.009857594 0.3353155 0.9421001 0.003326594 0.7969774 -0.6030586 0.03387624 0.9047665 -0.4250077 -0.02768069 0.9991266 0.03186166 0.0270397 0.9717344 0.2353343 -0.01870828 0.4676827 -0.8831462 -0.03640985 0.2653629 -0.963882 0.02267563 -0.3888478 -0.920679 0.03387653 -0.1898572 -0.9814224 -0.02764999 -0.8748245 -0.4840299 0.01992881 -0.7488562 -0.661479 -0.04074347 -0.9994896 0.02075272 -0.02429288 0.6850098 0.728439 -0.01174998 -0.3353155 0.9421001 -0.003326594 0 0 1 1.12329e-6 0 1 3.12437e-6 0 1 1.34416e-6 0 1 9.74305e-7 0 1 -3.75561e-6 0 1 5.00445e-6 0 1 -1.87199e-6 0 1 4.99309e-6 0 1 2.40025e-6 0 1 -1.24194e-6 0 1 -3.59494e-6 0 1 7.41187e-7 0 1 1.24673e-6 0 1 -1.24983e-6 0 1 4.98435e-6 0 1 9.00703e-7 0 1 -9.95244e-6 0 1 -5.99922e-7 0 1 -2.40204e-6 0 1 2.50672e-6 0 1 9.98734e-6 0 1 -4.98665e-6 0 1 -1.2441e-6 0 1 1.23974e-6 0 1 -1.86747e-6 0 1 2.50737e-6 0 1 -1.24492e-6 0 1 0 5.87942e-6 1 0 2.49816e-6 1 9.64371e-6 -9.15466e-7 1 0 5.9312e-6 1 0 -6.33652e-6 1 1.41459e-6 -4.42441e-6 1 0 4.0931e-6 1 0 4.42439e-6 1 2.84642e-6 -4.09321e-6 1 2.15938e-6 0 1 7.18949e-6 0 1 2.4076e-6 -7.72502e-6 1 0 7.60646e-6 1 0 -6.93856e-6 1 0 6.35926e-6 1 -1.07006e-6 1.01755e-6 1 0 1.7159e-6 1 -4.31872e-6 0 1 6.76304e-6 0 1 -1.20393e-6 -9.06031e-7 1 8.09935e-7 0 1 4.8626e-6 -7.60441e-6 1 0 7.72159e-6 1 -0.0303052 -0.9995223 0.006073236 0.09421163 -0.995494 -0.01077312 0.3726349 -0.9278333 -0.01638859 0.6014158 -0.7984492 -0.02789473 0.6916481 -0.7222279 0.003143429 0.9058107 -0.4236679 -0.003540217 0.895071 -0.4457044 0.01397782 0.9770363 -0.2118631 -0.02267563 0.9743182 -0.225169 -0.001800596 -0.3806059 -0.9247339 -0.00250256 -0.3387268 -0.9408297 -0.01019322 -0.7353327 -0.6774986 0.01678562 -0.6674324 -0.7446469 -0.005920767 -0.9348176 -0.3551269 0.001007139 -0.8968502 -0.4419399 -0.01867735 -0.9813118 -0.1910802 0.02270621 -0.9766449 -0.214672 -0.008972644 -0.96845 0.249002 -0.01013219 -0.885517 0.4645646 0.006286919 -0.9835548 0.1748467 -0.04526054 -0.995489 0.0926547 0.02041697 -0.7415546 0.669682 0.04028528 -0.590917 0.8065977 -0.01474088 -0.782047 0.6216702 -0.0439167 0.5967379 0.8023443 -0.01214653 0.2392076 0.970961 -0.003814816 0.2389928 0.9708952 0.01565611 0.7845951 0.6196373 -0.02145516 0.6724285 0.7397233 0.02548348 0.866539 0.4989321 0.01330643 0.9504778 0.310773 -0.003479123 0.9813216 0.19096 -0.02328628 0.992145 0.1113641 0.05697911 -0.1625728 0.9866065 -0.01333659 -0.2661246 0.9636641 0.0230112 0.988672 -0.1478659 0.02575826 0.7084626 -0.7055938 -0.01477104 0.9917321 0.1199991 -0.04547268 0.600158 -0.7998139 0.01040697 -0.1145974 -0.9932897 0.01559501 0.0453816 -0.9989449 -0.007049858 -0.1604394 0.9856178 -0.05307286 -0.5695453 0.8211437 0.03662276 0.2189142 0.9748136 0.04260474 0.6249769 0.7794052 -0.04394793 0.8226109 0.5672884 0.03866761 -0.8949682 0.4431352 -0.05160754 -0.9893137 0.1402667 0.03979712 -0.9372463 -0.3469734 -0.03433412 -0.8162569 -0.5759516 0.04477113 -0.5667333 -0.8237013 -0.01815861 0.8843619 -0.466802 0 0.884363 -0.4667999 0 -1.13103e-5 0 1 1.40486e-5 0 1 2.63519e-5 -9.37308e-6 1 -3.48771e-6 0 1 -1.1721e-6 0 1 7.18286e-6 0 1 4.28134e-6 0 1 2.55363e-6 0 1 7.36242e-6 0 1 -6.92521e-6 0 1 -6.67501e-6 0 1 6.94983e-6 0 1 6.53186e-6 0 1 -7.23865e-7 0 1 -8.95183e-7 0 1 -2.64885e-6 0 1 7.42241e-6 0 1 -1.40485e-5 0 1 -5.24356e-5 -9.32507e-6 1 0.8843619 0.4668018 0 0.8843629 0.4668001 0 2.52123e-6 0 1 -1.66739e-6 0 1 -4.6696e-6 0 1 4.6568e-6 0 1 4.59569e-6 0 1 -1.189e-6 0 1 -1.16287e-6 0 1 1.15882e-6 0 1 5.76911e-7 0 1 -4.66102e-6 0 1 -2.55481e-6 0 1 8.5821e-7 0 1 2.76987e-6 0 1 -4.51634e-6 0 1 -2.20263e-6 0 1 5.18726e-5 0 1 -1.64258e-6 0 1 8.16301e-7 0 1 9.73379e-7 0 1 2.14995e-6 0 1 2.59488e-5 0 1 -2.80345e-6 0 1 1 0 0 0 -1 0 -1 0 0 0 1 0 0.8843623 0.4668012 0 0.8843625 0.4668011 0 0.8843625 -0.4668011 0 0.8843623 -0.4668011 0 0 0 -1 1.95159e-7 0 1 -3.91276e-7 0 1 -4.07636e-7 0 1 0 0 1 -1.48088e-7 0 1 7.04841e-7 0 1 -3.09171e-7 0 1 -4.66289e-7 0 1 3.48085e-7 0 1 1.26639e-6 0 1 1.60914e-7 0 1 0 0 1 0 0 1 0 0 1 1.24182e-7 0 1 0 0 1 1.48632e-7 0 1 0.96845 0.249002 0.01013219 0.885517 0.4645646 -0.006286919 0.9835548 0.1748467 0.04526054 0.995489 0.0926547 -0.02041697 0.7468027 0.6640043 -0.03720277 0.5923441 0.805428 0.02035617 0.782047 0.6216702 0.0439167 -0.6074177 0.7941019 0.02111905 -0.235849 0.9715343 0.02227866 -0.4279983 0.9035758 -0.01919639 -0.7848379 0.6191784 0.0254532 -0.7558743 0.6541532 -0.02716225 -0.8809552 0.4731937 -0.002410948 -0.9541114 0.299207 0.01211595 -0.9813216 0.19096 0.02328628 -0.992145 0.1113641 -0.05697911 0.1703903 0.9851079 0.02301168 -0.06207484 0.9978973 -0.01864683 0.3358976 0.9416181 -0.02298116 -0.8968443 -0.4419521 -0.01867789 -0.9909899 0.1290047 0.03601264 -0.8990401 0.4351759 -0.04846477 0.1403253 0.9892054 0.04220747 0.5715677 0.8192633 -0.04602324 -0.2387222 0.9696299 -0.05319517 -0.6211256 0.7827551 0.03869825 0.8179168 0.573793 0.04211658 0.9902223 0.1299502 -0.05072271 0 0 -1 -2.25016e-7 0 -1 0 0 -1 3.11645e-7 0 -1 -3.12132e-7 0 -1 -1.56341e-7 0 -1 2.34959e-7 0 -1 0 0 -1 -1.9444e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.50247e-7 0 -1 0 0 -1 -1.56214e-7 0 -1 1.49817e-7 0 -1 0 0 -1 -1.49906e-7 0 -1 3.11975e-7 0 -1 0 0 -1 -1.56167e-7 0 -1 -1.56046e-7 0 -1 0 0 -1 0.7223257 0.6915014 0.008453786 0.8016074 0.5977722 -0.009704947 0.226207 0.9737403 -0.02569699 -0.7223257 0.6915014 -0.008453786 -0.226207 0.9737403 0.02569699 -0.795454 -0.6058989 -0.01181095 -0.8203924 -0.5715982 -0.01522916 -0.9995189 0.02856552 -0.01208537 -0.2820562 -0.9593937 -0.002868771 0.4027327 -0.9152128 -0.01385575 0.2820562 -0.9593937 0.002868771 0.8203924 -0.5715982 0.01522916 0.795454 -0.6058989 0.01181095 0.9995189 0.02856552 0.01208537 0.9992972 -0.0234999 -0.02920705 -0.4027327 -0.9152128 0.01385575 -0.9992972 -0.0234999 0.02920705 -0.8016076 0.5977723 0.009674429 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.005562365 0.04258525 0.001999974 -0.0107795 0.03987348 0 -0.0107795 0.03987348 0.001999974 0.00262767 0.04408955 0.001999974 0.003372311 0.04408955 0 -0.004858732 0.04282909 0 0.01156228 0.04258531 0 0.01085865 0.04282909 0.001999974 0.01677948 0.03987348 0.001999974 0.01677948 0.03987348 0 0.01677948 0.03987348 0.001999974 0.01820278 0.03987348 0.001999974 0.01820278 0.03987348 0 0.01677948 0.03987348 0 0.01820278 0.03987348 0.001999974 0.02385956 0.0342167 0.001999974 0.02385956 0.0342167 0 0.01820278 0.03987348 0 0.02385956 0.0342167 0 0.02385956 0.0342167 0.001999974 0.02385956 0.0327934 0.001999974 0.02385956 0.0327934 0 0.02401059 0.03287494 0.001999974 0.02410221 0.03292447 0 0.02778947 0.01521819 0.001999974 0.02778947 0.02280956 0 0.02766585 0.02354389 0.001999974 0.02401059 0.005152761 0 0.02766585 0.01448386 0 0.02410221 0.00510323 0.001999974 0.02385956 0.005234301 0.001999974 0.02385956 0.003811061 0.001999974 0.02385956 0.003811061 0 0.02385956 0.005234301 0 0.02385956 0.003811061 0.001999974 0.01820278 -0.001845717 0.001999974 0.01820278 -0.001845717 0 0.02385956 0.003811061 0 0.01820278 -0.001845717 0.001999974 0.01677948 -0.001845717 0.001999974 0.01677948 -0.001845717 0 0.01820278 -0.001845717 0 0.01156234 -0.004557549 0.001999974 0.01677948 -0.001845717 0 0.01677948 -0.001845717 0.001999974 0.003372311 -0.006061732 0.001999974 0.00262767 -0.006061732 0 0.01085877 -0.004801332 0 -0.005562424 -0.00455749 0 -0.004858851 -0.004801332 0.001999974 -0.0107795 -0.001845717 0.001999974 -0.0107795 -0.001845717 0 -0.0107795 -0.001845717 0.001999974 -0.01220279 -0.001845717 0.001999974 -0.01220279 -0.001845717 0 -0.0107795 -0.001845717 0 -0.01220279 -0.001845717 0.001999974 -0.01785957 0.003811061 0.001999974 -0.01785957 0.003811061 0 -0.01220279 -0.001845717 0 -0.01785957 0.003811061 0.001999974 -0.01785957 0.005234301 0.001999974 -0.01785957 0.005234301 0 -0.01785957 0.003811061 0 -0.01804459 0.03289598 0.001999974 -0.02196449 0.02221554 0.001999974 -0.02182996 0.02313083 0 -0.02153056 0.01388913 0 -0.01797485 0.03285729 0 -0.02138948 0.01325488 0.001999974 -0.01804459 0.005131721 0 -0.01797485 0.005170404 0.001999974 -0.01785957 0.0327934 0.001999974 -0.01785957 0.0342167 0.001999974 -0.01785957 0.0342167 0 -0.01785957 0.0327934 0 -0.01785957 0.0342167 0.001999974 -0.01220279 0.03987348 0.001999974 -0.01220279 0.03987348 0 -0.01785957 0.0342167 0 -0.01220279 0.03987348 0.001999974 -0.0107795 0.03987348 0.001999974 -0.0107795 0.03987348 0 -0.01220279 0.03987348 0 -0.01206058 0.003940641 0 -0.01213574 0.004198551 0.001999974 -0.01183533 0.003897607 0.001999974 -0.0115627 0.004198551 0 -0.01159191 0.004333853 0.001999974 -0.01192754 0.00442022 0 0.01757222 0.03384792 0.001999974 0.01783537 0.03359603 0 0.01796311 0.033598 0.001999974 0.01813572 0.03389698 0 0.01798379 0.03413057 0.001999974 0.01759189 0.03403234 0 0.005999982 0.00999999 0.001999974 0.005999982 0.00999999 0 0.005999982 0 0 0.005999982 0 0.001999974 0.003990709 0.02854472 0 0.002009272 0.02854472 0.001999974 0.008127927 0.02730947 0.001999974 0.008407413 0.02692455 0 0.01229423 0.02196305 0 0.01166945 0.0229696 0.001999974 0.01263433 0.01853609 0.001999974 0.01157134 0.014418 0 0.01087391 0.01356858 0.001999974 0.006102204 0.009764492 0.001999974 0.006077527 0.00982064 0 -0.002127945 0.02730947 0 -0.002407371 0.02692455 0.001999974 -0.00629425 0.02196294 0.001999974 -0.006298363 0.02161681 0 -0.005571246 0.01441788 0.001999974 -0.005994141 0.01554429 0 -0.00281924 0.01141208 0 -7.75439e-5 0.00982064 0.001999974 0 0.00999999 0 0 0 0.001999974 0 0 0 0 0.00999999 0 0 0.00999999 0.001999974 0 0 0.001999974 0.005999982 0 0.001999974 0.005999982 0 0 0 0 0 -0.01201361 0.03361278 0 -0.0120517 0.03367346 0.001999974 -0.01157218 0.03384792 0 -0.01159155 0.03373318 0.001999974 -0.01191818 0.03415447 0.001999974 -0.01193249 0.03413933 0 -0.0118491 0.03359538 0.001999974 -0.005355 0.02353537 0.001999974 -0.01785957 0.005234301 0.001999974 -0.01785957 0.003811061 0.001999974 0.009434163 0.0260033 0.001999974 0.01757156 0.03386306 0.001999974 0.008195996 0.02696698 0.001999974 0.01238435 0.0175361 0.001999974 0.02722156 0.01282417 0.001999974 0.02791309 0.01693135 0.001999974 -0.02173417 0.02264958 0.001999974 -0.006370425 0.02057749 0.001999974 -0.02094244 0.02620786 0.001999974 0.01784914 0.03359538 0.001999974 0.02585786 0.02913898 0.001999974 -0.007125079 -0.003843963 0.001999974 0 0 0.001999974 -0.01158553 0.004118204 0.001999974 0.02385956 0.0327934 0.001999974 0.0180931 0.03377413 0.001999974 0.01312506 -0.003843963 0.001999974 0.01760524 0.004075884 0.001999974 0.005999982 0 0.001999974 0.007365584 0.01057636 0.001999974 0.01771038 0.004405021 0.001999974 0.00862497 0.0113582 0.001999974 0.009189665 -0.005207717 0.001999974 0.01027023 0.01285445 0.001999974 9.17493e-4 -0.00589919 0.001999974 0.005082488 -0.00589919 0.001999974 0.01677948 -0.001845717 0.001999974 0.02585786 0.008888721 0.001999974 -0.001365602 0.01057636 0.001999974 0 0.00999999 0.001999974 -0.02094244 0.01181977 0.001999974 -0.006040215 0.01609426 0.001999974 -0.006384313 0.0175361 0.001999974 0.02385956 0.005234301 0.001999974 0.01808094 0.004298567 0.001999974 0.02385956 0.003811061 0.001999974 0.01249998 0.01901388 0.001999974 0.02791309 0.02109634 0.001999974 -0.006499946 0.01901388 0.001999974 -0.00598526 0.02209848 0.001999974 -0.01964175 0.02961325 0.001999974 -0.01206892 0.004037797 0.001999974 -0.01785957 0.0327934 0.001999974 -0.01206886 0.03373622 0.001999974 0.01677948 0.03987348 0.001999974 0.006816089 0.02771365 0.001999974 -0.004496812 0.02484887 0.001999974 0.005332052 0.02822315 0.001999974 0.01312506 0.04187166 0.001999974 0.009189665 0.04323548 0.001999974 -0.003189682 0.04323548 0.001999974 -8.16107e-4 0.02771365 0.001999974 6.67888e-4 0.02822315 0.001999974 0.005082488 0.04392695 0.001999974 9.17493e-4 0.04392695 0.001999974 0.002215445 0.02848136 0.001999974 -0.01175767 0.03411465 0.001999974 -0.01220279 0.03987348 0.001999974 -0.01208102 0.03399699 0.001999974 0.003784477 0.02848136 0.001999974 -0.007125079 0.04187166 0.001999974 -0.0107795 0.03987348 0.001999974 0.01204025 0.01609426 0.001999974 -0.01175779 0.004416167 0.001999974 -0.002624928 0.0113582 0.001999974 -0.004270374 0.01285457 0.001999974 -0.02173417 0.01537817 0.001999974 -0.02199995 0.01901388 0.001999974 0.01147609 0.01472359 0.001999974 0.01237034 0.02057749 0.001999974 0.02722156 0.02520358 0.001999974 0.0119853 0.02209848 0.001999974 0.01135498 0.02353537 0.001999974 0.01049679 0.02484887 0.001999974 -0.003434121 0.0260033 0.001999974 -0.01785957 0.0342167 0.001999974 -0.01964175 0.008414387 0.001999974 -0.005476057 0.01472359 0.001999974 -0.0118491 0.003896892 0.001999974 -0.0107795 -0.001845717 0.001999974 -0.01220279 -0.001845717 0.001999974 -0.003189682 -0.005207717 0.001999974 0.005999982 0.00999999 0.001999974 0.02385956 0.0342167 0.001999974 0.01820278 0.03987348 0.001999974 0.01804792 0.03403013 0.001999974 0.01780402 0.03411865 0.001999974 -0.01158553 0.03381669 0.001999974 -0.002195954 0.02696698 0.001999974 -0.01208102 0.004298508 0.001999974 0.01784914 0.003896892 0.001999974 0.01820278 -0.001845717 0.001999974 0.0180689 0.004037797 0.001999974 0.01249998 0.01901388 0 0.01237034 0.02057749 0 0.02791309 0.02109634 0 -0.01157158 0.03386306 0 -0.0107795 0.03987348 0 -0.007125079 0.04187166 0 0.01204025 0.01609426 0 0.02722156 0.01282417 0 0.02585786 0.008888721 0 -0.003189682 0.04323548 0 6.67888e-4 0.02822315 0 -8.16107e-4 0.02771365 0 0.018081 0.03399699 0 0.02385956 0.0342167 0 -0.02094244 0.02620786 0 -0.00598526 0.02209848 0 -0.006370425 0.02057749 0 0.005082488 -0.00589919 0 9.17493e-4 -0.00589919 0 0.005999982 0 0 -0.0118491 0.003896892 0 -0.01220279 -0.001845717 0 0.02585786 0.02913898 0 0.01784914 0.03359538 0 0.02385956 0.0327934 0 0.0180689 0.03373622 0 -0.003189682 -0.005207717 0 0 0 0 -0.002624928 0.0113582 0 -0.001365602 0.01057636 0 -0.01160526 0.004075884 0 -0.0107795 -0.001845717 0 -0.007125079 -0.003843963 0 0.01758551 0.004118204 0 0.01677948 -0.001845717 0 0.01312506 -0.003843963 0 0.0180689 0.004037797 0 0.02385956 0.003811061 0 0.01820278 -0.001845717 0 -0.0117104 0.004405021 0 -0.004270374 0.01285457 0 -0.01964175 0.008414387 0 -0.01204812 0.00433135 0 -0.01209306 0.004075586 0 0.01784914 0.003896892 0 0.005999982 0.00999999 0 0.007365584 0.01057636 0 -0.01785957 0.005234301 0 -0.01785957 0.003811061 0 -0.01964175 0.02961325 0 -0.0118491 0.03359538 0 0.01677948 0.03987348 0 -0.004496812 0.02484887 0 0.005332052 0.02822315 0 0.009189665 0.04323548 0 0.01312506 0.04187166 0 0.008195996 0.02696698 0 0.01758551 0.03381669 0 0.009434163 0.0260033 0 0.01049679 0.02484887 0 0.006816089 0.02771365 0 0.0119853 0.02209848 0 0.01135498 0.02353537 0 -0.01220279 0.03987348 0 -0.01204806 0.03402996 0 -0.02173417 0.01537817 0 -0.006499946 0.01901388 0 -0.006384313 0.0175361 0 0.02722156 0.02520358 0 0.009189665 -0.005207717 0 0.00862497 0.0113582 0 -0.005355 0.02353537 0 -0.02094244 0.01181977 0 0.005082488 0.04392695 0 0.003784477 0.02848136 0 0.01820278 0.03987348 0 -0.006040215 0.01609426 0 0.002215445 0.02848136 0 9.17493e-4 0.04392695 0 0.018081 0.004298508 0 0.02385956 0.005234301 0 0.01775771 0.03411465 0 -0.005476057 0.01472359 0 -0.01785957 0.0327934 0 -0.01209306 0.03377401 0 0.01027023 0.01285445 0 0.01775777 0.004416167 0 0.01147609 0.01472359 0 0.01238435 0.0175361 0 0.02791309 0.01693135 0 -0.003434121 0.0260033 0 -0.02173417 0.02264958 0 -0.02199995 0.01901388 0 0 0.00999999 0 -0.01785957 0.0342167 0 -0.002195954 0.02696698 0 -0.01180398 0.03411865 0 0.01759195 0.004333853 0 0.01769757 0.004396855 0.001999974 0.01813572 0.004198491 0 0.01813006 0.004230618 0.001999974 0.01771461 0.00389707 0.001999974 0.01783537 0.003897607 0 + + + + + + + + + + -0.3483716 0.9373531 -0.002563536 -0.4581566 0.8888152 -0.0100103 -0.4612095 0.8872913 0 0.03674501 0.999319 0.00338757 0.284134 0.9587615 -0.006653189 0.3483716 0.9373531 0.002563536 0.4581566 0.8888152 0.0100103 0.4612095 0.8872913 0 -0.03674501 0.9993188 -0.003418087 -0.284134 0.9587615 0.006653189 0 1 0 0.707107 0.7071067 0 0.7071065 0.7071071 0 1 0 0 0.9899399 -0.1414853 0.001037597 0.9899399 0.1414853 -0.001037597 0.9755172 0.219586 -0.01217716 0.9315705 0.3617145 0.0365926 0.9298754 -0.3642411 -0.05157661 0.9755172 -0.219586 0.01217716 0.9315705 -0.3617145 -0.0365926 0.9298754 0.3642411 0.05157661 0.7071098 -0.7071038 0 0.7071102 -0.7071033 0 0 -1 0 0.3483716 -0.9373531 -0.002563536 0.4581566 -0.8888152 -0.0100103 0.4612095 -0.8872913 0 -0.03674501 -0.999319 0.00338757 -0.284134 -0.9587615 -0.006653189 -0.3483716 -0.9373531 0.002563536 -0.4581566 -0.8888152 0.0100103 -0.4612095 -0.8872913 0 0.03674501 -0.999319 -0.00338757 0.284134 -0.9587615 0.006653189 -0.7071098 -0.7071038 0 -0.7071099 -0.7071037 0 -1 0 0 -0.9305209 0.3654942 -0.0233469 -0.97701 0.2120166 0.02237051 -0.9944943 0.1044973 -0.007843375 -0.9824259 -0.186652 -6.7141e-4 -0.9289138 0.368184 -0.03949183 -0.9678457 -0.2515062 -0.00439471 -0.9220385 -0.3861868 0.02655148 -0.9204788 -0.3887795 0.03961342 -0.7071067 0.707107 0 -0.7071065 0.7071071 0 0.9947318 -0.0273754 -0.09878951 0.1434989 -0.9871885 0.06976574 -0.6241454 -0.7688363 -0.1390448 -0.3607695 0.9296505 -0.07480293 0.7952518 0.5926926 0.1276333 -0.9585523 0.2602997 0.1158515 0.962347 0.2495516 -0.1077616 0.4478374 -0.8890826 0.09473127 -0.1343129 -0.9885929 -0.06814825 -0.7948831 0.5904933 -0.1395661 0.4758204 0.871132 0.1213432 -0.9965645 -0.02850461 0.07776218 0.1185954 0.9917035 0.04959279 -0.1185954 0.9917035 -0.04959279 0.5373464 0.8423829 -0.04062062 0.6183608 0.783259 -0.06430512 0.949856 0.3119695 0.02118045 0.8632959 0.5044515 0.01577836 0.9838813 -0.07605409 -0.1618438 0.879502 -0.4756416 0.01553422 0.7601438 -0.6496641 -0.01086485 0.6379628 -0.7687965 -0.04422158 0.6414789 -0.7665764 -0.02942031 -0.5416845 0.8402534 0.02349972 -0.6183608 0.783259 0.06430512 -0.9475203 0.3184952 -0.02768063 -0.9666869 0.2525441 -0.04168879 -0.9616148 -0.2724713 0.03250241 -0.8766291 -0.4811633 0.001831114 -0.6282041 -0.7663943 0.1341617 -0.5210236 -0.8527976 0.03564637 -0.445725 -0.8898937 -0.09704935 -1 0 0 -1 0 0 -0.767529 -0.6409962 0.004822015 -0.591484 -0.805451 -0.03735494 0.9213628 -0.3839876 0.06036615 0.9956889 -0.08310377 -0.04120087 -0.2144861 0.9766016 0.01565611 -0.3654335 0.930827 -0.004425227 0 0 1 2.60762e-7 0 1 0 0 1 0 0 1 0 0 1 7.19393e-7 0 1 -2.66396e-7 0 1 0 0 1 0 0 1 0 0 1 1.49445e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 6.06606e-7 0 1 1.99797e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1.26403e-6 0 1 1.78493e-7 0 1 0 0 1 0 0 1 6.20333e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -4.64409e-7 0 1 0 0 1 0 0 1 0 0 1 -1.45322e-7 0 1 -3.36562e-7 0 1 0 0 -1 -0.5533166 0.8329658 0.002960324 -0.7853574 0.615364 -0.06738698 -0.4049916 -0.9123755 0.05960422 -0.1070286 -0.9942336 -0.006683528 0.9677804 0.2506506 0.02398771 0.98447 0.173107 -0.02920722 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.200578 -0.04945659 0.03999996 0.226821 -0.05648988 0.03999996 0.226821 -0.05949068 0.03999996 -0.200578 -0.0464558 0.03999996 -0.200578 -0.04945659 0.03999996 0.226821 -0.05949068 0.03999996 0.226821 -0.05949068 0.037 -0.200578 -0.04945659 0.037 0.226821 -0.05648988 0.03999996 -0.200578 -0.0464558 0.03999996 -0.200578 -0.0464558 0.037 0.226821 -0.05648988 0.037 0.3609696 -0.04586786 0.005040526 0.455 -0.04898321 0.005151689 0.3609671 -0.04594278 0.005414068 0.455 -0.04901653 0.005414187 0.455 -0.048859 0.004872143 0.360977 -0.04565167 0.004700958 0.455 -0.0487225 0.004707098 0.455 -0.04899978 0.005237877 0.455 -0.04896157 0.005090415 0.455 -0.04876726 0.005038082 0.455 -0.04882019 0.004820585 0.455 -0.0487225 0.004707098 0.455 -0.04890096 0.004949688 0.455 -0.04853647 0.004678368 0.455 -0.04832285 0.004307687 0.455 -0.0490151 0.005386829 0.1631315 -0.002192258 0.06499999 0.1630985 -0.002856254 0.06499999 0.1630984 -0.002535939 0.04499995 0.1633712 -0.001423776 0.06499999 0.1631746 -0.002004861 0.04499995 0.1636857 -8.97926e-4 0.04499995 0.163809 -7.43353e-4 0.06499999 0.1633449 -0.00149393 0.04499995 0.1643139 -2.79727e-4 0.06499999 0.1647744 -1.84106e-7 0.06499999 0.1648173 2.04365e-5 0.04499995 0.1642504 -3.21684e-4 0.04499995 0.1653228 2.05135e-4 0.04499995 0.1658041 2.92395e-4 0.06499999 0.165277 1.92494e-4 0.06499999 0.166341 2.96743e-4 0.06499999 0.1659969 3.10031e-4 0.04499995 0.1673766 2.02347e-5 0.06499999 0.1668725 2.04915e-4 0.06499999 0.1673085 5.67244e-5 0.04499995 0.166659 2.5364e-4 0.04499995 0.1678804 -2.8014e-4 0.04499995 0.1678417 -2.52057e-4 0.06499999 0.1683406 -6.93659e-4 0.06499999 0.1683855 -7.45038e-4 0.04499995 0.168794 -0.001365303 0.06499999 0.1688235 -0.001426577 0.04499995 0.1690627 -0.002194643 0.04499995 0.1690955 -0.00253576 0.06499999 0.1690199 -0.002008318 0.06499999 0.1690754 -0.00308001 0.06499999 0.1690891 -0.003004908 0.04499995 0.1689575 -0.003607094 0.06499999 0.1689432 -0.003650605 0.04499995 0.168426 -0.00459069 0.04499995 0.1686925 -0.004215717 0.06499999 0.168728 -0.004142642 0.04499995 0.168196 -0.00484997 0.06499999 0.1680494 -0.004976987 0.04499995 0.1675483 -0.005330324 0.06499999 0.166992 -0.005567252 0.04499995 0.1676157 -0.005286335 0.04499995 0.1663411 -0.005688726 0.04499995 0.1661199 -0.005698621 0.06499999 0.1667974 -0.005620896 0.06499999 0.1658033 -0.005684256 0.04499995 0.165583 -0.005654394 0.06499999 0.1652735 -0.005583703 0.04499995 0.1649476 -0.005475223 0.06499999 0.164772 -0.005390524 0.04499995 0.1642478 -0.005068242 0.06499999 0.1641961 -0.005027055 0.04499995 0.1637627 -0.004585385 0.06499999 0.1637356 -0.00455147 0.04499995 0.1634668 -0.004144787 0.06499999 0.163521 -0.004234433 0.04499995 0.163323 -0.003845274 0.04499995 0.1632075 -0.003531217 0.06499999 0.1631311 -0.003196716 0.04499995 0.05215305 0.001506328 0.06499999 0.05213886 6.19085e-4 0.06499999 0.05213272 7.07125e-4 0.04499995 0.05230611 0.002351224 0.06499999 0.05233019 0.002435028 0.04499995 0.05215948 0.001567542 0.04499995 0.05264884 0.003232955 0.04499995 0.05262184 0.003177702 0.06499999 0.05296766 0.003784835 0.06499999 0.05300217 0.003835916 0.04499995 0.05416846 0.005042433 0.06499999 0.05349999 0.004459738 0.06499999 0.05356091 0.0045228 0.04499995 0.05481237 0.005444169 0.04499995 0.05475795 0.00541526 0.06499999 0.05421823 0.005078554 0.04499995 0.05554419 0.005760908 0.06499999 0.05562746 0.005787968 0.04499995 0.05710303 0.006013929 0.06499999 0.05640715 0.005961418 0.06499999 0.05646812 0.005969941 0.04499995 0.05735123 0.006014227 0.04499995 0.05779767 0.005969405 0.06499999 0.05847936 0.005828976 0.06499999 0.05887407 0.005700707 0.04499995 0.0591365 0.005594551 0.06499999 0.05820339 0.005897819 0.04499995 0.05975592 0.005270242 0.06499999 0.0596742 0.005325317 0.04499995 0.06037235 0.004822194 0.04499995 0.06032526 0.004861772 0.06499999 0.06094038 0.00426203 0.06499999 0.06099635 0.004195332 0.04499995 0.06144875 0.003538429 0.06499999 0.06175869 0.002912342 0.06499999 0.0617817 0.0028553 0.04499995 0.06147956 0.003485143 0.04499995 0.06199294 0.002190351 0.04499995 0.06197804 0.002250134 0.06499999 0.06212347 0.001404643 0.06499999 0.06212961 0.001316189 0.04499995 0.06210929 5.15492e-4 0.06499999 0.06199216 -1.71003e-4 0.06499999 0.06193202 -4.13311e-4 0.04499995 0.06210285 4.5498e-4 0.04499995 0.06161195 -0.00121349 0.04499995 0.06172305 -9.86688e-4 0.06499999 0.06129372 -0.001763582 0.06499999 0.0611552 -0.001969337 0.04499995 0.06009495 -0.003018975 0.06499999 0.06076276 -0.002436637 0.06499999 0.06058239 -0.002610266 0.04499995 0.05989354 -0.003165543 0.04499995 0.05950516 -0.003392219 0.06499999 0.05871874 -0.003738045 0.06499999 0.0591349 -0.003572463 0.04499995 0.0578556 -0.003938615 0.06499999 0.05829805 -0.003858506 0.04499995 0.05699896 -0.003994584 0.06499999 0.05726051 -0.003994643 0.04499995 0.0564031 -0.003938078 0.04499995 0.05611926 -0.003887951 0.06499999 0.0552951 -0.003647565 0.06499999 0.05571985 -0.003788053 0.04499995 0.05489403 -0.003468811 0.04499995 0.05450576 -0.003247082 0.06499999 0.05401229 -0.002906441 0.04499995 0.05393743 -0.002839207 0.06499999 0.05332243 -0.002239882 0.06499999 0.05339103 -0.00231105 0.04499995 0.05286031 -0.001603305 0.04499995 0.05281382 -0.001515984 0.06499999 0.05250316 -8.883e-4 0.06499999 0.05248039 -8.31838e-4 0.04499995 0.05228388 -2.25685e-4 0.06499999 0.05226904 -1.66018e-4 0.04499995 0.03414589 -0.04596477 0.04499995 0.177106 -0.04932105 0.04499995 0.177106 -0.04932105 0.037 0.03414589 -0.04596477 0.037 0.174816 -0.01425766 0.04499995 0.177928 -0.01433068 0.04499995 0.177106 -0.04932105 0.04499995 0.04512107 -0.008620321 0.04499995 0.06858998 -0.009090423 0.04499995 0.04474246 -0.008931696 0.04499995 0.03414589 -0.04596477 0.04499995 0.03932827 -0.01102834 0.04499995 0.03981506 -0.01097989 0.04499995 0.03496736 -0.01097434 0.04499995 0.03834515 -0.01105368 0.04499995 0.03883838 -0.01105296 0.04499995 0.07192236 -0.0112378 0.04499995 0.07239407 -0.01140844 0.04499995 0.04125809 -0.01069116 0.04499995 0.06933897 -0.00974977 0.04499995 0.06973749 -0.01005107 0.04499995 0.04394018 -0.009498417 0.04499995 0.04308664 -0.009983181 0.04499995 0.07057487 -0.01059055 0.04499995 0.04264318 -0.01019364 0.04499995 0.04548305 -0.008291542 0.04499995 0.06824165 -0.008733808 0.04499995 0.06895458 -0.009428203 0.04499995 0.06703627 -0.007145464 0.04499995 0.06730777 -0.00756514 0.04499995 0.04647016 -0.007200002 0.04499995 0.06759858 -0.007969081 0.04499995 0.0458312 -0.007942318 0.04499995 0.04616028 -0.007578432 0.04499995 0.05591994 -0.003839552 0.04499995 0.05626296 -0.003912627 0.04499995 0.04751759 -0.005541324 0.04499995 0.05695545 -0.003985404 0.04499995 0.04703527 -0.006395399 0.04499995 0.05660706 -0.003960967 0.04499995 0.04772716 -0.005096793 0.04499995 0.04791408 -0.004644334 0.04499995 0.05558526 -0.003743588 0.04499995 0.05433386 -0.00313276 0.04499995 0.05463117 -0.003318727 0.04499995 0.04822099 -0.003710865 0.04499995 0.05493807 -0.003481864 0.04499995 0.04807877 -0.004181802 0.04499995 0.05330097 -0.00220257 0.04499995 0.04843449 -0.002755939 0.04499995 0.04850566 -0.002272009 0.04499995 0.05271595 -0.001334786 0.04499995 0.04857718 -0.001291155 0.04499995 0.05256295 -0.001020908 0.04499995 0.04855328 -0.001783728 0.04499995 0.05308526 -0.001926064 0.04499995 0.05217999 3.14666e-4 0.04499995 0.04864293 0.001459777 0.04499995 0.05214369 6.60907e-4 0.04499995 0.06561839 0.001473844 0.04499995 0.06563121 0.001011312 0.04499995 0.06211876 0.001361548 0.04499995 0.04882955 0.002836823 0.04499995 0.05243307 0.002722084 0.04499995 0.05232524 0.002390503 0.04499995 0.06202208 0.002049982 0.04499995 0.06558108 0.001932263 0.04499995 0.06208246 0.001707792 0.04499995 0.05308657 0.003950834 0.04499995 0.04923439 0.004155874 0.04499995 0.04941594 0.004578113 0.04499995 0.06193774 0.002388179 0.04499995 0.0618298 0.002721071 0.04499995 0.06543177 0.002840816 0.04499995 0.05036395 0.006154656 0.04499995 0.05433547 0.005156695 0.04499995 0.05009466 0.005779325 0.04499995 0.06117689 0.003949344 0.04499995 0.06502646 0.00415951 0.04499995 0.0613721 0.003659844 0.04499995 0.04894059 0.003282964 0.04499995 0.04907608 0.003724992 0.04499995 0.05271655 0.00335884 0.04499995 0.06021058 0.004950463 0.04499995 0.06416529 0.00578314 0.04499995 0.06441318 0.005395293 0.04499995 0.0609619 0.004224658 0.04499995 0.06072878 0.00448352 0.04499995 0.06464087 0.004993081 0.04499995 0.05932408 0.005504667 0.04499995 0.0590049 0.005647003 0.04499995 0.0636081 0.006515622 0.04499995 0.05712878 0.009511172 0.04499995 0.05758965 0.009498775 0.04499995 0.05666995 0.009498775 0.04499995 0.05765467 0.005983769 0.04499995 0.06111055 0.008522152 0.04499995 0.06151169 0.008295476 0.04499995 0.05804926 0.009461581 0.04499995 0.05621069 0.009461164 0.04499995 0.05575364 0.009398818 0.04499995 0.05850398 0.009399592 0.04499995 0.05895668 0.009312808 0.04499995 0.05530279 0.009312331 0.04499995 0.05940437 0.009201705 0.04499995 0.05485588 0.00920099 0.04499995 0.05441486 0.009065449 0.04499995 0.059843 0.009066998 0.04499995 0.05730664 0.006008207 0.04499995 0.06069958 0.00872606 0.04499995 0.06027555 0.008908152 0.04499995 0.06190079 0.008047044 0.04499995 0.0580008 0.005935072 0.04499995 0.05834084 0.005862772 0.04499995 0.06227338 0.007779419 0.04499995 0.0629763 0.007182657 0.04499995 0.05867767 0.005766093 0.04499995 0.06263226 0.007490873 0.04499995 0.0633006 0.006858289 0.04499995 0.05963218 0.005340874 0.04499995 0.06389778 0.006155669 0.04499995 0.05992758 0.005156159 0.04499995 0.06047707 0.004726886 0.04499995 0.06484466 0.004582226 0.04499995 0.0651862 0.003725588 0.04499995 0.161882 -0.009664714 0.04499995 0.169983 -0.00996077 0.04499995 0.1618109 -0.0100131 0.04499995 0.171883 -0.01322066 0.04499995 0.159556 -0.01310485 0.04499995 0.159853 -0.01290845 0.04499995 0.170045 -0.01030749 0.04499995 0.161594 -0.01069289 0.04499995 0.170131 -0.01064848 0.04499995 0.17024 -0.01098167 0.04499995 0.06169945 0.003043651 0.04499995 0.06532078 0.003287255 0.04499995 0.06154608 0.003358423 0.04499995 0.1705279 -0.01162296 0.04499995 0.161094 -0.01163697 0.04499995 0.161282 -0.01133495 0.04499995 0.171121 -0.01249325 0.04499995 0.1606529 -0.01219797 0.04499995 0.170903 -0.01221776 0.04499995 0.04874318 0.002386569 0.04499995 0.174464 -0.01423674 0.04499995 0.157192 -0.01383095 0.04499995 0.174116 -0.01419168 0.04499995 0.06551915 0.002386569 0.04499995 0.04962116 0.004992246 0.04499995 0.0535354 0.004485428 0.04499995 0.05330175 0.004226088 0.04499995 0.05378586 0.004727303 0.04499995 0.04984718 0.005392134 0.04499995 0.05405408 0.004952192 0.04499995 0.05256408 0.003046214 0.04499995 0.05289179 0.003662109 0.04499995 0.04868137 0.001932263 0.04499995 0.05217999 0.001707792 0.04499995 0.05224025 -2.73543e-5 0.04499995 0.05232459 -3.65154e-4 0.04499995 0.05243277 -6.98732e-4 0.04499995 0.05353355 -0.002460777 0.04499995 0.05405229 -0.002928137 0.04499995 0.0483396 -0.003235518 0.04499995 0.05378466 -0.002703368 0.04499995 0.04728645 -0.005975425 0.04499995 0.06790959 -0.008358359 0.04499995 0.07384049 -0.01177495 0.04499995 0.07335346 -0.01167714 0.04499995 0.04434728 -0.009225666 0.04499995 0.04352027 -0.009750664 0.04499995 0.07014876 -0.01033097 0.04499995 0.07101517 -0.01082944 0.04499995 0.0714643 -0.01104515 0.04499995 0.04219108 -0.01038157 0.04499995 0.04172849 -0.01054769 0.04499995 0.04078358 -0.01081049 0.04499995 0.07287138 -0.01155495 0.04499995 0.04030209 -0.01090687 0.04499995 0.07433229 -0.01184839 0.04499995 0.07482886 -0.01189738 0.04499995 0.07533025 -0.011922 0.04499995 0.156834 -0.01383548 0.04499995 0.1579 -0.0137459 0.04499995 0.1582469 -0.01366585 0.04499995 0.173435 -0.01402896 0.04499995 0.1575469 -0.01380127 0.04499995 0.173773 -0.01412236 0.04499995 0.158922 -0.0134322 0.04499995 0.172468 -0.01360887 0.04499995 0.172781 -0.01377165 0.04499995 0.158589 -0.01356089 0.04499995 0.173102 -0.01391136 0.04499995 0.1601369 -0.01269066 0.04499995 0.171358 -0.0127539 0.04499995 0.171612 -0.01299577 0.04499995 0.172169 -0.01342505 0.04499995 0.159245 -0.01327979 0.04499995 0.160403 -0.01245439 0.04499995 0.170705 -0.01192736 0.04499995 0.160883 -0.01192617 0.04499995 0.16145 -0.01101905 0.04499995 0.170373 -0.01130837 0.04499995 0.161715 -0.0103569 0.04499995 0.169946 -0.009612023 0.04499995 0.161929 -0.009311735 0.04499995 0.1699336 -0.009238541 0.04499995 0.1619499 -0.008954226 0.04499995 0.1687999 -0.001395046 0.04499995 0.169827 -0.00125283 0.04499995 0.16993 -0.001551866 0.04499995 0.163097 -0.002695977 0.04499995 0.162097 -0.0026955 0.04499995 0.163109 -0.002426207 0.04499995 0.166232 3.00953e-4 0.04499995 0.166781 0.001245021 0.04499995 0.1670899 0.001178622 0.04499995 0.1673949 0.001087605 0.04499995 0.167689 9.73439e-4 0.04499995 0.1665 2.76681e-4 0.04499995 0.1664659 0.001286745 0.04499995 0.166765 2.28718e-4 0.04499995 0.167975 8.35428e-4 0.04499995 0.1682479 6.76295e-4 0.04499995 0.167025 1.56851e-4 0.04499995 0.168509 4.95057e-4 0.04499995 0.168753 2.9463e-4 0.04499995 0.167276 6.2542e-5 0.04499995 0.1659629 3.00953e-4 0.04499995 0.164901 0.001121103 0.04499995 0.165207 0.001203775 0.04499995 0.167519 -5.4655e-5 0.04499995 0.168982 7.48203e-5 0.04499995 0.16775 -1.9235e-4 0.04499995 0.167968 -3.5102e-4 0.04499995 0.169192 -1.62009e-4 0.04499995 0.16817 -5.27935e-4 0.04499995 0.169382 -4.14805e-4 0.04499995 0.168356 -7.22707e-4 0.04499995 0.169553 -6.82187e-4 0.04499995 0.168524 -9.33195e-4 0.04499995 0.169701 -9.61596e-4 0.04499995 0.168672 -0.00115776 0.04499995 0.168906 -0.001642167 0.04499995 0.170008 -0.001859724 0.04499995 0.169049 -0.002160489 0.04499995 0.168989 -0.001898705 0.04499995 0.170062 -0.00217086 0.04499995 0.169085 -0.002426207 0.04499995 0.162147 -0.002064168 0.04499995 0.163145 -0.002159953 0.04499995 0.16211 -0.002377688 0.04499995 0.163522 -0.001156687 0.04499995 0.162406 -0.00115323 0.04499995 0.16254 -8.66177e-4 0.04499995 0.163394 -0.001393795 0.04499995 0.1622959 -0.001449942 0.04499995 0.170091 -0.00248754 0.04499995 0.1632879 -0.001641333 0.04499995 0.162209 -0.001754939 0.04499995 0.169097 -0.002695977 0.04499995 0.163205 -0.001897156 0.04499995 0.165169 -0.005548954 0.04499995 0.165428 -0.005620479 0.04499995 0.163838 -7.21587e-4 0.04499995 0.16367 -9.3229e-4 0.04499995 0.162696 -5.90147e-4 0.04499995 0.164227 -3.50003e-4 0.04499995 0.1640239 -5.27432e-4 0.04499995 0.162873 -3.28075e-4 0.04499995 0.163071 -7.98112e-5 0.04499995 0.163287 1.5081e-4 0.04499995 0.164444 -1.92235e-4 0.04499995 0.164676 -5.38516e-5 0.04499995 0.163522 3.64961e-4 0.04499995 0.163771 5.58458e-4 0.04499995 0.164918 6.26602e-5 0.04499995 0.165171 1.57378e-4 0.04499995 0.164037 7.33008e-4 0.04499995 0.164314 8.84626e-4 0.04499995 0.16543 2.28854e-4 0.04499995 0.164604 0.001014769 0.04499995 0.165695 2.7692e-4 0.04499995 0.1655189 0.001261949 0.04499995 0.165834 0.001295208 0.04499995 0.166151 0.001303613 0.04499995 0.163109 -0.002965867 0.04499995 0.163145 -0.003231585 0.04499995 0.1649169 -0.005454063 0.04499995 0.1646749 -0.005337536 0.04499995 0.163205 -0.00349307 0.04499995 0.1632879 -0.003749966 0.04499995 0.163394 -0.00399667 0.04499995 0.163521 -0.004234433 0.04499995 0.163669 -0.004458427 0.04499995 0.164023 -0.004863619 0.04499995 0.163837 -0.004669547 0.04499995 0.164443 -0.005199074 0.04499995 0.1642259 -0.005041241 0.04499995 0.168672 -0.004234969 0.04499995 0.1656939 -0.005668699 0.04499995 0.165961 -0.005692839 0.04499995 0.166231 -0.005692958 0.04499995 0.166764 -0.005620896 0.04499995 0.166499 -0.005668818 0.04499995 0.167275 -0.005454838 0.04499995 0.167023 -0.005549311 0.04499995 0.167749 -0.005200088 0.04499995 0.167518 -0.005338013 0.04499995 0.168169 -0.004864871 0.04499995 0.167967 -0.005041778 0.04499995 0.168523 -0.004460036 0.04499995 0.168356 -0.004670143 0.04499995 0.168905 -0.003750324 0.04499995 0.168799 -0.003998398 0.04499995 0.169049 -0.003231763 0.04499995 0.168988 -0.003494977 0.04499995 0.169085 -0.002965867 0.04499995 0.06169807 -0.001023769 0.04499995 0.06556457 -0.001886963 0.04499995 0.06154555 -0.001336693 0.04499995 0.06213116 0.001011312 0.04499995 0.05065184 0.006512939 0.04499995 0.05463248 0.005342066 0.04499995 0.05494016 0.005505681 0.04499995 0.05095869 0.006854891 0.04499995 0.05525916 0.00564754 0.04499995 0.05558735 0.005766928 0.04499995 0.05128514 0.007181584 0.04499995 0.05162739 0.007488727 0.04499995 0.05592179 0.005862832 0.04499995 0.0562644 0.005935549 0.04499995 0.05198538 0.007776498 0.04499995 0.05236029 0.008045971 0.04499995 0.05660909 0.005984008 0.04499995 0.0527479 0.008293867 0.04499995 0.05695807 0.006008207 0.04499995 0.05314767 0.008519887 0.04499995 0.05356109 0.008725047 0.04499995 0.05398386 0.008907139 0.04499995 0.05224084 0.002052128 0.04499995 0.05214357 0.001361548 0.04499995 0.05213117 0.001011312 0.04499995 0.06020849 -0.002929329 0.04499995 0.0656771 -0.00341767 0.04499995 0.05992585 -0.003134548 0.04499995 0.0657643 -0.003910064 0.04499995 0.05963116 -0.003318727 0.04499995 0.06587588 -0.00439769 0.04499995 0.05932146 -0.003483176 0.04499995 0.05900347 -0.003624796 0.04499995 0.06601077 -0.004876971 0.04499995 0.05289059 -0.001637458 0.04499995 0.0661695 -0.005348503 0.04499995 0.05867505 -0.003744125 0.04499995 0.05833935 -0.003840386 0.04499995 0.0663532 -0.005815327 0.04499995 0.05799949 -0.003912627 0.04499995 0.06655848 -0.006269872 0.04499995 0.05765217 -0.003961265 0.04499995 0.06678545 -0.006712138 0.04499995 0.05730485 -0.003985583 0.04499995 0.05525708 -0.003623902 0.04499995 0.046763 -0.006803929 0.04499995 0.06561529 -0.002924263 0.04499995 0.06047618 -0.002704858 0.04499995 0.0607267 -0.002463042 0.04499995 0.06557786 -0.002426624 0.04499995 0.06096148 -0.00220257 0.04499995 0.0611754 -0.001928687 0.04499995 0.06137067 -0.001639187 0.04499995 0.06182968 -6.98732e-4 0.04499995 0.06193709 -3.68223e-4 0.04499995 0.06208235 3.14666e-4 0.04499995 0.06202155 -2.94007e-5 0.04499995 0.06211876 6.60907e-4 0.04499995 0.02481675 -0.01727098 0.0444594 0.02470511 -0.02202981 0.04511076 0.02480649 -0.01770997 0.04462206 0.02494609 -0.01176089 0.03792709 0.02494817 -0.0116747 0.03746688 0.02414858 -0.04573005 0.037 0.02494955 -0.01161187 0.037 0.02494037 -0.01200336 0.03882747 0.02494359 -0.01187038 0.03838056 0.02493256 -0.01233935 0.03970116 0.02493679 -0.0121597 0.03926765 0.02492254 -0.01276308 0.04053568 0.02492779 -0.01254105 0.04012507 0.02491068 -0.01327127 0.04132479 0.02491688 -0.01300668 0.04093587 0.02486455 -0.01523429 0.04331886 0.02488148 -0.014512 0.04272246 0.02454984 -0.02864027 0.04510897 0.02483665 -0.01642149 0.04406654 0.02484625 -0.01601248 0.04383736 0.02468657 -0.0228163 0.0451045 0.02485555 -0.01561725 0.04358869 0.02479588 -0.01815927 0.04476279 0.02471965 -0.02140527 0.04510664 0.02482676 -0.01684248 0.04427486 0.02475267 -0.02000039 0.0450837 0.02473068 -0.02093595 0.04511076 0.02474164 -0.02046686 0.04510837 0.02477449 -0.01906955 0.04496937 0.02478528 -0.01861107 0.04487788 0.02476358 -0.01953488 0.04503726 0.02487325 -0.01486456 0.04302918 0.02488934 -0.01417589 0.04239809 0.02489697 -0.01385486 0.04205417 0.02490407 -0.01355338 0.04169636 0.02437835 -0.03594475 0.04511463 0.02414858 -0.04573005 0.0451222 0.01807218 -0.04558736 0.04550355 0.02414858 -0.04573005 0.04512214 0.02414858 -0.04573005 0.037 0.005918443 -0.04530209 0.04619544 -1.58877e-4 -0.04515939 0.04650586 0.01199549 -0.04544478 0.04586136 -0.006236493 -0.0450167 0.04679268 -0.127851 -0.04216158 0.037 -0.01231437 -0.04487395 0.04705578 -0.0244711 -0.04458856 0.04751086 -0.01839256 -0.04473125 0.04729515 -0.03662908 -0.04430317 0.04787135 -0.03055 -0.04444587 0.04770296 -0.04878818 -0.04401767 0.04813706 -0.04270845 -0.04416048 0.04801607 -0.06094837 -0.04373228 0.04830807 -0.05486816 -0.04387497 0.04823446 -0.07310986 -0.04344666 0.04838448 -0.06702899 -0.04358947 0.0483582 -0.08527261 -0.04316115 0.04836606 -0.07919108 -0.04330396 0.04838716 -0.09743648 -0.04287558 0.04825305 -0.09135437 -0.0430184 0.04832148 -0.109601 -0.04258996 0.04804527 -0.103519 -0.04273277 0.04816108 -0.1217679 -0.04230439 0.0477429 -0.115684 -0.04244714 0.04790598 -0.127851 -0.04216158 0.04755616 -0.127851 -0.04216158 0.04755616 -0.127851 -0.04216158 0.037 -0.127333 -0.0200783 0.04623466 -0.12735 -0.02080929 0.0464763 -0.1275792 -0.03058254 0.04757517 -0.127299 -0.01864916 0.0456838 -0.1273159 -0.01935797 0.04597038 -0.127385 -0.02228558 0.04688787 -0.127402 -0.02303087 0.04705774 -0.12742 -0.02378535 0.04719644 -0.1275094 -0.02761018 0.04756492 -0.127367 -0.02154505 0.04669409 -0.1274909 -0.0268324 0.04754257 -0.1274729 -0.02606958 0.04748195 -0.127456 -0.02530747 0.04740405 -0.127438 -0.02454608 0.04730898 -0.127283 -0.0179488 0.04537409 -0.127267 -0.01725667 0.04504126 -0.127251 -0.01657289 0.04468536 -0.127219 -0.01525145 0.04391157 -0.1272349 -0.0159049 0.04430896 -0.1271899 -0.01398098 0.04305148 -0.127204 -0.01461017 0.04349237 -0.127161 -0.012766 0.04210954 -0.127175 -0.01336389 0.04258865 -0.127134 -0.01161879 0.04109567 -0.127148 -0.01218479 0.04161238 -0.127109 -0.01053249 0.04000425 -0.127121 -0.01106798 0.04055964 -0.127085 -0.009525299 0.03885239 -0.127097 -0.01001948 0.03943639 -0.127063 -0.008591115 0.03763419 -0.127074 -0.009049177 0.03825169 -0.127053 -0.008151113 0.037 -0.137849 -0.04192686 0.037 -0.137253 -0.01656526 0.0436517 -0.137237 -0.01588708 0.0432595 -0.137097 -0.009922027 0.03822726 -0.137085 -0.009418666 0.03762269 -0.1370739 -0.008932709 0.037 -0.137122 -0.01098054 0.03938198 -0.137109 -0.01044255 0.03881365 -0.137148 -0.01210826 0.04046428 -0.137135 -0.01153576 0.03993219 -0.137177 -0.01330518 0.04147398 -0.137162 -0.01269805 0.04097819 -0.137206 -0.01457124 0.04241114 -0.1371909 -0.01392954 0.04195165 -0.137222 -0.01522296 0.0428465 -0.137269 -0.01725757 0.04402309 -0.137572 -0.03016614 0.04676306 -0.137337 -0.02013087 0.04528105 -0.13732 -0.01939898 0.0450018 -0.137632 -0.03269451 0.0467692 -0.1375994 -0.0313369 0.04677379 -0.1373029 -0.01867765 0.04469984 -0.137554 -0.02937859 0.04677599 -0.137426 -0.0239104 0.04632318 -0.137408 -0.02314376 0.04616379 -0.13739 -0.02238374 0.04598039 -0.137372 -0.02162635 0.04577136 -0.137517 -0.02780646 0.04676377 -0.137535 -0.02859115 0.04678165 -0.13748 -0.02624517 0.04665738 -0.137462 -0.02546346 0.04656958 -0.137499 -0.02702444 0.04672235 -0.137444 -0.02468359 0.04645836 -0.137354 -0.02087336 0.04553759 -0.137286 -0.017964 0.04437375 -0.1376643 -0.03408282 0.0467506 -0.1378487 -0.04192686 0.04673331 -0.07699996 -0.01322466 0.03849995 -0.05899995 -0.01322466 0.03849995 -0.05899995 -0.01372468 0.03849995 -0.07699996 -0.01372468 0.03849995 -0.1731539 -0.03088897 0.04199999 -0.157323 -0.01871317 0.04199999 -0.156547 -0.01845979 0.04199999 -0.1583933 -0.01907765 0.04199999 -0.1593453 -0.01941585 0.04199999 -0.1601924 -0.01972961 0.04199999 -0.1608352 -0.01997601 0.04199999 -0.1615641 -0.02026426 0.04199999 -0.1623056 -0.0205695 0.04199999 -0.1631053 -0.02091175 0.04199999 -0.1638817 -0.02126014 0.04199999 -0.1644926 -0.02154558 0.04199999 -0.1651155 -0.02184838 0.04199999 -0.1656905 -0.02213996 0.04199999 -0.1662597 -0.02244049 0.04199999 -0.1667219 -0.022695 0.04199999 -0.1671419 -0.02293467 0.04199999 -0.167745 -0.0232945 0.04199999 -0.1683115 -0.02365231 0.04199999 -0.1691446 -0.02422225 0.04199999 -0.168716 -0.02392226 0.04199999 -0.1696441 -0.02459335 0.04199999 -0.170056 -0.02492195 0.04199999 -0.170563 -0.02535825 0.04199999 -0.170312 -0.02513736 0.04199999 -0.171048 -0.025819 0.04199999 -0.170808 -0.02558547 0.04199999 -0.1731637 -0.03050369 0.04199999 -0.171505 -0.02630716 0.04199999 -0.171281 -0.02605926 0.04199999 -0.171929 -0.02682489 0.04199999 -0.172127 -0.0270949 0.04199999 -0.171723 -0.02656227 0.04199999 -0.172482 -0.0276615 0.04199999 -0.173151 -0.02988386 0.04199999 -0.172311 -0.02737379 0.04199999 -0.173071 -0.02922016 0.04199999 -0.172995 -0.02889388 0.04199999 -0.1726379 -0.02795755 0.04199999 -0.172776 -0.02826207 0.04199999 -0.172897 -0.02857476 0.04199999 -0.173124 -0.02955037 0.04199999 -0.1496199 -0.007950723 0.03373789 -0.149294 -0.008387029 0.03445827 -0.1470659 -0.01136398 0.03299999 -0.1499339 -0.007531523 0.03299999 -0.148954 -0.008840441 0.03516125 -0.148602 -0.00931096 0.03584688 -0.1478599 -0.01030325 0.0371657 -0.148237 -0.009798526 0.03651499 -0.147469 -0.01082509 0.03779888 -0.1470659 -0.01136398 0.03841465 -0.1470659 -0.01136398 0.03299999 -0.14089 -0.006741702 0.03299999 -0.1439099 -0.006977021 0.03299999 -0.146925 -0.007240295 0.03299999 -0.1499339 -0.007531523 0.03299999 -0.141604 -0.0418387 0.0463435 -0.137849 -0.04192686 0.04673337 -0.137849 -0.04192686 0.037 -0.167787 -0.041224 0.04289805 -0.171513 -0.0411365 0.04230356 -0.145355 -0.04175055 0.045928 -0.152847 -0.04157465 0.04502028 -0.149103 -0.04166257 0.04548686 -0.160324 -0.04139918 0.0440104 -0.156588 -0.04148685 0.04452806 -0.164058 -0.0413115 0.04346698 -0.175235 -0.04104906 0.04168355 -0.178954 -0.0409618 0.04103797 -0.18638 -0.04078745 0.037 -0.182669 -0.0408746 0.04036676 -0.18638 -0.04078745 0.03966999 -0.1382009 -0.0569269 0.037 -0.169503 -0.05619198 0.04260134 -0.1734 -0.05610048 0.04198336 -0.1928319 -0.05564427 0.03854119 -0.196707 -0.05555325 0.03778225 -0.200579 -0.05546236 0.037 -0.18507 -0.05582648 0.03998845 -0.188952 -0.05573529 0.03927659 -0.177294 -0.05600905 0.0413419 -0.181183 -0.05591768 0.04067689 -0.165603 -0.05628347 0.0431959 -0.157791 -0.05646687 0.0443145 -0.1616989 -0.0563752 0.04376697 -0.149966 -0.05665057 0.04533928 -0.15388 -0.05655866 0.04483854 -0.142126 -0.05683469 0.04627007 -0.146048 -0.05674254 0.04581636 -0.1382009 -0.0569269 0.04670029 -0.1382004 -0.0569269 0.04670023 -0.1382009 -0.0569269 0.037 -0.138729 -0.0794205 0.04493588 -0.1384763 -0.06867396 0.04667353 -0.1385223 -0.07064491 0.04662716 -0.138659 -0.07644265 0.04589468 -0.1386409 -0.0756762 0.04607307 -0.138694 -0.07794785 0.04546386 -0.138495 -0.06946128 0.04666137 -0.1386229 -0.07490748 0.046229 -0.1386049 -0.07413649 0.04636216 -0.138568 -0.07258605 0.046543 -0.13855 -0.07180577 0.04658049 -0.1385869 -0.0733633 0.04647284 -0.138677 -0.07720148 0.04569196 -0.138712 -0.0786876 0.04521185 -0.138746 -0.08014678 0.04463607 -0.138763 -0.08086305 0.04431337 -0.138779 -0.08156377 0.04396957 -0.1388109 -0.08293437 0.04321336 -0.138795 -0.08225417 0.04360288 -0.138842 -0.08426165 0.04236739 -0.138827 -0.08360427 0.0428012 -0.138872 -0.08552277 0.04144507 -0.138857 -0.08489918 0.04191654 -0.1389 -0.08672827 0.0404402 -0.138886 -0.08613246 0.04095298 -0.138927 -0.08786785 0.03936195 -0.138914 -0.08730936 0.03990745 -0.138952 -0.0889343 0.03821688 -0.13894 -0.0884096 0.03879839 -0.138976 -0.08993309 0.037 -0.1389639 -0.08944219 0.03761738 -0.128203 -0.05716156 0.037 -0.128817 -0.08327579 0.04423075 -0.128832 -0.08392995 0.04383379 -0.128977 -0.0901153 0.03823757 -0.128988 -0.09057539 0.03762698 -0.128998 -0.0910179 0.037 -0.1289539 -0.08914238 0.03940927 -0.128966 -0.08963769 0.03883165 -0.12893 -0.0880993 0.0405153 -0.128942 -0.08862966 0.03997045 -0.128904 -0.08698588 0.0415554 -0.128917 -0.08755135 0.04104357 -0.128876 -0.08580356 0.04252839 -0.12889 -0.08640277 0.04205077 -0.128847 -0.08456939 0.04341775 -0.128862 -0.08519387 0.04298257 -0.128801 -0.08260905 0.0446071 -0.128736 -0.07984256 0.04588598 -0.128472 -0.06859755 0.04752308 -0.128719 -0.07912516 0.0461511 -0.128455 -0.06787949 0.04751497 -0.128769 -0.08124935 0.04528909 -0.128785 -0.0819351 0.04495865 -0.128508 -0.07012659 0.04755485 -0.128526 -0.07088905 0.04754465 -0.12849 -0.06936275 0.04754769 -0.128544 -0.07165026 0.04751718 -0.128668 -0.076936 0.04680466 -0.128597 -0.07393556 0.04734909 -0.128561 -0.07241308 0.0474779 -0.128579 -0.07317656 0.04742538 -0.12865 -0.07618957 0.0469771 -0.128633 -0.07543998 0.04712557 -0.128615 -0.07468998 0.04724919 -0.128702 -0.07840377 0.04639154 -0.1286849 -0.07767409 0.04660946 -0.128753 -0.08055186 0.04559814 -0.1283761 -0.0645048 0.04751878 -0.128203 -0.05716156 0.04753112 -0.123452 -0.05727308 0.04768246 -0.128203 -0.05716156 0.04753118 -0.128203 -0.05716156 0.037 -0.118701 -0.05738466 0.04781925 -0.11395 -0.05749619 0.0479415 -0.109199 -0.05760765 0.04804909 -0.104448 -0.05771929 0.04814207 -0.09969729 -0.05783075 0.04822045 -0.0949465 -0.05794227 0.04828429 -0.09019589 -0.05805385 0.04833346 -0.08544528 -0.05816537 0.04836809 -0.08069467 -0.05827689 0.04838806 -0.0759443 -0.05838847 0.04839348 -0.07119399 -0.05849999 0.04838418 -0.06644368 -0.05861145 0.04836034 -0.06169348 -0.05872297 0.04832196 -0.05694335 -0.05883449 0.04826897 -0.05219328 -0.05894607 0.04820138 -0.04744338 -0.05905759 0.04811918 -0.04269349 -0.05916905 0.04802227 -0.03794366 -0.05928057 0.04791086 -0.033194 -0.05939209 0.04778486 -0.02844429 -0.05950355 0.04764425 -0.02369475 -0.05961507 0.04748898 -0.01894527 -0.05972659 0.04731917 -0.01419585 -0.05983805 0.04713475 -0.009446561 -0.05994957 0.04693579 0.02379649 -0.06073009 0.037 -0.004697322 -0.06006109 0.04672205 0.004800915 -0.06028407 0.04625105 5.18404e-5 -0.06017255 0.04649388 0.01429885 -0.06050705 0.04572159 0.009549915 -0.06039559 0.04599356 0.01904767 -0.06061857 0.04543495 0.02379649 -0.06073009 0.04513365 0.02379643 -0.06073009 0.0451337 0.02379649 -0.06073009 0.037 0.02364403 -0.06722187 0.04513871 0.02343815 -0.07599085 0.04514551 0.02292406 -0.09788757 0.04134094 0.0229308 -0.0976032 0.04171878 0.02293789 -0.0973019 0.04207926 0.02294528 -0.09698367 0.04242235 0.02295327 -0.0966463 0.04275029 0.02296149 -0.0962938 0.04305946 0.02297019 -0.09592676 0.04334938 0.02297919 -0.09554177 0.04362237 0.02298855 -0.09514325 0.04387557 0.02299809 -0.09473478 0.04410648 0.02300798 -0.09431529 0.04431545 0.02311849 -0.089607 0.04515612 0.02301806 -0.0938847 0.04450255 0.02302837 -0.09344691 0.04466629 0.02310258 -0.09028625 0.04514819 0.0230388 -0.0930019 0.04480659 0.02304929 -0.0925554 0.04492247 0.02306008 -0.09209686 0.04501575 0.02307105 -0.09162628 0.04508668 0.02308279 -0.09112977 0.04511904 0.02291226 -0.09839069 0.04055309 0.02291798 -0.09814947 0.04095315 0.02290236 -0.09881138 0.03971546 0.02290707 -0.09861177 0.04013967 0.02289456 -0.09914529 0.03883665 0.02289825 -0.098989 0.03928154 0.02288889 -0.0993871 0.03792828 0.02289146 -0.0992791 0.0383833 0.0228855 -0.09953218 0.037 0.02288687 -0.0994715 0.03746718 0.03313225 -0.08913952 0.04484099 0.03311675 -0.08979988 0.04483968 0.0330199 -0.09392637 0.04428625 0.03288799 -0.09954565 0.03791868 0.03288567 -0.09964019 0.03746289 0.03379368 -0.06096476 0.037 0.03288406 -0.09971147 0.037 0.03289395 -0.09928667 0.03880888 0.03289067 -0.09942775 0.03836739 0.0329023 -0.09893459 0.03967034 0.03289788 -0.09912228 0.03924316 0.03291255 -0.09849619 0.0404911 0.03290718 -0.09872525 0.04008746 0.03294646 -0.09705156 0.04231154 0.03293877 -0.09737861 0.04197698 0.03291845 -0.09824579 0.04088377 0.03298079 -0.0955913 0.04346156 0.03297168 -0.09597849 0.0432024 0.03314995 -0.08838576 0.04483622 0.03296285 -0.09635257 0.04292309 0.03299975 -0.09478056 0.04391729 0.03299015 -0.09519267 0.04369938 0.03305137 -0.09258306 0.04466617 0.03304076 -0.09303516 0.04456377 0.03300976 -0.09435695 0.04411399 0.03308397 -0.09119665 0.04483586 0.03310579 -0.0902664 0.04484939 0.03309488 -0.09073245 0.04485285 0.03306216 -0.09212499 0.04474484 0.03307306 -0.09166085 0.04479986 0.03303015 -0.09348577 0.04443615 0.03295445 -0.09671008 0.04262638 0.0334466 -0.07574838 0.0448271 0.03293156 -0.09768617 0.04162806 0.03292477 -0.09797459 0.04126495 0.03379368 -0.06096476 0.04481643 0.04098755 -0.06113362 0.04463875 0.03379368 -0.06096476 0.04481649 0.03379368 -0.06096476 0.037 0.1171076 -0.06292068 0.04220527 0.05043315 -0.06135547 0.04439115 0.06001222 -0.0615803 0.04412442 0.06963902 -0.06180632 0.04384028 0.08384841 -0.06213992 0.0433917 0.07669568 -0.06197196 0.04362136 0.0909937 -0.06230765 0.04315245 0.09824466 -0.06247794 0.04290163 0.1076119 -0.06269776 0.04256349 0.124351 -0.0630908 0.04192107 0.1314469 -0.06325739 0.04163473 0.1409791 -0.06348115 0.04123574 0.148173 -0.06365007 0.04092389 0.1553257 -0.06381797 0.04060566 0.1767539 -0.0643211 0.037 0.1695881 -0.06415283 0.03994405 0.162464 -0.06398558 0.04027849 0.1767539 -0.0643211 0.03959774 -0.200578 -0.0464558 0.03999996 -0.200578 -0.04945659 0.03999996 -0.200578 -0.04945659 0.037 -0.200578 -0.0464558 0.037 -0.199725 -0.102371 0.009499967 -0.1728039 -0.113968 0.009499967 -0.199883 -0.102465 0.009499967 -0.202226 -0.09699088 0.009499967 -0.199116 -0.0996977 0.009499967 -0.2026799 -0.09788185 0.009499967 -0.200046 -0.1025519 0.009499967 -0.172968 -0.114069 0.009499967 -0.200294 -0.1026722 0.009499967 -0.20055 -0.10278 0.009499967 -0.173117 -0.114189 0.009499967 -0.173251 -0.114327 0.009499967 -0.17263 -0.113888 0.009499967 -0.204737 -0.10435 0.009499967 -0.204058 -0.10403 0.009499967 -0.206055 -0.10505 0.009499967 -0.205403 -0.10469 0.009499967 -0.206694 -0.10543 0.009499967 -0.173368 -0.114479 0.009499967 -0.217117 -0.120263 0.009499967 -0.172086 -0.120351 0.009499967 -0.171961 -0.121 0.009499967 -0.208539 -0.106698 0.009499967 -0.1734679 -0.114643 0.009499967 -0.172763 -0.117812 0.009499967 -0.216552 -0.118101 0.009499967 -0.216318 -0.117397 0.009499967 -0.216763 -0.118814 0.009499967 -0.172388 -0.1190699 0.009499967 -0.172228 -0.119708 0.009499967 -0.1734589 -0.115967 0.009499967 -0.215479 -0.11533 0.009499967 -0.173727 -0.115363 0.009499967 -0.172977 -0.117192 0.009499967 -0.2160609 -0.1166999 0.009499967 -0.173209 -0.116576 0.009499967 -0.2132149 -0.111477 0.009499967 -0.213644 -0.112089 0.009499967 -0.214806 -0.113993 0.009499967 -0.2144399 -0.113347 0.009499967 -0.201983 -0.103214 0.009499967 -0.2012709 -0.102986 0.009499967 -0.212299 -0.110299 0.009499967 -0.173681 -0.115177 0.009499967 -0.2026849 -0.103464 0.009499967 -0.2033759 -0.103736 0.009499967 -0.209694 -0.107636 0.009499967 -0.209125 -0.107158 0.009499967 -0.207319 -0.10583 0.009499967 -0.207937 -0.106255 0.009499967 -0.211311 -0.109186 0.009499967 -0.173623 -0.114994 0.009499967 -0.211814 -0.109735 0.009499967 -0.210247 -0.108132 0.009499967 -0.173553 -0.1148149 0.009499967 -0.210788 -0.108652 0.009499967 -0.212764 -0.110877 0.009499967 -0.214053 -0.112712 0.009499967 -0.2151539 -0.1146579 0.009499967 -0.215781 -0.116011 0.009499967 -0.172567 -0.118439 0.009499967 -0.216951 -0.119535 0.009499967 -0.21726 -0.121 0.009499967 -0.1988469 -0.1014479 0.009499967 -0.172069 -0.113762 0.009499967 -0.17226 -0.113786 0.009499967 -0.199571 -0.102269 0.009499967 -0.199423 -0.102158 0.009499967 -0.172448 -0.113827 0.009499967 -0.199283 -0.102038 0.009499967 -0.199153 -0.101907 0.009499967 -0.199034 -0.101765 0.009499967 -0.1989319 -0.101613 0.009499967 -0.1987839 -0.101275 0.009499967 -0.1987439 -0.101095 0.009499967 -0.198729 -0.100911 0.009499967 -0.171878 -0.113752 0.009499967 -0.1987349 -0.100727 0.009499967 -0.171685 -0.113755 0.009499967 -0.198808 -0.1003659 0.009499967 -0.198763 -0.100545 0.009499967 -0.171494 -0.11377 0.009499967 -0.198868 -0.100192 0.009499967 -0.199023 -0.0998575 0.009499967 -0.1989409 -0.100022 0.009499967 -0.1674759 -0.114695 0.009499967 -0.16793 -0.115586 0.009499967 -0.240213 -0.119763 0.02002996 -0.240132 -0.12006 0.01964175 -0.23982 -0.12023 0.01986616 -0.2401173 -0.1195108 0.02045804 -0.239942 -0.119911 0.02022606 -0.239651 -0.120001 0.02043056 -0.239641 -0.1196345 0.02081167 -0.23935 -0.12003 0.02063745 -0.2387959 -0.120328 0.02056986 -0.239047 -0.119996 0.020841 -0.2391721 -0.1190698 0.02140253 -0.2395497 -0.1191956 0.02115577 -0.2391443 -0.1195775 0.02114427 -0.2386757 -0.1193221 0.02144217 -0.2388654 -0.1188187 0.02159339 -0.2383127 -0.118923 0.0216549 -0.238672 -0.118544 0.02170068 -0.2379495 -0.1185073 0.02176243 -0.2385327 -0.1182041 0.02176815 -0.2391169 -0.1184862 0.02159351 -0.237947 -0.118216 0.02179139 -0.2382167 -0.118051 0.02180308 -0.237947 -0.11792 0.02179795 -0.239443 -0.120679 0.01906979 -0.2396125 -0.1206055 0.01880276 -0.2404119 -0.1198289 0.01943325 -0.2403084 -0.1200638 0.01880282 -0.239995 -0.120302 0.0192306 -0.2403332 -0.1190743 0.02052015 -0.2405205 -0.1191637 0.02018028 -0.240459 -0.11956 0.01984775 -0.2406944 -0.119247 0.01971369 -0.240654 -0.119541 0.01924669 -0.239942 -0.120382 0.01880276 -0.2407736 -0.1192854 0.01935476 -0.2406062 -0.1196838 0.01880288 -0.2408244 -0.1193093 0.018803 -0.239055 -0.120799 0.01934295 -0.2388006 -0.1209276 0.01880264 -0.239653 -0.120488 0.01947718 -0.2399459 -0.1191661 0.02088016 -0.2400752 -0.1189492 0.02088093 -0.239213 -0.1207939 0.01880276 -0.239287 -0.1206009 0.01973438 -0.2380698 -0.1208828 0.01964914 -0.238247 -0.120793 0.01989138 -0.238381 -0.120959 0.01922219 -0.238093 -0.1209681 0.01924544 -0.2381194 -0.1210067 0.01880258 -0.239488 -0.120333 0.02010017 -0.2389079 -0.1206369 0.01999455 -0.239143 -0.120366 0.02033698 -0.238652 -0.120837 0.01961946 -0.2380366 -0.1206334 0.02024507 -0.2385269 -0.120596 0.02025049 -0.23875 -0.119902 0.02103519 -0.2380177 -0.1204417 0.02055639 -0.238469 -0.119749 0.02121448 -0.2379952 -0.1200847 0.02096557 -0.237978 -0.1197113 0.02126443 -0.2395588 -0.1186999 0.02134519 -0.238457 -0.12022 0.02079206 -0.2379592 -0.1191329 0.02158159 -0.238212 -0.119543 0.02137386 0.48 -0.06471025 0.002999961 0.455 -0.074225 0.002999961 0.455 -0.06471025 0.002999961 0.48 -0.074225 0.002999961 0.415 -0.129584 0.000999987 0.415 -0.146919 0.000999987 0.39 -0.144032 0.000999987 0.39 -0.127696 0.000999987 0.09331017 -0.08841687 0.04039996 0.08690077 -0.09724777 0.04039996 0.09036058 -0.09707748 0.04039996 0.08343786 -0.09739476 0.04039996 0.09381729 -0.09688377 0.04039996 0.09727096 -0.09666687 0.04039996 0.100722 -0.0964266 0.04039996 0.104169 -0.09616285 0.04039996 0.107613 -0.09587597 0.04039996 0.111055 -0.09556567 0.04039996 0.114493 -0.09523206 0.04039996 0.117928 -0.09487509 0.04039996 0.12136 -0.09449487 0.04039996 0.1247889 -0.09409129 0.04039996 0.128215 -0.0936644 0.04039996 0.131638 -0.09321409 0.04039996 0.135058 -0.09274047 0.04039996 0.138474 -0.09224361 0.04039996 0.141888 -0.09172338 0.04039996 0.145298 -0.09117978 0.04039996 0.148706 -0.09061288 0.04039996 0.15211 -0.09002268 0.04039996 0.08337146 -0.0974552 0.008960962 0.08304905 -0.09774839 0.008731901 0.08273547 -0.0980336 0.008481264 0.08168387 -0.09898978 0.03830736 0.08041906 -0.10014 0.03394454 0.08150219 -0.099155 0.03799575 0.08077627 -0.0998153 0.03627306 0.08067417 -0.09990805 0.03590047 0.08102649 -0.09958767 0.03699266 0.08117288 -0.09945458 0.03733766 0.08046799 -0.100096 0.0347408 0.08051908 -0.100049 0.03513199 0.08058875 -0.09998577 0.03552025 0.08043467 -0.100126 0.03434544 0.08089476 -0.09970748 0.03663796 0.08133226 -0.09930956 0.03767246 0.0818755 -0.09881556 0.03860777 0.08207559 -0.09863358 0.03889697 0.0822857 -0.09844255 0.03917509 0.08250308 -0.09824478 0.03944206 0.08295756 -0.0978316 0.03994309 0.08272707 -0.09804117 0.03969806 0.08319449 -0.09761607 0.04017698 0.08438509 -0.09653335 0.009516417 0.08343786 -0.09739476 0.04039996 0.08243018 -0.09831118 0.008208632 0.08213639 -0.09857839 0.007917642 0.08107519 -0.09954351 0.006570518 0.081321 -0.09931987 0.006932437 0.08084285 -0.09975469 0.006192445 0.08062428 -0.09995347 0.00579822 0.0804193 -0.10014 0.005387842 0.0815804 -0.09908396 0.007278203 0.08185338 -0.0988357 0.007607817 0.08370327 -0.09715336 0.00916922 0.08404117 -0.09684616 0.009354412 0.08509057 -0.09589177 0.009772062 0.08473598 -0.09621429 0.009655952 0.08581018 -0.09523737 0.009933769 0.08544826 -0.09556657 0.009864568 0.08617377 -0.0949068 0.009978353 0.08653759 -0.094576 0.009997665 0.08726787 -0.09391176 0.009963214 0.08690309 -0.09424346 0.00999242 0.08799099 -0.0932542 0.009834229 0.08762997 -0.09358251 0.009910643 0.08834898 -0.0929287 0.009733796 0.09331017 -0.08841687 0.04039996 0.08904969 -0.09229147 0.009460449 0.08870118 -0.09260839 0.009609162 0.08972758 -0.09167498 0.009095072 0.08939278 -0.09197938 0.009288549 0.09037679 -0.09108448 0.008640766 0.090056 -0.0913763 0.008878886 0.09098768 -0.09052896 0.008103132 0.09068667 -0.09080278 0.008382558 0.0915572 -0.09001106 0.007486104 0.09127897 -0.09026408 0.007803201 0.09207975 -0.08953577 0.006795048 0.09182429 -0.08976817 0.007149875 0.09254789 -0.08911019 0.006040632 0.09232038 -0.08931708 0.006426155 0.0929597 -0.08873569 0.005226016 0.09276205 -0.0889154 0.005638837 0.09331017 -0.08841687 0.004358887 0.09314239 -0.08856958 0.004799365 0.0923165 -0.09202373 0.00547403 0.0916714 -0.0921877 0.006068468 0.09238058 -0.09154266 0.005083322 0.08330821 -0.1002155 0.004884779 0.08301126 -0.100486 0.00431025 0.08285236 -0.100327 0.004317104 0.09190529 -0.08969455 0.007041752 0.09135776 -0.09022569 0.007326006 0.09165418 -0.0899229 0.007368505 0.09200465 -0.09071826 0.00530976 0.0926792 -0.09046667 0.004044234 0.0920909 -0.09100168 0.005205869 0.09391599 -0.09056937 0 0.0938946 -0.09058821 6.9302e-4 0.09375417 -0.09037631 -2.19974e-7 0.09331667 -0.08952516 0.001430511 0.09337705 -0.08983188 0.001402497 0.09304636 -0.08977097 0.002819061 0.09302788 -0.0894652 0.002887666 0.09330469 -0.08921349 0.00146532 0.08996617 -0.09416139 0.007552981 0.08993506 -0.09376657 0.007480859 0.09295499 -0.09102028 0.003949046 0.09293282 -0.0914632 0.004420757 0.09087038 -0.09333908 0.007003426 0.09084808 -0.09293627 0.006875514 0.09158033 -0.0926932 0.006371498 0.09340494 -0.0894795 0 0.09380382 -0.09067165 0.001571714 0.09363657 -0.09040045 0.001369535 0.09341347 -0.08894175 0 0.09334158 -0.08890438 0.00150603 0.09355795 -0.08842211 2.15825e-7 0.09195327 -0.09235417 0.005950272 0.09357768 -0.09087789 0.002696931 0.09337776 -0.09063577 0.002698838 0.09354704 -0.08999282 0 0.09259206 -0.08958595 0.004342734 0.09265416 -0.08930796 0.004474461 0.09305709 -0.08916318 0.002967953 0.0927602 -0.08904927 0.004617154 0.09340453 -0.08842015 0.002792358 0.09313321 -0.08887225 0.003057956 0.09348469 -0.09012609 0.001381993 0.09322357 -0.09036356 0.002723515 0.09263277 -0.09173625 0.004973948 0.09324949 -0.09117567 0.003695309 0.09260475 -0.09017258 0.004124939 0.09257549 -0.08987659 0.004225254 0.09278941 -0.08889061 0.005584239 0.09252458 -0.08916652 0.005602657 0.09258699 -0.08907461 0.005970299 0.09335708 -0.08841818 0.003493726 0.09349691 -0.088422 0.001609921 0.09297657 -0.08872026 0.005188167 0.09315025 -0.08856236 0.004779756 0.09331017 -0.08841687 0.004358887 0.09208846 -0.0896601 0.005943357 0.09311217 -0.09007287 0.002763926 0.0935412 -0.08842349 8.799e-4 0.09196037 -0.09016048 0.005590081 0.09200328 -0.08989989 0.005759656 0.08917415 -0.09488165 0.007842481 0.08895897 -0.09465426 0.007866621 0.0913645 -0.09166216 0.006214737 0.09126389 -0.09139198 0.006338775 0.08923238 -0.09241968 0.008476138 0.09026688 -0.09147888 0.007790327 0.0902751 -0.0916931 0.007560968 0.0919609 -0.09043556 0.005438864 0.08926171 -0.09213179 0.009031057 0.08961766 -0.09177488 0.009166061 0.08993315 -0.091488 0.008967816 0.08836781 -0.09561496 0.007992267 0.0879485 -0.09557318 0.008021593 0.09052145 -0.09242886 0.007041215 0.09040397 -0.09217399 0.007181763 0.09118038 -0.09086978 0.006673455 0.08752167 -0.09638416 0.007977247 0.08693325 -0.09649646 0.007941246 0.09120196 -0.09112566 0.006492912 0.08922928 -0.0922603 0.008746504 0.08945029 -0.0930413 0.007814049 0.08958637 -0.09327918 0.007661163 0.08594316 -0.09739691 0.007627844 0.08639585 -0.09740799 0.007709681 0.09032118 -0.09192669 0.007356464 0.0884307 -0.09396851 0.008217036 0.0885868 -0.09418827 0.008056223 0.08725941 -0.09391945 0.009964048 0.08808338 -0.09320336 0.009496808 0.08686345 -0.09431278 0.009683907 0.08708649 -0.09459286 0.008821368 0.08583128 -0.09551268 0.008997857 0.08698147 -0.09446668 0.009088933 0.08560448 -0.0981276 0.007320284 0.08500707 -0.09824818 0.007090628 0.08516806 -0.09852468 0.007026731 0.0847392 -0.0989145 0.006682157 0.08737516 -0.09492826 0.008378922 0.08755195 -0.09512931 0.00821495 0.08829987 -0.09376478 0.008416891 0.08934426 -0.0928151 0.008004128 0.08083128 -0.09987378 0.005078256 0.08159399 -0.09920376 0.006329834 0.08183306 -0.09914857 0.006134152 0.08453959 -0.0978688 0.007261514 0.0834102 -0.09853416 0.006627976 0.08430278 -0.09772247 0.007406413 0.08415257 -0.0990253 0.006345331 0.08391398 -0.09882956 0.006403267 0.08340466 -0.09970539 0.00541383 0.08315926 -0.09951597 0.005463302 0.08563786 -0.09542727 0.00958687 0.0858668 -0.09518599 0.00994265 0.08621406 -0.0948702 0.00998038 0.08257979 -0.100111 0.004352986 0.08517748 -0.09581279 0.009799182 0.08552199 -0.09549945 0.009882628 0.0881977 -0.09358227 0.008650898 0.08433955 -0.09927809 0.006289362 0.08395671 -0.09962606 0.005849301 0.08444249 -0.0965144 0.009208559 0.08483767 -0.09612178 0.009694576 0.08230459 -0.09995669 0.004416823 0.08289855 -0.09936106 0.005544364 0.08571958 -0.09545201 0.009284853 0.08361387 -0.09993809 0.005375325 0.08331251 -0.0975421 0.008559942 0.08352637 -0.09731429 0.00906378 0.0838449 -0.09702467 0.00925219 0.0841704 -0.09672868 0.009420514 0.08596998 -0.09560817 0.008732974 0.08321279 -0.0975995 0.008853733 0.08470928 -0.096533 0.008642733 0.08456188 -0.0965048 0.008918404 0.08261245 -0.09814536 0.008377909 0.08228087 -0.09848016 0.007660269 0.08268046 -0.098378 0.007189571 0.08246839 -0.09840857 0.00741887 0.08364868 -0.09749746 0.00803399 0.08346748 -0.09750008 0.00829029 0.08177918 -0.09890317 0.007524788 0.08204621 -0.09866046 0.007825851 0.0813781 -0.09930115 0.006535768 0.08152139 -0.09913766 0.007204771 0.08127605 -0.09936076 0.006870329 0.08061468 -0.09996217 0.00578016 0.08082276 -0.09977298 0.006157994 0.08041602 -0.1001359 0.005387783 0.08104318 -0.09957259 0.006521403 0.09279686 -0.09075158 0.003985106 0.09111785 -0.09041059 0.007971346 0.09139239 -0.09016096 0.007678031 0.09237247 -0.08926969 0.006341516 0.09214568 -0.08947587 0.006697893 0.0922172 -0.09127867 0.005129754 0.09054338 -0.09093308 0.008503615 0.09083485 -0.09066796 0.008246541 0.09036397 -0.09112936 0.008300304 0.09119969 -0.09063071 0.006875872 0.09150147 -0.09192955 0.00612384 0.08896249 -0.0923708 0.009491324 0.08929187 -0.09207117 0.00933808 0.0912593 -0.09041416 0.007095158 0.09067076 -0.0926851 0.006938278 0.0876075 -0.09360295 0.009915947 0.08795046 -0.09329098 0.009842574 0.0886293 -0.09267377 0.009625673 0.0902968 -0.09128946 0.008038818 0.08974939 -0.09352296 0.007549166 0.08691155 -0.09423589 0.009990632 0.08927106 -0.09260618 0.008226633 0.08812648 -0.09342545 0.008913338 0.09024178 -0.09120738 0.008746981 0.08703798 -0.09682416 0.007894158 0.08876436 -0.0944187 0.007938504 0.0823239 -0.09840786 0.008110225 0.08808797 -0.09329807 0.009197592 0.0882911 -0.09298127 0.009745836 0.08774465 -0.09534609 0.008094906 0.08721876 -0.09474796 0.00858277 0.08690661 -0.09437251 0.00937885 0.08651226 -0.09607475 0.008132636 0.08631479 -0.09589266 0.008294999 0.08672016 -0.09627765 0.008013784 0.08613258 -0.0957359 0.008496761 0.08656388 -0.09455198 0.009995818 0.08549827 -0.09699696 0.007811665 0.08528047 -0.09683328 0.007967591 0.08572095 -0.09718638 0.007697463 0.08507305 -0.09669929 0.008161425 0.08488106 -0.09659838 0.00838828 0.08450269 -0.09642636 0.00956875 0.08477628 -0.09804546 0.007155358 0.08407157 -0.09761005 0.007586598 0.08385169 -0.09753447 0.007797539 0.08366447 -0.09866458 0.006498277 0.0823571 -0.09916919 0.005792558 0.0831573 -0.0984416 0.006789147 0.08291208 -0.09838908 0.006977915 0.08290815 -0.0978766 0.008625149 0.08262896 -0.09924459 0.00565499 0.08200192 -0.09983509 0.00450766 0.0820896 -0.099137 0.005953609 0.08159613 -0.09975916 0.004667103 0.08119207 -0.09977322 0.004864275 0.176136 -0.09067881 0.03851968 0.1767539 -0.0643211 0.037 0.176136 -0.09067881 0.037 0.176207 -0.08764016 0.03946167 0.1762282 -0.086726 0.03956913 0.1762574 -0.08549368 0.03962194 0.176195 -0.08815491 0.03936254 0.176147 -0.09020018 0.03873497 0.176182 -0.08869826 0.03924089 0.176158 -0.0897141 0.03892695 0.1761699 -0.08922058 0.03909575 0.176218 -0.08715426 0.03953838 0.1765286 -0.07392621 0.03960871 0.1767544 -0.0643211 0.03959774 0.3607464 -0.04579383 0.004957556 0.3607731 -0.04571616 0.004824876 0.3603535 -0.04566818 0.005181431 0.3602956 -0.04544353 0.004908084 0.3605064 -0.04566222 0.004926025 0.360968 -0.0459249 0.005257725 0.360967 -0.04593718 0.005414187 0.3607496 -0.04590898 0.005414187 0.3606343 -0.04584103 0.005177557 0.3607918 -0.04589003 0.005178451 0.3604609 -0.04553437 0.004817306 0.3604875 -0.04576653 0.005178391 0.3601555 -0.04542702 0.005184173 0.3601097 -0.04526555 0.005086064 0.3602403 -0.04554939 0.005181133 0.360069 -0.04526877 0.005257725 0.3600441 -0.04525387 0.005414068 0.3600147 -0.0450657 0.005286157 0.36 -0.04493767 0.005414187 0.3602266 -0.04557675 0.005414187 0.3606946 -0.04561227 0.004739344 0.3604605 -0.04578334 0.005414187 0.3609773 -0.04564875 0.004702985 0.3609699 -0.04586046 0.005022585 0.360977 -0.04564446 0.004707098 0.455 -0.0487225 0.004707098 0.455 -0.04701435 0.002999961 0.360977 -0.04393649 0.002999961 0.186752 -0.06455576 0.037 0.1867514 -0.06455576 0.03910237 0.186272 -0.0849871 0.03914386 0.1862847 -0.08443933 0.03914928 0.186248 -0.08602279 0.03909337 0.18626 -0.08550035 0.03912228 0.186308 -0.08344858 0.03912496 0.186223 -0.08705615 0.03896766 0.186235 -0.08654165 0.03904217 0.186211 -0.08756887 0.03886938 0.186199 -0.08807998 0.03874748 0.186188 -0.0885818 0.03860318 0.186176 -0.08907437 0.03843647 0.186165 -0.0895577 0.03824758 0.1865706 -0.0722661 0.03911143 0.1861529 -0.09003168 0.03803616 0.186143 -0.09049636 0.03780257 0.186132 -0.0909518 0.03754657 0.186132 -0.0909518 0.037 0.214199 -0.06520026 0.03768056 0.186752 -0.06455576 0.037 0.226821 -0.0654965 0.037 0.200843 -0.06488668 0.03838139 0.186752 -0.06455576 0.03910237 -0.2005786 -0.04945653 0.037 -0.1382009 -0.0569269 0.037 -0.200579 -0.05546236 0.037 0.226821 -0.05949068 0.037 0.03379368 -0.06096476 0.037 0.02379649 -0.06073009 0.037 0.186752 -0.06455576 0.037 0.176136 -0.09067881 0.037 0.1767539 -0.0643211 0.037 0.226821 -0.0654965 0.037 0.186132 -0.0909518 0.037 0.02790695 -0.0996288 0.037 0.03288406 -0.09971147 0.037 0.0228855 -0.09953218 0.037 -0.134121 -0.09047645 0.037 -0.128203 -0.05716156 0.037 -0.128998 -0.0910179 0.037 -0.138976 -0.08993309 0.037 0.226821 -0.05949068 0.03999996 0.226821 -0.05648988 0.03999996 0.226821 -0.05648988 0.037 0.226821 -0.05949068 0.037 0.187104 -0.04955577 0.037 0.199878 -0.04985564 0.0384323 0.213117 -0.05016648 0.03773736 0.187104 -0.04955577 0.03908467 0.226821 -0.05048829 0.037 0.1873937 -0.03720748 0.03907012 0.187104 -0.04955577 0.037 0.1877329 -0.02277135 0.03804969 0.187744 -0.0222941 0.03782045 0.187721 -0.02325898 0.03825628 0.18771 -0.02375358 0.03843927 0.187698 -0.02425599 0.03859889 0.187686 -0.02476876 0.03873544 0.1875792 -0.02930277 0.03906071 0.187674 -0.02528476 0.0388481 0.1876609 -0.02580386 0.03893655 0.1876119 -0.02791047 0.03905516 0.187624 -0.02738326 0.03904139 0.187649 -0.0263291 0.03898549 0.187637 -0.02685606 0.0390172 0.187755 -0.02183085 0.03756946 0.1871042 -0.04955577 0.03908467 0.187765 -0.02137869 0.03729599 0.187776 -0.02093738 0.037 0.187104 -0.04955577 0.037 0.226821 -0.05048829 0.037 0.226821 -0.05648988 0.037 -0.188 -0.04199999 0.037 -0.2005783 -0.04645574 0.037 -0.134669 -0.008715927 0.037 -0.132197 -0.008513391 0.037 -0.127053 -0.008151113 0.037 -0.137849 -0.04192686 0.037 -0.127851 -0.04216158 0.037 -0.200577 -0.04199999 0.037 -0.18638 -0.04078745 0.037 -0.129658 -0.008325159 0.037 -0.1370739 -0.008932709 0.037 0.03494948 -0.01173305 0.037 0.02414858 -0.04573005 0.037 0.02494955 -0.01161187 0.037 0.03414589 -0.04596477 0.037 0.182874 -0.0202589 0.037 0.187776 -0.02093738 0.037 0.177106 -0.04932105 0.037 0.1778039 -0.01959508 0.037 0.275 -0.02647608 0.02999997 0.285347 -0.02647608 0.02999997 0.280212 -0.02647608 0.03068405 0.275 -0.02647608 0.03134715 0.275 -0.02597606 0.02999997 0.285347 -0.02647608 0.02999997 0.275 -0.02647608 0.02999997 0.29 -0.02712118 0.02999997 0.29 -0.02597606 0.02999997 0.455 -0.04901546 0.005414187 0.455 -0.04901546 0.02338826 0.441318 -0.04856759 0.02428668 0.427635 -0.04811966 0.02515727 0.413949 -0.04767167 0.02599996 0.360967 -0.04593718 0.005414187 0.360967 -0.04593718 0.02599996 0.3600348 -0.04522651 0.005414187 0.3600275 -0.04518121 0.02599996 0.36 -0.04493767 0.02599996 0.36 -0.04493767 0.005414187 0.3601466 -0.04546332 0.02599996 0.3602634 -0.04562532 0.005414187 0.360346 -0.04569751 0.02599996 0.3605821 -0.04584896 0.005414187 0.3606063 -0.04585987 0.02599996 0.3609659 -0.04594659 0.005414187 0.3609663 -0.04594302 0.02599996 0.48 -0.0544154 0.008824348 0.455 -0.05503058 0.008928477 0.48 -0.05583107 0.008999407 0.455 -0.05645281 0.009005069 0.48 -0.05725657 0.008948743 0.455 -0.05786925 0.008856594 0.48 -0.05865615 0.008673727 0.455 -0.05924403 0.008486926 0.48 -0.05999535 0.008180975 0.455 -0.06054306 0.007905423 0.48 -0.06123971 0.007483124 0.455 -0.06152743 0.007275402 0.48 -0.06235867 0.006597101 0.455 -0.0622614 0.006679236 0.48 -0.06318074 0.005715548 0.455 -0.06310278 0.005817115 0.48 -0.06374192 0.004954159 0.455 -0.06379413 0.004873991 0.48 -0.06412988 0.004302561 0.48 -0.06444823 0.003666937 0.455 -0.06424421 0.004089593 0.455 -0.06471955 0.003003537 0.48 -0.06471025 0.002999961 0.455 -0.05385231 0.008684575 0.455 -0.05295431 0.008387625 0.48 -0.05304545 0.008428215 0.455 -0.05189067 0.007896602 0.48 -0.05175524 0.007820844 0.455 -0.05070185 0.007116138 0.48 -0.05057752 0.00701785 0.455 -0.04964983 0.006157219 0.48 -0.04971498 0.006218552 0.455 -0.04890888 0.005246281 0.48 -0.04895216 0.005314648 0.455 -0.04842889 0.004502356 0.48 -0.04833102 0.004328668 0.455 -0.04801768 0.003699898 0.48 -0.04792106 0.00347805 0.455 -0.04768729 0.002856492 0.48 -0.04760479 0.002596735 0.455 -0.04744321 0.001982033 0.48 -0.04738014 0.001679718 0.455 -0.04728841 0.001089692 0.48 -0.04725342 7.47981e-4 0.455 -0.04721921 1.54381e-7 0.48 -0.04722499 0 0.411237 -0.03536736 0 0.411237 -0.03536736 0.01099997 0.406237 -0.03536736 0.01099997 0.406237 -0.03536736 0 0.363 -0.02387237 0.01499998 0.363 -0.02387237 0 0.338 -0.02387237 0 0.338 -0.02387237 0.01499998 0.3376293 -0.02394068 0 0.3376033 -0.02395141 0.01499998 0.3379992 -0.02386265 0.01499998 0.3379995 -0.02386635 0 0.337412 -0.02406334 0.01499998 0.3373605 -0.0241 0 0.3372279 -0.02423262 0.01499998 0.3371118 -0.02439612 0 0.3370688 -0.02450048 0.01499998 0.33699 -0.02487158 0 0.3369938 -0.02487188 0.01499998 0.295 -0.02647608 0.02862 0.29 -0.02647608 0 0.295 -0.02647608 0 0.29 -0.02647608 0.02935117 0.29 -0.02597606 0 0.29 -0.02647608 0 0.29 -0.02647608 0.02935117 0.29 -0.02597606 0.02999997 0.29 -0.02679258 0.02968138 0.29 -0.02712118 0.02999997 0.29 -0.02597606 0.02999997 0.275 -0.02597606 0 0.29 -0.02597606 0 0.275 -0.02597606 0.02999997 0.08463299 8.63139e-4 0.06499999 0.06047707 0.004726886 0.06499999 0.06072878 0.00448352 0.06499999 0.08773487 0.01550173 0.06499999 0.04398214 0.01508116 0.06499999 0.03942859 0.0145685 0.06499999 0.0932911 0.0150395 0.06499999 0.05377441 0.01586204 0.06499999 0.07728314 0.01608866 0.06499999 0.05508345 0.015935 0.06499999 0.04919183 0.01554906 0.06499999 0.08319789 0.01580375 0.06499999 0.07438397 0.0161817 0.06499999 0.05831223 0.01608431 0.06499999 0.06422722 0.01624399 0.06499999 0.06291788 0.01622152 0.06499999 0.07860642 0.01603591 0.06499999 0.06944739 0.01626372 0.06499999 0.06554853 0.01625967 0.06499999 0.06684356 0.01626777 0.06499999 0.05668962 0.01601511 0.06499999 0.07597422 0.0161345 0.06499999 0.07276308 0.01621901 0.06499999 0.05961793 0.01613229 0.06499999 0.0711283 0.01624685 0.06499999 0.06816691 0.0162692 0.06499999 0.06125277 0.0161826 0.06499999 0.05211424 0.01575934 0.06499999 0.08059698 0.01594495 0.06499999 0.05048465 0.01564651 0.06499999 0.04789817 0.01544433 0.06499999 0.08544594 0.01566237 0.06499999 0.04658019 0.01532971 0.06499999 0.045304 0.01521158 0.06499999 0.04266446 0.01494324 0.06499999 0.09003353 0.0153222 0.06499999 0.04106312 0.0147646 0.06499999 0.09167808 0.01518332 0.06499999 0.03816235 0.01440727 0.06499999 0.09561479 0.01481807 0.06499999 0.03683179 0.01422882 0.06499999 0.09752225 0.01462322 0.06499999 0.05730664 0.006008207 0.06499999 0.03525471 0.014005 0.06499999 0.09942007 0.01442033 0.06499999 0.1017478 0.01415657 0.06499999 0.104049 0.01388174 0.06499999 0.1062887 0.01360034 0.06499999 0.1082319 0.01334595 0.06499999 0.05765467 0.005983769 0.06499999 0.03326922 0.01370251 0.06499999 0.03165477 0.01343816 0.06499999 0.1098783 0.01312291 0.06499999 0.1117727 0.01285892 0.06499999 0.03036475 0.01321607 0.06499999 0.1140986 0.01252311 0.06499999 0.02912276 0.0129913 0.06499999 0.1180316 0.01192981 0.06499999 0.1160991 0.01222521 0.06499999 0.0580008 0.005935072 0.06499999 0.02622348 0.01242607 0.06499999 0.1205118 0.01154077 0.06499999 0.05695807 0.006008207 0.06499999 0.1230829 0.01112473 0.06499999 0.02458739 0.01207834 0.06499999 0.02335476 0.01180148 0.06499999 0.02200144 0.01148289 0.06499999 0.05834084 0.005862772 0.06499999 0.1275522 0.01037752 0.06499999 0.1251329 0.01078563 0.06499999 0.05867767 0.005766093 0.06499999 0.02019238 0.01102834 0.06499999 0.0590049 0.005647003 0.06499999 0.1306274 0.009847342 0.06499999 0.05932408 0.005504667 0.06499999 0.1335987 0.009325087 0.06499999 0.01887422 0.01067721 0.06499999 0.01792097 0.01040965 0.06499999 0.05963218 0.005340874 0.06499999 0.01693743 0.01012319 0.06499999 0.05992758 0.005156159 0.06499999 0.1366368 0.008781611 0.06499999 0.05660909 0.005984008 0.06499999 0.1402333 0.008127689 0.06499999 0.06021058 0.004950463 0.06499999 0.01572257 0.009753465 0.06499999 0.0146051 0.009392738 0.06499999 0.01355028 0.0090366 0.06499999 0.01293259 0.008819758 0.06499999 0.0562644 0.005935549 0.06499999 0.144085 0.007415175 0.06499999 0.01231759 0.008596062 0.06499999 0.0609619 0.004224658 0.06499999 0.01140469 0.008250772 0.06499999 0.1483358 0.006617546 0.06499999 0.0613721 0.003659844 0.06499999 0.06117689 0.003949344 0.06499999 0.05592179 0.005862832 0.06499999 0.01048588 0.007887959 0.06499999 0.009881019 0.007637679 0.06499999 0.05558735 0.005766928 0.06499999 0.009165227 0.007328212 0.06499999 0.05525916 0.00564754 0.06499999 0.06154608 0.003358423 0.06499999 0.07363599 0.001121282 0.06499999 0.1534069 0.005650877 0.06499999 0.05494016 0.005505681 0.06499999 0.06169945 0.003043651 0.06499999 0.008087038 0.006838619 0.06499999 0.0618298 0.002721071 0.06499999 0.007495582 0.006556451 0.06499999 0.05463248 0.005342066 0.06499999 0.05433547 0.005156695 0.06499999 0.006911039 0.006262183 0.06499999 0.006319046 0.005948007 0.06499999 0.06193774 0.002388179 0.06499999 0.05378586 0.004727303 0.06499999 0.1586781 0.004633247 0.06499999 0.05330175 0.004226088 0.06499999 0.004620611 0.00498265 0.06499999 0.05308657 0.003950834 0.06499999 0.06202208 0.002049982 0.06499999 0.05271655 0.00335884 0.06499999 0.05289179 0.003662109 0.06499999 0.003541827 0.004246711 0.06499999 0.164444 -1.92235e-4 0.06499999 0.164676 -5.38516e-5 0.06499999 0.003025114 0.003849208 0.06499999 0.002523422 0.003431975 0.06499999 0.05256408 0.003046214 0.06499999 0.05695569 -0.003985464 0.06499999 0.04842627 -0.008523106 0.06499999 0.05214357 0.001361548 0.06499999 0.05217999 0.001707792 0.06499999 9.12978e-4 0.001837968 0.06499999 0.08439826 -0.009134054 0.06499999 0.07340127 -0.008875906 0.06499999 0.05867505 -0.003744184 0.06499999 0.05834066 -0.003840088 0.06499999 0.163669 -0.004458725 0.06499999 0.1646749 -0.005337297 0.06499999 0.1642259 -0.005040943 0.06499999 0.1654289 -0.005620658 0.06499999 0.165169 -0.005548775 0.06499999 0.164918 -0.00545448 0.06499999 0.165693 -0.00566864 0.06499999 0.1379746 -0.0109595 0.06499999 0.1555112 -0.01131772 0.06499999 0.165962 -0.005692899 0.06499999 0.166231 -0.005692899 0.06499999 0.2111336 -0.00587511 0.06499999 0.166499 -0.005668878 0.06499999 0.1848666 -0.011936 0.06499999 0.1914696 -0.01207852 0.06499999 0.2204211 -0.007766544 0.06499999 0.1980295 -0.01222133 0.06499999 0.2251852 -0.008748888 0.06499999 0.2024463 -0.01231634 0.06499999 0.228106 -0.00936073 0.06499999 0.2304306 -0.009856224 0.06499999 0.2132731 -0.01254427 0.06499999 0.2168228 -0.01261454 0.06499999 0.2333056 -0.0104829 0.06499999 0.2204698 -0.01268053 0.06499999 0.2238303 -0.01273137 0.06499999 0.2360762 -0.01109105 0.06499999 0.2264357 -0.01276081 0.06499999 0.2289835 -0.01277905 0.06499999 0.2329761 -0.0127753 0.06499999 0.238838 -0.01168376 0.06499999 0.2312514 -0.01278215 0.06499999 0.2359817 -0.01275259 0.06499999 0.240231 -0.01199227 0.06499999 0.2375668 -0.01274472 0.06499999 0.2406592 -0.01273977 0.06499999 0.241667 -0.01228487 0.06499999 0.243144 -0.01256155 0.06499999 0.2427892 -0.01274049 0.06499999 0.2421153 -0.0127303 0.06499999 0.2434653 -0.01276612 0.06499999 0.244664 -0.01282227 0.06499999 0.2443525 -0.01281672 0.06499999 0.2084529 -0.01244384 0.06499999 0.1804289 -0.01184076 0.06499999 0.17135 -0.01164811 0.06499999 0.166764 -0.005620777 0.06499999 0.1657018 -0.0115295 0.06499999 0.1603667 -0.01141834 0.06499999 0.169049 -0.003231942 0.06499999 0.167023 -0.005549311 0.06499999 0.167276 -0.005454599 0.06499999 0.1480939 -0.01116561 0.06499999 0.1985138 -0.003313362 0.06499999 0.167749 -0.00519973 0.06499999 0.16817 -0.004864513 0.06499999 0.168355 -0.004670381 0.06499999 0.1429346 -0.01106047 0.06499999 0.168524 -0.004459679 0.06499999 0.168799 -0.00399816 0.06499999 0.168672 -0.004235267 0.06499999 0.1331612 -0.01086163 0.06499999 0.168905 -0.003750622 0.06499999 0.168988 -0.003494739 0.06499999 0.169085 -0.002965688 0.06499999 0.169097 -0.002695977 0.06499999 0.1240001 -0.0106737 0.06499999 0.1852391 -6.33477e-4 0.06499999 0.169085 -0.002426207 0.06499999 0.164444 -0.005199611 0.06499999 0.169049 -0.002160489 0.06499999 0.1176123 -0.01054042 0.06499999 0.168989 -0.001898705 0.06499999 0.164023 -0.004864037 0.06499999 0.168906 -0.001642167 0.06499999 0.1128127 -0.01043838 0.06499999 0.163837 -0.004669249 0.06499999 0.168672 -0.00115776 0.06499999 0.1687999 -0.001395046 0.06499999 0.1067851 -0.01030784 0.06499999 0.163521 -0.004234194 0.06499999 0.168524 -9.33195e-4 0.06499999 0.168356 -7.22707e-4 0.06499999 0.163394 -0.003996849 0.06499999 0.16817 -5.27935e-4 0.06499999 0.1002757 -0.01016223 0.06499999 0.06047648 -0.00270462 0.06499999 0.06020838 -0.002929449 0.06499999 0.167968 -3.5102e-4 0.06499999 0.09594786 -0.01006239 0.06499999 0.05992686 -0.003133952 0.06499999 0.09222757 -0.009973883 0.06499999 0.1773539 9.48776e-4 0.06499999 0.05962997 -0.003319323 0.06499999 0.167519 -5.4655e-5 0.06499999 0.16775 -1.9235e-4 0.06499999 0.05932229 -0.003482937 0.06499999 0.08771932 -0.009862601 0.06499999 0.167025 1.56851e-4 0.06499999 0.167276 6.2542e-5 0.06499999 0.05900329 -0.003624796 0.06499999 0.08336639 -0.00974977 0.06499999 0.1665 2.76681e-4 0.06499999 0.166765 2.28718e-4 0.06499999 0.07966333 -0.009649634 0.06499999 0.166232 3.00953e-4 0.06499999 0.1659629 3.00953e-4 0.06499999 0.07483279 -0.009511828 0.06499999 0.057998 -0.003912806 0.06499999 0.1632879 -0.003749728 0.06499999 0.1698154 0.002447962 0.06499999 0.07010799 -0.009366989 0.06499999 0.066859 -0.009260952 0.06499999 0.165695 2.7692e-4 0.06499999 0.06369495 -0.009152412 0.06499999 0.06072705 -0.002462685 0.06499999 0.05765336 -0.003961265 0.06499999 0.05730438 -0.003985464 0.06499999 0.06028664 -0.009028077 0.06499999 0.05784851 -0.00893408 0.06499999 0.06096059 -0.002203345 0.06499999 0.16543 2.28854e-4 0.06499999 0.1641289 0.00356847 0.06499999 0.05552035 -0.008840203 0.06499999 0.05306756 -0.008735954 0.06499999 0.165171 1.57378e-4 0.06499999 0.05088412 -0.008638501 0.06499999 0.164918 6.26602e-5 0.06499999 0.06117588 -0.001928091 0.06499999 3.83619e-4 0.001146137 0.06499999 2.82982e-4 9.7922e-4 0.06499999 0.05213117 0.001011312 0.06499999 0.163394 -0.001393795 0.06499999 0.163522 -0.001156687 0.06499999 4.92879e-4 0.001307547 0.06499999 0.163838 -7.21587e-4 0.06499999 0.1640239 -5.27432e-4 0.06499999 0.04610848 -0.008407771 0.06499999 0.06193715 -3.67822e-4 0.06499999 0.06182938 -6.99361e-4 0.06499999 0.05214357 6.61153e-4 0.06499999 1.93885e-4 8.06014e-4 0.06499999 1.18402e-4 6.26404e-4 0.06499999 0.0440765 -0.008301377 0.06499999 5.99461e-5 4.40292e-4 0.06499999 0.04147154 -0.008156895 0.06499999 2.33956e-5 2.49123e-4 0.06499999 0.05217999 3.1494e-4 0.06499999 9.89663e-6 5.48035e-5 0.06499999 0.03874611 -0.007994294 0.06499999 0.05660778 -0.003961026 0.06499999 0.03657811 -0.007855832 0.06499999 5.83173e-4 -0.001363754 0.06499999 0.05256295 -0.001020967 0.06499999 0.05243259 -6.98342e-4 0.06499999 0.03495281 -0.00774604 0.06499999 8.56969e-4 -0.001640856 0.06499999 7.15134e-4 -0.001507103 0.06499999 4.6215e-4 -0.001210749 0.06499999 0.05232465 -3.65482e-4 0.06499999 2.56764e-4 -8.79784e-4 0.06499999 0.001007437 -0.001765012 0.06499999 0.00149548 -0.00208652 0.06499999 0.001745045 -0.002220511 0.06499999 0.05271637 -0.00133568 0.06499999 0.001164793 -0.001880109 0.06499999 5.36521e-5 -3.32425e-4 0.06499999 1.05203e-4 -5.20456e-4 0.06499999 0.05224025 -2.72721e-5 0.06499999 0.001327753 -0.00198704 0.06499999 0.0331698 -0.00761944 0.06499999 0.002074241 -0.00237739 0.06499999 0.03126448 -0.007475316 0.06499999 0.05626165 -0.003912329 0.06499999 0.02977633 -0.007356345 0.06499999 0.02813416 -0.007218122 0.06499999 0.002429246 -0.002533078 0.06499999 0.02622103 -0.007046461 0.06499999 0.02430272 -0.006862282 0.06499999 0.05592149 -0.003840088 0.06499999 0.05289036 -0.00163716 0.06499999 0.05558478 -0.00374335 0.06499999 0.02224266 -0.006649255 0.06499999 0.00303471 -0.002788186 0.06499999 0.01938492 -0.006321132 0.06499999 0.02062302 -0.006467938 0.06499999 0.008392095 -0.004497885 0.06499999 0.05378538 -0.002704143 0.06499999 0.05308556 -0.0019266 0.06499999 0.003735244 -0.003071188 0.06499999 0.005467355 -0.00369817 0.06499999 0.05330049 -0.002201914 0.06499999 0.004463076 -0.003348588 0.06499999 0.005006253 -0.003542244 0.06499999 0.005926787 -0.003844022 0.06499999 0.05353355 -0.002460777 0.06499999 0.006480157 -0.004009008 0.06499999 0.007097661 -0.004178464 0.06499999 0.007620453 -0.004312753 0.06499999 0.05525755 -0.00362426 0.06499999 0.01817333 -0.006168484 0.06499999 0.05405187 -0.00292772 0.06499999 0.009475588 -0.004734516 0.06499999 0.01708537 -0.006023287 0.06499999 0.05493825 -0.003481924 0.06499999 0.0159927 -0.00586903 0.06499999 0.01055997 -0.004953086 0.06499999 0.05433475 -0.003133416 0.06499999 0.01167196 -0.005163252 0.06499999 0.05463027 -0.00331813 0.06499999 0.01273596 -0.005352795 0.06499999 0.01381731 -0.00553435 0.06499999 0.01490545 -0.005706548 0.06499999 1.73637e-4 -7.03251e-4 0.06499999 3.53058e-4 -0.001049101 0.06499999 2.08751e-5 -1.40236e-4 0.06499999 0.163145 -0.002159953 0.06499999 0.163109 -0.002426207 0.06499999 0.163205 -0.001897156 0.06499999 0.1632879 -0.001641333 0.06499999 0.06202155 -2.94072e-5 0.06499999 6.55758e-4 0.001526415 0.06499999 0.16367 -9.3229e-4 0.06499999 0.06213116 0.001011312 0.06499999 0.06211876 6.61153e-4 0.06499999 0.001109004 0.002061963 0.06499999 0.05232524 0.002390503 0.06499999 0.002036869 0.002995014 0.06499999 0.001565396 0.002538323 0.06499999 0.05224084 0.002052128 0.06499999 0.167967 -0.005041956 0.06499999 0.167518 -0.005338072 0.06499999 0.164227 -3.50003e-4 0.06499999 0.06169825 -0.001023471 0.06499999 0.06154584 -0.001336097 0.06499999 0.06137055 -0.001639366 0.06499999 0.163097 -0.002695977 0.06499999 0.163109 -0.002965688 0.06499999 0.163205 -0.003493249 0.06499999 0.163145 -0.003231465 0.06499999 0.06208246 3.1494e-4 0.06499999 0.0535354 0.004485428 0.06499999 0.0210818 0.01125568 0.06499999 0.02776664 0.01273453 0.06499999 0.05405408 0.004952192 0.06499999 0.005182623 0.005320966 0.06499999 0.004073679 0.004624545 0.06499999 0.05243307 0.002722084 0.06499999 0.06211876 0.001361548 0.06499999 0.06208246 0.001707792 0.06499999 0.1778039 -0.01959508 0.037 0.177106 -0.04932105 0.037 0.177106 -0.04932105 0.04499995 0.1778219 -0.01885795 0.03633916 0.1778129 -0.01922029 0.03667938 0.177928 -0.01433068 0.04499995 0.17783 -0.01850849 0.03597956 0.177838 -0.01817148 0.03560036 0.177845 -0.01784718 0.03520154 0.177853 -0.01753556 0.03478336 0.177872 -0.01671606 0.03343588 0.177866 -0.01697039 0.03390067 0.17786 -0.01724249 0.03434926 0.177928 -0.01433068 0.02999997 0.177877 -0.0164842 0.03296309 0.177882 -0.01628136 0.0324946 0.177886 -0.01610267 0.0320214 0.17789 -0.0159471 0.03154075 0.177893 -0.01580959 0.03103989 0.177896 -0.01569306 0.03052628 0.177898 -0.01559758 0.02999997 0.174816 -0.01425766 0.04499995 0.177928 -0.01433068 0.02999997 0.177928 -0.01433068 0.04499995 0.174816 -0.01425766 0.02999997 0.1708675 -0.01218235 0.02999997 0.171454 -0.01285326 0.02999997 0.1709192 -0.01225286 0.04499995 0.1703467 -0.01126867 0.02999997 0.1704571 -0.01149225 0.04499995 0.1701904 -0.01084864 0.04499995 0.1700744 -0.0104475 0.02999997 0.1700133 -0.0101636 0.04499995 0.1699553 -0.009755551 0.02999997 0.169946 -0.009612023 0.04499995 0.169933 -0.009141683 0.04499995 0.1699337 -0.009141683 0.02999997 0.171358 -0.0127539 0.04499995 0.1717731 -0.01313698 0.04499995 0.171883 -0.01322066 0.02999997 0.1722924 -0.01350784 0.02999997 0.1723453 -0.01354026 0.04499995 0.1729139 -0.01383584 0.02999997 0.1729707 -0.01386046 0.04499995 0.1735732 -0.01407319 0.02999997 0.173633 -0.0140897 0.04499995 0.1742568 -0.01421576 0.02999997 0.1743183 -0.01422375 0.04499995 0.174816 -0.01425766 0.02999997 0.174816 -0.01425766 0.04499995 0.170091 -0.00248754 0.04499995 0.169935 -0.009141683 0.02999997 0.169935 -0.009141683 0.04499995 0.170091 -0.00248754 0.02999997 0.1662796 0.00130254 0.04499995 0.1657065 0.001287698 0.02999997 0.1663399 0.001299381 0.02999997 0.1669656 0.001211225 0.02999997 0.166908 0.001223683 0.04499995 0.1673949 0.001087367 0.02999997 0.1675166 0.001046657 0.04499995 0.1678597 8.97554e-4 0.02999997 0.1680915 7.74329e-4 0.04499995 0.1684052 5.74079e-4 0.02999997 0.1686099 4.19666e-4 0.04499995 0.1688955 1.66203e-4 0.02999997 0.1691681 -1.20887e-4 0.04499995 0.1693131 -3.13091e-4 0.02999997 0.1696453 -8.43841e-4 0.02999997 0.169553 -6.82187e-4 0.04499995 0.169757 -0.001076579 0.04499995 0.1698279 -0.001254081 0.02999997 0.1699814 -0.001732647 0.02999997 0.16993 -0.001551866 0.04499995 0.1700369 -0.001991629 0.04499995 0.1700974 -0.002486944 0.02999997 0.170091 -0.00248754 0.04499995 0.1656478 0.00128144 0.04499995 0.1650844 0.001176536 0.02999997 0.165207 0.001203775 0.04499995 0.1647261 0.001064836 0.04499995 0.164484 9.67635e-4 0.02999997 0.1641472 8.0004e-4 0.04499995 0.1639257 6.67091e-4 0.02999997 0.1636216 4.49915e-4 0.04499995 0.163522 3.65381e-4 0.02999997 0.163156 1.96352e-5 0.04499995 0.163195 6.08281e-5 0.02999997 0.162874 -3.26305e-4 0.02999997 0.162873 -3.28075e-4 0.04499995 0.1626005 -7.47069e-4 0.04499995 0.162629 -6.97183e-4 0.02999997 0.1623029 -0.001403093 0.02999997 0.162406 -0.00115323 0.04499995 0.1622385 -0.001630425 0.04499995 0.1621268 -0.002185761 0.02999997 0.1621201 -0.002242326 0.04499995 0.162097 -0.0026955 0.02999997 0.162097 -0.0026955 0.04499995 0.1619499 -0.008954226 0.04499995 0.162097 -0.0026955 0.02999997 0.162097 -0.0026955 0.04499995 0.1619499 -0.008954226 0.02999997 0.1602969 -0.01255661 0.04499995 0.1602499 -0.01259839 0.02999997 0.1597309 -0.01299637 0.04499995 0.1596784 -0.013031 0.02999997 0.159245 -0.01327979 0.04499995 0.158789 -0.01349002 0.04499995 0.159245 -0.01327979 0.02999997 0.1587301 -0.01351279 0.02999997 0.1581062 -0.01370441 0.04499995 0.1580448 -0.0137186 0.02999997 0.1574037 -0.01381927 0.04499995 0.157341 -0.01382452 0.02999997 0.156834 -0.01383548 0.04499995 0.156834 -0.01383548 0.02999997 0.160754 -0.01208788 0.02999997 0.1607946 -0.01203984 0.04499995 0.1611711 -0.01152414 0.02999997 0.161094 -0.01163697 0.04499995 0.1613903 -0.01114374 0.04499995 0.1615125 -0.01089209 0.02999997 0.161715 -0.0103569 0.02999997 0.1616728 -0.01049154 0.04499995 0.1618449 -0.009875595 0.02999997 0.1618576 -0.009813904 0.04499995 0.1619605 -0.008954882 0.02999997 0.1619566 -0.008954644 0.04499995 0.07533025 -0.011922 0.04499995 0.07690238 -0.01195895 0.0357182 0.07847529 -0.01199585 0.03577768 0.156834 -0.01383548 0.04499995 0.1338571 -0.01329606 0.03252089 0.08004879 -0.01203274 0.03582125 0.07533025 -0.011922 0.03563886 0.08162248 -0.01206976 0.03585165 0.0831964 -0.01210665 0.03587108 0.0847705 -0.01214367 0.03588068 0.08634448 -0.01218056 0.0358814 0.08791846 -0.01221758 0.03587347 0.08949249 -0.01225447 0.03585755 0.09106636 -0.01229149 0.03583395 0.0926401 -0.01232838 0.03580307 0.09421366 -0.0123654 0.03576505 0.09658288 -0.01242095 0.03569561 0.09971714 -0.01249456 0.03557956 0.1028705 -0.01256853 0.03543788 0.105223 -0.01262378 0.03531545 0.1075698 -0.01267892 0.03518134 0.1107571 -0.01275378 0.03497695 0.1138725 -0.01282691 0.03475254 0.116215 -0.01288187 0.0345661 0.117784 -0.01291865 0.03443336 0.119351 -0.01295548 0.03429359 0.120918 -0.01299226 0.03414607 0.122485 -0.01302909 0.03399056 0.12405 -0.01306575 0.03382629 0.125615 -0.01310259 0.03365266 0.127178 -0.01313924 0.03346896 0.12874 -0.0131759 0.03327369 0.1303 -0.01321256 0.03306478 0.131858 -0.01324915 0.03283965 0.1327204 -0.01326936 0.03270685 0.1350169 -0.01332324 0.03231507 0.1361345 -0.01334959 0.03209722 0.156834 -0.01383548 0.02999997 0.136924 -0.01336807 0.03192728 0.137481 -0.01338118 0.03179806 0.138036 -0.01339417 0.0316593 0.138588 -0.01340705 0.03150814 0.1391465 -0.01342022 0.03133672 0.1394349 -0.01342707 0.03123795 0.1397529 -0.01343446 0.03111535 0.139986 -0.01344001 0.03101038 0.1401361 -0.01344335 0.03093272 0.1402927 -0.01344716 0.03083676 0.140386 -0.01344937 0.03076577 0.14045 -0.01345086 0.03070765 0.1405079 -0.01345217 0.03064286 0.140554 -0.0134533 0.03056985 0.140582 -0.01345396 0.03048855 0.1405888 -0.01345407 0.03040426 0.140594 -0.01345425 0.02999997 0.140582 -0.01345396 0.03048855 0.140554 -0.0134533 0.03056985 0.1405079 -0.01345217 0.03064286 0.09696578 -0.01215052 0.03442132 0.09658074 -0.01242119 0.03569567 0.1405888 -0.01345419 0.03040415 0.14045 -0.01345086 0.03070765 0.140386 -0.01344937 0.03076577 0.1402927 -0.01344722 0.03083676 0.1401361 -0.01344352 0.03093272 0.139986 -0.01343989 0.03101038 0.1397526 -0.01343363 0.03111553 0.135468 -0.01322269 0.02999997 0.1394349 -0.01342707 0.0312379 0.1391465 -0.01342022 0.03133672 0.138588 -0.01340705 0.03150814 0.137481 -0.01338118 0.03179806 0.136924 -0.01336807 0.03192728 0.138036 -0.01339417 0.0316593 0.1361346 -0.01334953 0.03209722 0.1338737 -0.01329851 0.03251785 0.1350169 -0.01332324 0.03231507 0.1289352 -0.01307064 0.03269135 0.1294312 -0.0129739 0.02999991 0.131858 -0.01324915 0.03283965 0.1327232 -0.01326948 0.03270643 0.12874 -0.0131759 0.03327369 0.1303 -0.01321256 0.03306478 0.127178 -0.01313924 0.03346896 0.125615 -0.01310259 0.03365266 0.12405 -0.01306575 0.03382629 0.1170484 -0.012901 0.03449743 0.1170759 -0.01264899 0.03331828 0.122485 -0.01302909 0.03399056 0.120918 -0.01299226 0.03414607 0.1138772 -0.01282721 0.03475219 0.1069867 -0.01236587 0.03387409 0.1107587 -0.01275378 0.03497684 0.1075699 -0.01267898 0.03518134 0.09971535 -0.0124945 0.03557968 0.08682805 -0.01199984 0.03497129 0.08162248 -0.01206976 0.03585165 0.07904899 -0.01193219 0.03539305 0.08791846 -0.01221758 0.03587347 0.08634448 -0.01218056 0.0358814 0.07392102 -0.01178783 0.02999997 0.07904887 -0.01181316 0.03337466 0.08673536 -0.01188021 0.03294903 0.07391977 -0.01178854 0.03418308 0.07393777 -0.01179146 0.03440284 0.07397568 -0.01179766 0.03458225 0.07422471 -0.0118345 0.03506845 0.07434606 -0.01185005 0.03520536 0.07403725 -0.01180738 0.03475505 0.07412099 -0.01181989 0.03491777 0.07533025 -0.011922 0.03563886 0.07479715 -0.01189517 0.03551286 0.07463437 -0.01188135 0.03542959 0.07448315 -0.01186609 0.03532665 0.07690238 -0.01195895 0.0357182 0.07496929 -0.01190698 0.03557574 0.07514858 -0.01191556 0.03561478 0.08721226 -0.01188611 0.02999997 0.08004879 -0.01203274 0.03582125 0.0847705 -0.01214367 0.03588068 0.0831964 -0.01210665 0.03587108 0.08949249 -0.01225447 0.03585755 0.09421366 -0.0123654 0.03576505 0.09106636 -0.01229149 0.03583395 0.0926401 -0.01232838 0.03580307 0.1028709 -0.01256853 0.03543788 0.105223 -0.01262378 0.03531545 0.119351 -0.01295548 0.03429359 0.1200799 -0.01263129 0.03109127 0.07847529 -0.01199585 0.03577768 0.09443628 -0.01199054 0.03252166 0.1021121 -0.01213502 0.03209489 0.1123715 -0.0123912 0.03152304 0.09747141 -0.01204198 0.02999997 0.1077206 -0.01226657 0.02999997 0.1174885 -0.01254546 0.02999997 0.140594 -0.01345425 0.02999997 0.06812572 -0.008611559 0.02999997 0.06854873 -0.009061455 0.04499995 0.07533025 -0.011922 0.04499995 0.07514858 -0.01191556 0.03561478 0.07533025 -0.011922 0.03563886 0.06735026 -0.007641315 0.02999997 0.06755983 -0.007931113 0.04499995 0.06658655 -0.006345987 0.02999997 0.06688404 -0.00689423 0.04499995 0.0664342 -0.006009042 0.04499995 0.06617701 -0.005368888 0.02999997 0.06598663 -0.004825472 0.04499995 0.06588667 -0.004472076 0.02999997 0.06570678 -0.003619194 0.04499995 0.06564676 -0.003222823 0.02999997 0.06557786 -0.002428889 0.02999997 0.06559163 -0.002675592 0.04499995 0.06556433 -0.00169003 0.04499995 0.06556564 -0.00169003 0.02999997 0.06902712 -0.009502112 0.02999997 0.06950581 -0.009883403 0.04499995 0.07001602 -0.01024734 0.02999997 0.07032746 -0.0104469 0.04499995 0.07087564 -0.01076036 0.02999997 0.07120645 -0.01092797 0.04499995 0.07178723 -0.01118683 0.02999997 0.07211959 -0.01131552 0.04499995 0.07272744 -0.01151674 0.02999997 0.07308065 -0.0116142 0.04499995 0.07392078 -0.01178944 0.02999997 0.07384049 -0.01177495 0.04499995 0.07459276 -0.01188057 0.04499995 0.07412099 -0.01181989 0.03491777 0.07463437 -0.01188135 0.03542959 0.07422471 -0.0118345 0.03506845 0.07434606 -0.01185005 0.03520536 0.07391971 -0.01178848 0.03402131 0.07397568 -0.01179766 0.03458225 0.07393777 -0.01179146 0.03440284 0.07392227 -0.0117889 0.03422039 0.07403725 -0.01180738 0.03475505 0.07448315 -0.01186609 0.03532665 0.07479715 -0.01189517 0.03551286 0.07496929 -0.01190698 0.03557574 0.06563121 0.001011312 0.04499995 0.06556779 -0.001690089 0.02999997 0.06556779 -0.001690089 0.04499995 0.06563121 0.001011312 0.02999997 0.05799287 0.009475529 0.04499995 0.05661195 0.009503364 0.04499995 0.05765062 0.009503364 0.02999997 0.05935096 0.009224593 0.04499995 0.05901789 0.009307444 0.02999997 0.06045514 0.008837521 0.04499995 0.06033563 0.008892714 0.02999997 0.06127864 0.008433878 0.04499995 0.06156849 0.008270502 0.02999997 0.06223058 0.007821619 0.04499995 0.06249165 0.007611513 0.02999997 0.0629763 0.007182657 0.04499995 0.06297725 0.007181584 0.02999997 0.0634312 0.006721436 0.04499995 0.06365483 0.006472706 0.02999997 0.06389778 0.006155669 0.04499995 0.06427174 0.005627334 0.04499995 0.06445229 0.005345582 0.02999997 0.0648266 0.004639685 0.04499995 0.06495869 0.004332005 0.02999997 0.0653122 0.003347098 0.04499995 0.06527101 0.003469109 0.02999997 0.06548947 0.002572417 0.02999997 0.06558227 0.001992642 0.04499995 0.06560868 0.001665174 0.02999997 0.06563121 0.001011312 0.04499995 0.06563121 0.001011312 0.02999997 0.05626946 0.009475529 0.02999997 0.05524462 0.009307444 0.04499995 0.05511772 0.009272277 0.02999997 0.05423998 0.009007334 0.02999997 0.05392712 0.008892834 0.04499995 0.05356287 0.00872606 0.02999997 0.05298441 0.008434236 0.02999997 0.0526939 0.008270442 0.04499995 0.05236166 0.008047044 0.02999997 0.05183774 0.007665276 0.02999997 0.05157792 0.007456898 0.04499995 0.05128616 0.007182657 0.02999997 0.05083137 0.006721615 0.02999997 0.05077368 0.006657361 0.04499995 0.05036467 0.006155669 0.02999997 0.04998987 0.005626142 0.02999997 0.05036395 0.006154656 0.04499995 0.04980981 0.005345046 0.04499995 0.04962146 0.004993081 0.02999997 0.04933768 0.004410803 0.02999997 0.04930377 0.004332005 0.04499995 0.04907619 0.003725588 0.02999997 0.04889023 0.003104507 0.02999997 0.04907608 0.003724992 0.04499995 0.04880917 0.002780139 0.04499995 0.04874318 0.002386569 0.02999997 0.04866021 0.001744151 0.02999997 0.0486536 0.001663148 0.04499995 0.04863119 0.001011312 0.02999997 0.04863119 0.001011312 0.04499995 0.04857718 -0.001291155 0.04499995 0.04863119 0.001011312 0.02999997 0.04863119 0.001011312 0.04499995 0.04857718 -0.001291155 0.02999997 0.04517519 -0.008583426 0.04499995 0.04508227 -0.008663773 0.02999997 0.04399716 -0.009471118 0.04499995 0.04389393 -0.009536683 0.02999997 0.04290574 -0.01007533 0.04499995 0.04282736 -0.01011252 0.02999997 0.0420044 -0.01045459 0.04499995 0.04192268 -0.01048398 0.02999997 0.04084861 -0.01080352 0.04499995 0.04072809 -0.01083076 0.02999997 0.03939241 -0.01103109 0.04499995 0.0392701 -0.01104027 0.02999997 0.03834515 -0.01105368 0.04499995 0.03834515 -0.01105368 0.02999997 0.04612857 -0.007626771 0.02999997 0.04620844 -0.007533967 0.04499995 0.04701077 -0.006448328 0.02999997 0.04707664 -0.00634402 0.04499995 0.04771041 -0.005153357 0.02999997 0.0476464 -0.005281329 0.04499995 0.04801547 -0.00437653 0.04499995 0.04814249 -0.003990352 0.02999997 0.04838424 -0.003038942 0.02999997 0.04836064 -0.003175616 0.04499995 0.04853081 -0.002072274 0.02999997 0.04853922 -0.001986086 0.04499995 0.04857718 -0.001291155 0.02999997 0.04857718 -0.001291155 0.04499995 0.03496736 -0.01097434 0.04499995 0.03834515 -0.01105368 0.02999997 0.03834515 -0.01105368 0.04499995 0.03496736 -0.01097434 0.02999997 0.03414589 -0.04596477 0.04499995 0.03414589 -0.04596477 0.037 0.03494948 -0.01173305 0.037 0.03496736 -0.01097434 0.04499995 0.03496736 -0.01097434 0.02999997 0.03495138 -0.01165449 0.03355598 0.03495138 -0.01165467 0.02999997 0.275 -0.02147608 0.02999997 0.283 -0.02147608 0 0.275 -0.02147608 0 0.283 -0.02147608 0.02999997 0.275 -0.02597606 0.02999997 0.275 -0.02647608 0.02999997 0.275 -0.02599799 0.03092098 0.275 -0.02511399 0.02999997 0.275 -0.02147608 0.02999997 0.275 -0.02147608 0 0.275 -0.02647608 0.03134715 0.275 -0.02554398 0.03047198 0.275 -0.02597606 0 0.08439826 -0.009134054 0.06499999 0.07340127 -0.008875906 0.02999997 0.07340127 -0.008875906 0.06499999 0.08439826 -0.009134054 0.02999997 0.08463299 8.63139e-4 0.06499999 0.08439826 -0.009134054 0.02999997 0.08439826 -0.009134054 0.06499999 0.08463299 8.63139e-4 0.02999997 0.07363599 0.001121282 0.06499999 0.08463299 8.63139e-4 0.02999997 0.08463299 8.63139e-4 0.06499999 0.07363599 0.001121282 0.02999997 0.07340127 -0.008875906 0.06499999 0.07363599 0.001121282 0.02999997 0.07363599 0.001121282 0.06499999 0.07340127 -0.008875906 0.02999997 -0.07699996 -0.01372468 0 -0.07699996 -0.01322466 0.03849995 -0.07699996 -0.01372468 0.03849995 -0.07699996 -0.01322466 0 -0.07699996 -0.01372468 0.03849995 -0.07644939 -0.01372468 0.04508948 -0.08099997 -0.01372468 0.04506736 -0.07197409 -0.01372468 0.04508918 -0.06757408 -0.01372468 0.04506629 -0.05899995 -0.01372468 0.03849995 -0.0632494 -0.01372468 0.04502087 -0.05899995 -0.01372468 0.04495298 -0.07699996 -0.01372468 0 -0.08099997 -0.01372468 0 -0.08099997 -0.01372468 0 -0.08099997 -0.009508609 0.04066419 -0.08099997 -0.009906411 0.04122138 -0.08099997 -0.00913316 0.04009699 -0.08099997 -0.006209433 0 -0.08099997 -0.008780121 0.03951954 -0.08099997 -0.008449554 0.0389322 -0.08099997 -0.007591784 0.03709149 -0.08099997 -0.00621289 0.02845692 -0.08099997 -0.007855534 0.03772717 -0.08099997 -0.008141338 0.03833478 -0.08099997 -0.007350623 0.03645169 -0.08099997 -0.007131934 0.03580784 -0.08099997 -0.006482422 0.03319245 -0.08099997 -0.006427466 0.03251719 -0.08099997 -0.006610989 0.03385239 -0.08099997 -0.006935775 0.03516006 -0.08099997 -0.006762087 0.03450816 -0.08099997 -0.006295561 0.03048986 -0.08099997 -0.006354689 0.03150361 -0.08099997 -0.00624746 0.02947568 -0.08099997 -0.01032668 0.04176849 -0.08099997 -0.01075536 0.0422852 -0.08099997 -0.01120299 0.04278677 -0.08099997 -0.01166945 0.04327315 -0.08099997 -0.01215487 0.0437445 -0.08099997 -0.01265925 0.04420059 -0.08099997 -0.01318246 0.04464155 -0.08099997 -0.01372468 0.04506736 -0.1128309 -0.004560053 0.02283155 -0.137205 -0.003983974 0.02101159 -0.137207 -0.003985226 0.02041125 -0.05899995 -0.01372468 0.04495298 -0.03894525 -0.01427006 0.04487186 -0.0632494 -0.01372468 0.04502087 -0.07033514 -0.01372539 0.04509013 -0.03894919 -0.03107416 0.04769426 -0.112843 -0.0345214 0.04839026 -0.03894877 -0.02722465 0.04769426 -0.03894579 -0.01536256 0.0456295 0.02486824 -0.01507991 0.04320681 -0.08099997 -0.01372468 0.04506736 0.02488148 -0.014512 0.04272246 -0.05899995 -0.01324176 0.04455459 -0.03894138 -0.008995115 0.03455197 -0.05899995 -0.007788062 0.03435707 -0.05899995 -0.00769174 0.03342884 -0.03894186 -0.009217679 0.03660279 0.02494955 -0.01161187 0.037 0.02494722 -0.01171243 0.03770124 -0.1271756 -0.01337718 0.04260706 -0.08099997 -0.01318246 0.04464155 -0.112837 -0.01378256 0.04402625 -0.127219 -0.01525145 0.04391157 -0.127204 -0.01461017 0.04349237 -0.112838 -0.01582825 0.04536259 -0.07644939 -0.01372468 0.04508948 -0.01481616 -0.01038658 0.02999997 0.03495138 -0.01165449 0.03355598 -0.02034187 -0.0101279 0.02999997 -0.05900001 -0.007621586 0.03140115 -0.03894084 -0.008988142 0.03126746 0.0248503 -0.01584237 0.0437386 -0.03894627 -0.01656377 0.04629474 -0.127267 -0.01725667 0.04504126 -0.112838 -0.01803225 0.0464797 -0.1272921 -0.01835042 0.04555833 -0.03970551 -0.009038448 0.02999997 -0.02720028 -0.009778559 0.0300002 -0.1272429 -0.01623308 0.04450124 -0.03894674 -0.01789134 0.04685884 -0.112839 -0.02038174 0.04735869 -0.1273328 -0.02007472 0.0462383 0.02483665 -0.01642149 0.04406654 0.02481943 -0.01715791 0.04441899 0.03494948 -0.01173305 0.037 -0.007071316 -0.01071226 0.02999997 0.03495138 -0.01165467 0.02999997 0.02663654 -0.01157855 0.02999997 -0.03894728 -0.01938378 0.04730868 -0.1128399 -0.02286469 0.04798167 -0.127385 -0.02228558 0.04688787 0.01536285 -0.01138645 0.02999997 0.004067718 -0.01109564 0.03000003 -0.1273596 -0.02123129 0.04660749 -0.1128399 -0.0254842 0.04832887 -0.03894776 -0.0211572 0.04761755 -0.127456 -0.02530747 0.04740405 -0.1274262 -0.02404558 0.04724013 -0.05899995 -0.007658004 0.02999997 -0.127161 -0.012766 0.04210954 -0.08100003 -0.01264029 0.04419213 0.02478057 -0.018808 0.04492121 -0.05120515 -0.008252382 0.03000003 -0.1128309 -0.004565775 0.02631628 -0.08099997 -0.006235063 0.02913719 -0.137212 -0.00398916 0.02161157 0.02494364 -0.01186633 0.0383839 -0.05899995 -0.008121907 0.03619664 -0.05899995 -0.007932007 0.03530883 -0.08099997 -0.006213009 0.0284605 -0.03894239 -0.009624838 0.03823685 -0.1372238 -0.00399816 0.01931571 -0.08099997 -0.006212472 0.02507215 -0.05899995 -0.008665502 0.03798466 0.02493685 -0.01215565 0.03927046 -0.05899995 -0.008362472 0.03709298 -0.03894287 -0.01016288 0.03965836 -0.11283 -0.004559457 0.01834827 -0.137224 -0.003997921 0.01380681 -0.05899995 -0.009012162 0.03885328 -0.08099997 -0.006211817 0.0196532 -0.08099997 -0.006211578 0.01761811 -0.137224 -0.003997862 0.01260626 0.02492779 -0.01254105 0.04012507 -0.05899995 -0.009414315 0.03969478 -0.112829 -0.00455892 0.01303589 -0.137223 -0.003997564 0.005402505 -0.112829 -0.004558384 0.00793153 -0.03894335 -0.01080816 0.04092478 0.02491986 -0.0128799 0.04073929 -0.137224 -0.003997743 0.009604871 -0.1372229 -0.003997862 0.008408129 -0.08099997 -0.006210803 0.01151877 -0.05899995 -0.009860992 0.04051637 -0.05899995 -0.01051223 0.0415371 -0.03894388 -0.01154607 0.04206377 0.02490466 -0.0135281 0.04167217 -0.05899995 -0.0110929 0.04231494 0.02489358 -0.01399695 0.0422123 -0.03894436 -0.01236879 0.0430935 -0.05899995 -0.01168912 0.04303258 -0.05899995 -0.0125271 0.04390847 -0.03894478 -0.01327484 0.04402685 0.02480095 -0.01794439 0.04470199 -0.1275089 -0.02759617 0.04756474 -0.112841 -0.02833837 0.04839026 -0.127581 -0.03065735 0.04757499 0.02467775 -0.02319204 0.04510462 -0.03894966 -0.03534829 0.04769426 -0.112843 -0.03776568 0.04839026 0.02441471 -0.0343945 0.04511344 -0.127743 -0.03756237 0.04756373 -0.127725 -0.03679597 0.04756504 -0.112844 -0.04109275 0.04839026 -0.127797 -0.03986197 0.04755997 -0.127851 -0.04216158 0.04755616 -0.0389502 -0.04001706 0.04769426 -0.115684 -0.04244714 0.04790598 -0.1217679 -0.04230439 0.0477429 -0.103519 -0.04273277 0.04816108 -0.109601 -0.04258996 0.04804527 -0.09743648 -0.04287558 0.04825305 -0.08879756 -0.04307842 0.04834592 -0.07668823 -0.04336267 0.04839193 -0.06430238 -0.04365348 0.04834169 0.0242365 -0.0419867 0.04511922 -0.0520507 -0.04394108 0.04819536 -0.0397166 -0.04423069 0.04795086 -0.02520352 -0.04457122 0.04754006 0.02422547 -0.04245555 0.0451197 -0.01839256 -0.04473125 0.04729515 0.0242145 -0.04292339 0.04512 -0.01231437 -0.04487395 0.04705578 -0.006236493 -0.0450167 0.04679268 0.02420347 -0.04339116 0.04512035 0.02419257 -0.043859 0.04512065 -1.58877e-4 -0.04515939 0.04650586 0.02418148 -0.04432696 0.0451194 0.009467542 -0.04538536 0.04600858 0.02414882 -0.04573023 0.04512619 -0.127653 -0.03372889 0.0475701 -0.112842 -0.03137439 0.04839026 -0.148954 -0.008840441 0.03516125 -0.134669 -0.008715927 0.037 -0.1370739 -0.008932709 0.037 -0.03894829 -0.02381908 0.04769426 0.02473741 -0.02064836 0.04511189 -0.1274851 -0.02659046 0.04752939 0.0247581 -0.01977014 0.04506611 -0.112836 -0.01190495 0.04248696 -0.08099997 -0.01166945 0.04327315 -0.1271345 -0.01162666 0.0411117 -0.1271086 -0.01052814 0.04000562 -0.08099997 -0.01120299 0.04278677 -0.1270855 -0.00954163 0.03888255 -0.112836 -0.01020199 0.04075378 -0.1270734 -0.009033501 0.03823995 -0.08099997 -0.01034194 0.04179567 -0.112835 -0.008680522 0.03882879 -0.08099997 -0.009906411 0.04122138 -0.08099997 -0.00913316 0.04009699 -0.08099997 -0.009508609 0.04066419 -0.127053 -0.008151113 0.037 -0.1496199 -0.007950723 0.03373789 -0.1499339 -0.007531523 0.03299999 -0.146925 -0.007240295 0.03299999 -0.112834 -0.007355451 0.03671115 -0.149294 -0.008387029 0.03445827 -0.1439099 -0.006977021 0.03299999 -0.08099997 -0.008608937 0.03922784 -0.129658 -0.008325159 0.037 -0.08099997 -0.008141338 0.03833478 -0.140561 -0.006495296 0.03255856 -0.140244 -0.006258785 0.03210514 -0.139942 -0.006032168 0.03163975 -0.112833 -0.006249308 0.03440058 -0.08099997 -0.007751107 0.03749239 -0.139652 -0.005815386 0.03116238 -0.132197 -0.008513391 0.037 -0.08099997 -0.007350623 0.03645169 -0.139113 -0.005411624 0.03017145 -0.1370899 -0.009625315 0.03788036 -0.148602 -0.00931096 0.03584688 -0.148237 -0.009798526 0.03651499 -0.1375099 -0.02750319 0.04675167 -0.172776 -0.02826207 0.04199999 -0.1726379 -0.02795755 0.04199999 -0.1374732 -0.02596616 0.0466302 -0.172995 -0.02889388 0.04199999 -0.172897 -0.02857476 0.04199999 -0.173071 -0.02922016 0.04199999 -0.173124 -0.02955037 0.04199999 -0.1375359 -0.02862548 0.04678249 -0.1731637 -0.03050369 0.04199999 -0.173151 -0.02988386 0.04199999 -0.1731539 -0.03088897 0.04199999 -0.137589 -0.03087389 0.04676955 -0.176279 -0.03322768 0.04146897 -0.1376514 -0.03353881 0.04675614 -0.179525 -0.03565686 0.04090368 -0.182892 -0.03817689 0.040304 -0.1377025 -0.03570109 0.04674673 -0.1377747 -0.03879046 0.04674029 -0.18638 -0.04078745 0.03966999 -0.182669 -0.0408746 0.04036676 -0.178954 -0.0409618 0.04103797 -0.137793 -0.03957486 0.0467385 -0.175235 -0.04104906 0.04168355 -0.171513 -0.0411365 0.04230356 -0.137812 -0.0403589 0.04673677 -0.167787 -0.041224 0.04289805 -0.164058 -0.0413115 0.04346698 -0.160324 -0.04139918 0.0440104 -0.13783 -0.04114288 0.04673504 -0.156588 -0.04148685 0.04452806 -0.1517235 -0.041601 0.04516595 -0.1437422 -0.04178845 0.04611378 -0.137849 -0.04192686 0.04673337 -0.172482 -0.0276615 0.04199999 -0.172311 -0.02737379 0.04199999 -0.172127 -0.0270949 0.04199999 -0.171929 -0.02682489 0.04199999 -0.171723 -0.02656227 0.04199999 -0.171505 -0.02630716 0.04199999 -0.171281 -0.02605926 0.04199999 -0.137444 -0.02468359 0.04645836 -0.170808 -0.02558547 0.04199999 -0.171048 -0.025819 0.04199999 -0.137426 -0.0239104 0.04632318 -0.170563 -0.02535825 0.04199999 -0.170312 -0.02513736 0.04199999 -0.170056 -0.02492195 0.04199999 -0.169645 -0.0245943 0.0419991 -0.137408 -0.02314376 0.04616379 -0.1691447 -0.02422237 0.04199999 -0.168716 -0.02392226 0.04199999 -0.1683117 -0.02365249 0.04199999 -0.13739 -0.02238374 0.04598039 -0.1677452 -0.02329462 0.04199999 -0.1671447 -0.02293664 0.04199922 -0.137372 -0.02162635 0.04577136 -0.1667219 -0.022695 0.04199999 -0.1662598 -0.02244061 0.04199999 -0.1656945 -0.02214229 0.04199928 -0.137354 -0.02087336 0.04553759 -0.1651158 -0.02184849 0.04199999 -0.1644928 -0.0215457 0.04199999 -0.137337 -0.02013087 0.04528105 -0.1638867 -0.02126264 0.04199934 -0.1631059 -0.02091199 0.04199999 -0.162301 -0.02056741 0.04200041 -0.1615645 -0.02026438 0.04199999 -0.13732 -0.01939898 0.0450018 -0.1371291 -0.01127433 0.03968393 -0.147825 -0.01193225 0.03884005 -0.1470659 -0.01136398 0.03841465 -0.1371676 -0.01291966 0.04116678 -0.1371989 -0.01427471 0.04220664 -0.150137 -0.01366245 0.03997796 -0.1608354 -0.01997607 0.04199999 -0.150919 -0.01424747 0.04031127 -0.1601837 -0.01972603 0.04200059 -0.137148 -0.01210826 0.04046428 -0.14859 -0.01250487 0.03924238 -0.151706 -0.01483678 0.04062145 -0.1373029 -0.01867765 0.04469984 -0.1593461 -0.01941615 0.04199999 -0.149361 -0.01308155 0.03962165 -0.1583939 -0.01907783 0.04199999 -0.152499 -0.01543015 0.04090875 -0.1573264 -0.01871448 0.04199957 -0.1372318 -0.01565814 0.0431236 -0.137286 -0.017964 0.04437375 -0.156547 -0.01845979 0.04199999 -0.155726 -0.01784557 0.04182779 -0.1372624 -0.01697599 0.04387867 -0.154911 -0.01723539 0.04163259 -0.153297 -0.01602774 0.0411731 -0.154101 -0.01662945 0.04141426 -0.147469 -0.01082509 0.03779888 -0.1478599 -0.01030325 0.0371657 -0.137109 -0.01044255 0.03881365 -0.112833 -0.00539112 0.03190028 -0.138863 -0.005224585 0.02965807 -0.138409 -0.004884779 0.02859818 -0.138626 -0.00504738 0.0291326 -0.08099997 -0.007027089 0.03548139 -0.08099997 -0.006762087 0.03450816 -0.138208 -0.004734873 0.02805358 -0.138024 -0.004597127 0.02749836 -0.137856 -0.004471421 0.02693265 -0.08099997 -0.006610989 0.03385239 -0.137709 -0.004361331 0.0263617 -0.112832 -0.004815816 0.02921366 -0.08099997 -0.006478965 0.03317338 -0.137383 -0.004116952 0.02460598 -0.08099997 -0.006378054 0.03184169 -0.137582 -0.004265964 0.02578419 -0.137313 -0.00406444 0.02401196 -0.137262 -0.00402683 0.02341628 -0.08099997 -0.006328821 0.03115594 -0.1372294 -0.004002094 0.02275562 -0.137224 -0.003998339 0.0180093 -0.137224 -0.003998041 0.01680868 -0.08099997 -0.006212234 0.02371704 -0.08099997 -0.006210982 0.01287317 -0.08099997 -0.006210327 0.007453918 -0.137223 -0.003997504 0.004201769 -0.08099997 -0.006210148 0.006098687 -0.112828 -0.004557788 0.003542363 -0.137223 -0.003997385 0.001800239 -0.08099997 -0.006209671 0.002710521 -0.08915656 -0.005687355 0 -0.08099997 -0.006209373 6.77632e-4 -0.08099997 -0.006209492 0.00135523 -0.137223 -0.003997385 0.001200079 -0.09850734 -0.005171775 4.94869e-7 -0.1093158 -0.004701972 -1.54882e-6 -0.1182633 -0.004391372 -1.19708e-6 -0.137223 -0.003997325 6.00012e-4 -0.1290121 -0.004117667 0 -0.137223 -0.003997266 0 -0.08099997 -0.006209254 0 -0.137473 -0.004184484 0.02519899 -0.139376 -0.005608558 0.03067284 -0.127402 -0.02303087 0.04705774 -0.14089 -0.006741702 0.03299999 -0.1686907 -0.0185483 0.01250618 -0.1566646 -0.0185483 0.01250314 -0.1550945 -0.01737248 0.01244962 -0.1672019 -0.01743441 0.0124526 -0.1658987 -0.01645886 0.01232665 -0.153666 -0.01630365 0.01229935 -0.1527568 -0.01562303 0.01215368 -0.1646785 -0.01554554 0.01213669 -0.1511021 -0.01438492 0.01178711 -0.1519205 -0.01499772 0.01198589 -0.1635125 -0.01467299 0.01188689 -0.1625205 -0.01393067 0.01161712 -0.1502772 -0.0137673 0.01155018 -0.1615883 -0.01323318 0.01131612 -0.16071 -0.01257562 0.01098233 -0.1490577 -0.01285433 0.01112854 -0.1496469 -0.01329565 0.01134276 -0.1478705 -0.01196604 0.01062738 -0.1599425 -0.01200133 0.01065039 -0.148449 -0.01239937 0.01088267 -0.1584809 -0.01090723 0.009895145 -0.1467042 -0.01109308 0.01003438 -0.1592155 -0.01145696 0.01029533 -0.147275 -0.0115208 0.01033669 -0.1577889 -0.0103892 0.009471833 -0.1459081 -0.01049786 0.009563267 -0.145026 -0.00983715 0.008962988 -0.1568108 -0.009656786 0.008788824 -0.144667 -0.00956887 0.008694648 -0.145389 -0.01010894 0.009220063 -0.1572909 -0.01001626 0.009136915 -0.14397 -0.009047091 0.008120536 -0.15628 -0.009260177 0.008366882 -0.155954 -0.009016036 0.008088588 -0.144315 -0.009305059 0.008414208 -0.142979 -0.008305668 0.007162749 -0.1432999 -0.008545458 0.007496058 -0.155019 -0.008315861 0.007182598 -0.155636 -0.008777797 0.007798254 -0.1436319 -0.00879389 0.007814466 -0.154159 -0.007672786 0.006165921 -0.142365 -0.00784558 0.006455659 -0.154437 -0.007880866 0.006517291 -0.154723 -0.00809437 0.006856381 -0.142668 -0.008072376 0.006815969 -0.153638 -0.007282555 0.005424082 -0.153401 -0.00710541 0.005032539 -0.141533 -0.007223427 0.005286693 -0.142074 -0.007628202 0.006080806 -0.153891 -0.00747168 0.005801856 -0.141798 -0.007421314 0.005690932 -0.153178 -0.006938397 0.004623353 -0.141283 -0.007035613 0.004867911 -0.141053 -0.006863534 0.004434525 -0.152972 -0.006784379 0.004202604 -0.152785 -0.00664395 0.003771543 -0.140839 -0.006703734 0.003986597 -0.152621 -0.006521701 0.003326773 -0.140642 -0.006556212 0.003524184 -0.1404999 -0.006450831 0.003044962 -0.152226 -0.006227195 0.001932561 -0.14023 -0.006247699 0.002049088 -0.140128 -0.006171226 0.001546859 -0.1521434 -0.006164073 0.001457035 -0.139963 -0.006048381 0 -0.151989 -0.006048381 0 -0.1553249 -0.008545339 0.00749588 -0.06999999 -0.005724668 0.02999997 -0.05899995 -0.005724668 0.02999997 -0.05899995 -0.005724668 0 -0.06999999 -0.005724668 0 -0.05899995 -0.01277655 0.04413968 -0.05899995 -0.01322466 0.03849995 -0.05899995 -0.0123291 0.04370826 -0.05899995 -0.01324176 0.04455459 -0.05899995 -0.01372468 0.03849995 -0.05899995 -0.01372468 0.04495298 -0.05899995 -0.01189929 0.04326039 -0.05899995 -0.0114873 0.04279595 -0.05899995 -0.0110929 0.04231494 -0.05899995 -0.01071619 0.04181748 -0.05899995 -0.01035869 0.04130506 -0.05899995 -0.008665502 0.03798466 -0.05899995 -0.008892476 0.03856438 -0.05899995 -0.007658004 0.02999997 -0.05899995 -0.00970906 0.04024529 -0.05899995 -0.01002389 0.04078209 -0.05899995 -0.007627546 0.03125137 -0.05899995 -0.007633328 0.03187495 -0.05899995 -0.007635712 0.03062635 -0.05899995 -0.007987976 0.03558838 -0.05899995 -0.008121907 0.03619664 -0.05899995 -0.007720291 0.03374028 -0.05899995 -0.00765109 0.03249758 -0.05899995 -0.007674634 0.03312045 -0.05899995 -0.007788062 0.03435707 -0.05899995 -0.007877349 0.03497296 -0.05899995 -0.008279085 0.03679776 -0.05899995 -0.008460521 0.0373944 -0.05899995 -0.009141504 0.03913348 -0.05899995 -0.009414315 0.03969478 -0.05899995 -0.01322466 0 -0.05899995 -0.005724668 0 -0.05899995 -0.005724668 0.02999997 -0.07699996 -0.01322466 0.03849995 -0.05899995 -0.01322466 0 -0.05899995 -0.01322466 0.03849995 -0.07699996 -0.01322466 0 -0.155607 -0.008755922 0.007768094 -0.151383 -0.005595147 0.04199999 -0.155327 -0.008546888 0.007495403 -0.185295 -0.0309754 0.001328289 -0.185346 -0.0310139 8.91371e-4 -0.188 -0.03299999 0 -0.185379 -0.03103828 4.48597e-4 -0.185135 -0.03085577 0.002184748 -0.1852239 -0.03092265 0.001759409 -0.184899 -0.0306794 0.003017842 -0.185027 -0.03077465 0.002604186 -0.184592 -0.03044909 0.003824055 -0.184753 -0.03056985 0.003425717 -0.1842319 -0.03017967 0.004584848 -0.184419 -0.03032004 0.00420916 -0.183812 -0.02986598 0.005307495 -0.184029 -0.03002798 0.004951059 -0.188 -0.03299999 0.04199999 -0.183591 -0.02969986 0.005651533 -0.183358 -0.02952557 0.005984961 -0.1831139 -0.02934288 0.00630778 -0.182858 -0.02915185 0.006619989 -0.182599 -0.0289579 0.006922364 -0.181777 -0.02834248 0.007768452 -0.182059 -0.02855348 0.007496654 -0.1823329 -0.02875858 0.007214665 -0.18149 -0.02812778 0.008031129 -0.1812 -0.02791035 0.008284926 -0.180903 -0.02768868 0.008529305 -0.180602 -0.02746289 0.008764207 -0.180295 -0.02723348 0.008990287 -0.179987 -0.02700257 0.009208798 -0.179674 -0.02676868 0.009418725 -0.1793569 -0.02653169 0.00962007 -0.179037 -0.02629166 0.009812772 -0.178715 -0.0260508 0.009998977 -0.17839 -0.02580767 0.01017737 -0.178062 -0.0255624 0.0103479 -0.177732 -0.02531486 0.01051068 -0.177399 -0.02506619 0.01066678 -0.177065 -0.02481615 0.01081609 -0.176729 -0.0245645 0.01095819 -0.176391 -0.02431118 0.01109319 -0.1758794 -0.02392864 0.01128441 -0.1753669 -0.02354496 0.01145905 -0.175023 -0.02328729 0.01156789 -0.1744906 -0.02288937 0.01172357 -0.1738084 -0.02237862 0.01190066 -0.1730989 -0.0218479 0.01205807 -0.1724012 -0.02132546 0.01218932 -0.1716975 -0.02079886 0.01229709 -0.171173 -0.02040606 0.01236176 -0.170648 -0.02001339 0.01241511 -0.1699334 -0.01947849 0.01246631 -0.169401 -0.01907998 0.0124889 -0.1688784 -0.01868867 0.01249992 -0.1681546 -0.0181477 0.01249462 -0.1674492 -0.01761931 0.01246649 -0.166917 -0.01722085 0.01242947 -0.1663843 -0.01682245 0.01238065 -0.1653268 -0.0160306 0.01224339 -0.165856 -0.01642668 0.01231789 -0.1646236 -0.01550453 0.0121231 -0.1639358 -0.01499003 0.0119825 -0.1632272 -0.01445937 0.01181167 -0.162705 -0.01406878 0.0116688 -0.1621904 -0.01368343 0.01151412 -0.161332 -0.01304066 0.01122039 -0.161673 -0.01329636 0.01134186 -0.160654 -0.01253348 0.01095658 -0.160992 -0.01278626 0.01109194 -0.159983 -0.01203137 0.01066589 -0.160318 -0.01228177 0.01081454 -0.159321 -0.01153558 0.01034659 -0.15965 -0.01178234 0.01051014 -0.158668 -0.01104694 0.009997904 -0.158993 -0.01129049 0.01017588 -0.158026 -0.01056647 0.009618759 -0.158345 -0.01080507 0.009812772 -0.157397 -0.01009589 0.009207308 -0.15771 -0.01032996 0.009416937 -0.156782 -0.009635627 0.008763134 -0.157087 -0.009863913 0.00898981 -0.156185 -0.009189128 0.008283257 -0.156482 -0.009410858 0.008527517 -0.155893 -0.008970379 0.008030414 -0.155054 -0.008342087 0.007213294 -0.154786 -0.008141517 0.006921648 -0.154524 -0.007945716 0.006620347 -0.154274 -0.007758259 0.006307482 -0.154031 -0.007576763 0.005984425 -0.153796 -0.007401227 0.005651056 -0.1535699 -0.007231533 0.005307435 -0.153358 -0.007073044 0.004952967 -0.153158 -0.006923556 0.004587948 -0.15297 -0.006782352 0.004212379 -0.152792 -0.006649494 0.00382632 -0.152631 -0.006529092 0.003431141 -0.152489 -0.00642246 0.003027319 -0.151383 -0.005595147 0 -0.152361 -0.006327211 0.002614021 -0.152249 -0.006243288 0.002191245 -0.152155 -0.006172597 0.001761317 -0.152085 -0.006120085 0.001329898 -0.152034 -0.006081879 8.92581e-4 -0.152002 -0.006057977 4.49268e-4 -0.151989 -0.006048381 0 -0.185392 -0.03104835 0 -0.168065 -0.02708047 0.009136915 -0.1685466 -0.02744102 0.008787691 -0.18033 -0.02725964 0.008962988 -0.180689 -0.02752786 0.008694648 -0.179967 -0.02698779 0.009220063 -0.1786462 -0.02599954 0.01003748 -0.1661455 -0.02564358 0.01029276 -0.166871 -0.02618652 0.00989753 -0.179447 -0.02659821 0.009563803 -0.1675664 -0.02670711 0.009472191 -0.178081 -0.02557605 0.01033669 -0.1774862 -0.02513128 0.01062703 -0.16556 -0.02520507 0.01058095 -0.165012 -0.02479505 0.01082885 -0.176907 -0.02469736 0.01088267 -0.1762952 -0.02424019 0.01112967 -0.1643086 -0.02426898 0.0111162 -0.1635441 -0.02369648 0.0113914 -0.175709 -0.02380114 0.01134276 -0.1750793 -0.02332979 0.01155 -0.1628346 -0.02316552 0.01161736 -0.1742424 -0.02270334 0.01179009 -0.1618528 -0.02243077 0.01188462 -0.1734452 -0.0221064 0.01198375 -0.1606917 -0.02156198 0.01213407 -0.1725885 -0.02146577 0.01215565 -0.1716982 -0.02079927 0.01229828 -0.1594471 -0.02063035 0.0123279 -0.1702663 -0.01972788 0.01244932 -0.158155 -0.01966303 0.01245248 -0.1566652 -0.01854842 0.01250618 -0.1686913 -0.01854842 0.01250314 -0.169076 -0.02783656 0.008366882 -0.181041 -0.02779167 0.008414208 -0.1813859 -0.02804964 0.008120536 -0.169402 -0.0280807 0.008088588 -0.1697199 -0.028319 0.007798254 -0.181724 -0.02830284 0.007814466 -0.170031 -0.02855145 0.00749588 -0.182056 -0.02855128 0.007496058 -0.170337 -0.02878087 0.007182598 -0.182376 -0.02879106 0.007162749 -0.170633 -0.02900236 0.006856381 -0.1826879 -0.02902436 0.006815969 -0.182991 -0.02925115 0.006455659 -0.170919 -0.02921587 0.00651735 -0.1711969 -0.02942395 0.006165921 -0.183282 -0.02946859 0.006080806 -0.171465 -0.02962505 0.005801856 -0.183558 -0.02967548 0.005690932 -0.183822 -0.02987337 0.005286693 -0.171718 -0.02981418 0.005424082 -0.171955 -0.02999138 0.005032539 -0.184073 -0.03006118 0.004867911 -0.172178 -0.0301584 0.004623353 -0.184303 -0.0302332 0.004434525 -0.184517 -0.030393 0.003986597 -0.172384 -0.03031235 0.004202604 -0.172571 -0.03045284 0.003771543 -0.184714 -0.03054058 0.003524124 -0.172735 -0.03057509 0.003326773 -0.184858 -0.03064864 0.003035366 -0.1851258 -0.03084969 0.002049684 -0.17313 -0.0308696 0.001932382 -0.185228 -0.03092557 0.001546919 -0.1853926 -0.03104841 0 -0.1732126 -0.03093272 0.001457214 -0.173367 -0.03104835 0 -0.18638 -0.04078745 0.037 -0.176279 -0.03322768 0.04146897 -0.179525 -0.03565686 0.04090368 -0.182892 -0.03817689 0.040304 -0.18638 -0.04078745 0.03966999 -0.188 -0.04199999 0.037 -0.170302 -0.02875465 0.007213294 -0.137224 -0.0039981 0.01930278 -0.1508767 -0.0142163 0.01172691 -0.154911 -0.01723539 0.04163259 -0.1470659 -0.01136398 0.03299999 -0.154101 -0.01662945 0.04141426 -0.155726 -0.01784557 0.04182779 -0.153297 -0.01602774 0.0411731 -0.152499 -0.01543015 0.04090875 -0.151706 -0.01483678 0.04062145 -0.150919 -0.01424747 0.04031127 -0.150137 -0.01366245 0.03997796 -0.149361 -0.01308155 0.03962165 -0.14859 -0.01250487 0.03924238 -0.147825 -0.01193225 0.03884005 -0.1470659 -0.01136398 0.03841465 -0.1731539 -0.03088897 0.04199999 -0.156547 -0.01845979 0.04199999 -0.140561 -0.006495296 0.03255856 -0.14089 -0.006741702 0.03299999 -0.148627 -0.01253229 0.01095819 -0.148965 -0.01278555 0.01109319 -0.140244 -0.006258785 0.03210514 -0.139942 -0.006032168 0.03163975 -0.139652 -0.005815386 0.03116238 -0.139376 -0.005608558 0.03067284 -0.139113 -0.005411624 0.03017145 -0.138863 -0.005224585 0.02965807 -0.138626 -0.00504738 0.0291326 -0.138409 -0.004884779 0.02859818 -0.138208 -0.004734873 0.02805358 -0.138024 -0.004597127 0.02749836 -0.137856 -0.004471421 0.02693265 -0.137709 -0.004361331 0.0263617 -0.137582 -0.004265964 0.02578419 -0.137473 -0.004184484 0.02519899 -0.137383 -0.004116952 0.02460598 -0.137313 -0.00406444 0.02401196 -0.137262 -0.00402683 0.02341628 -0.1372183 -0.003994166 0.02212059 -0.1522476 -0.01524245 0.01205629 -0.148291 -0.01228058 0.01081609 -0.1494886 -0.01317751 0.01128894 -0.147624 -0.01178187 0.01051068 -0.147294 -0.01153439 0.0103479 -0.147957 -0.0120306 0.01066678 -0.145998 -0.0105651 0.00962007 -0.146641 -0.01104599 0.009998977 -0.1447539 -0.009633958 0.008764266 -0.145061 -0.009863257 0.008990287 -0.145682 -0.01032805 0.009418725 -0.1453689 -0.01009416 0.009208798 -0.144156 -0.009186387 0.008284926 -0.144452 -0.009408056 0.008529305 -0.143297 -0.008543312 0.007496714 -0.143579 -0.008754312 0.007768452 -0.142497 -0.007944881 0.006619989 -0.1372234 -0.003997683 0.009224951 -0.143023 -0.008338153 0.007214665 -0.1427569 -0.008138895 0.006922364 -0.1419979 -0.00757122 0.005984961 -0.142242 -0.007753908 0.00630778 -0.141543 -0.007230818 0.005307495 -0.1417649 -0.007396876 0.005651533 -0.140937 -0.00677675 0.00420916 -0.137223 -0.003997266 0 -0.141124 -0.006917119 0.004584848 -0.141327 -0.007068753 0.004951059 -0.1407639 -0.006647706 0.003824114 -0.140603 -0.006526887 0.003425717 -0.140457 -0.006417393 0.003017902 -0.140329 -0.006322145 0.002604246 -0.1401309 -0.006174087 0.001759409 -0.1402209 -0.006241023 0.002184748 -0.140061 -0.006121397 0.001328289 -0.1400099 -0.006082832 8.91373e-4 -0.139977 -0.006058514 4.48598e-4 -0.139963 -0.006048381 0 -0.167959 -0.0270009 0.009207308 -0.168269 -0.02723288 0.00898981 -0.1571996 -0.01894813 0.01249462 -0.1564775 -0.018408 0.01249992 -0.143866 -0.008968949 0.008031129 -0.146319 -0.01080507 0.009812772 -0.146966 -0.01128906 0.01017737 -0.149989 -0.01355177 0.01145905 -0.150333 -0.0138095 0.01156795 -0.137207 -0.003985226 0.02041125 -0.137205 -0.003983974 0.02101159 -0.1515478 -0.01471817 0.01190066 -0.1529552 -0.01577162 0.01218938 -0.137232 -0.004003822 0.02281677 -0.153658 -0.01629757 0.01229703 -0.154183 -0.01669067 0.01236176 -0.1547082 -0.0170837 0.01241511 -0.1554226 -0.01761829 0.01246631 -0.155955 -0.01801675 0.0124889 -0.1579062 -0.01947718 0.01246654 -0.1589714 -0.02027422 0.01238065 -0.158439 -0.01987588 0.01242947 -0.1595 -0.02067005 0.01231789 -0.1600291 -0.021066 0.01224344 -0.1607346 -0.02159386 0.01212269 -0.161428 -0.02211308 0.01198065 -0.1621294 -0.02263802 0.01181149 -0.162651 -0.02302795 0.0116688 -0.1631666 -0.02341413 0.01151376 -0.1638638 -0.02393591 0.01127922 -0.164364 -0.02431046 0.01109194 -0.1647019 -0.02456325 0.01095658 -0.165373 -0.02506548 0.01066589 -0.165038 -0.02481496 0.01081454 -0.1660349 -0.02556115 0.01034659 -0.165706 -0.02531439 0.01051014 -0.166688 -0.02604979 0.009997904 -0.166363 -0.02580624 0.01017588 -0.16733 -0.02653038 0.009618759 -0.167011 -0.02629166 0.009812772 -0.167646 -0.02676677 0.009416937 -0.168874 -0.02768588 0.008527517 -0.168574 -0.02746117 0.008763134 -0.169463 -0.02812635 0.008030414 -0.169171 -0.02790766 0.008283257 -0.170029 -0.02854984 0.007495403 -0.169749 -0.02834087 0.007768154 -0.188 -0.04199999 0 -0.17057 -0.02895528 0.006921648 -0.170832 -0.02915108 0.006620347 -0.171082 -0.02933847 0.006307542 -0.171325 -0.02951997 0.005984425 -0.171559 -0.02969557 0.005651056 -0.171786 -0.0298652 0.005307435 -0.171998 -0.03002369 0.004952967 -0.1721979 -0.03017318 0.004587948 -0.172386 -0.03031438 0.004212379 -0.172564 -0.0304473 0.00382632 -0.172725 -0.0305677 0.003431141 -0.172867 -0.03067427 0.003027319 -0.172995 -0.03076958 0.002614021 -0.173107 -0.03085345 0.002191305 -0.173201 -0.0309242 0.001761317 -0.173271 -0.03097665 0.001329898 -0.173322 -0.03101485 8.92583e-4 -0.173354 -0.03103876 4.49269e-4 -0.173367 -0.03104835 0 -0.2163903 -0.04199999 0.03405684 -0.188 -0.04199999 0 -0.188 -0.04199999 0.037 -0.2005757 -0.04199999 0.037 -0.2057305 -0.04199999 0.03602266 -0.2104817 -0.04199999 0.03513395 -0.2137384 -0.04199999 0.03453588 -0.2201569 -0.04199999 0.0333932 -0.2233408 -0.04199999 0.03285127 -0.2258996 -0.04199999 0.03243076 -0.2292683 -0.04199999 0.03189605 -0.2316722 -0.04199999 0.03153306 -0.233673 -0.04199999 0.03124165 -0.2356619 -0.04199999 0.03096461 -0.2374035 -0.04199999 0.03073048 -0.2388969 -0.04199999 0.03053778 -0.2405959 -0.04199999 0.03032833 -0.2422968 -0.04199999 0.03012746 -0.2438294 -0.04199999 0.02995568 -0.2457945 -0.04199999 0.02974849 -0.247349 -0.04199999 0.02959668 -0.2503849 -0.04199999 0.02933144 -0.286063 -0.04199999 0.01822435 -0.2486552 -0.04199999 0.02947819 -0.283639 -0.04199999 0.02044665 -0.2540311 -0.04199999 0.02905768 -0.283009 -0.04199999 0.02097928 -0.284868 -0.04199999 0.01935964 -0.2524617 -0.04199999 0.02916806 -0.284258 -0.04199999 0.0199092 -0.2556271 -0.04199999 0.02895873 -0.281723 -0.04199999 0.02201396 -0.28237 -0.04199999 0.02150595 -0.2574932 -0.04199999 0.02885937 -0.280409 -0.04199999 0.02297335 -0.281069 -0.04199999 0.02250307 -0.2594168 -0.04199999 0.028746 -0.278413 -0.04199999 0.02427577 -0.27908 -0.04199999 0.02385956 -0.279742 -0.04199999 0.0234248 -0.2634801 -0.04199999 0.0284698 -0.276325 -0.04199999 0.02540355 -0.277036 -0.04199999 0.02504777 -0.277732 -0.04199999 0.02467185 -0.274065 -0.04199999 0.02634966 -0.274838 -0.04199999 0.0260545 -0.2650156 -0.04199999 0.02832037 -0.2756 -0.04199999 0.02573907 -0.273289 -0.04199999 0.02662467 -0.269335 -0.04199999 0.02766817 -0.27251 -0.04199999 0.02687954 -0.268537 -0.04199999 0.02781927 -0.261498 -0.04199999 0.0286265 -0.26229 -0.04199999 0.02857124 -0.270137 -0.04199999 0.0275048 -0.271728 -0.04199999 0.02711439 -0.267742 -0.04199999 0.02795797 -0.266951 -0.04199999 0.02808427 -0.266167 -0.04199999 0.02819406 -0.270942 -0.04199999 0.02732896 -0.28547 -0.04199999 0.01879805 -0.286648 -0.04199999 0.01763868 -0.287226 -0.04199999 0.01705098 -0.2901943 -0.04199999 0.009850382 -0.287796 -0.04199999 0.0164572 -0.288359 -0.04199999 0.01585525 -0.288914 -0.04199999 0.01524507 -0.2899998 -0.04199999 0.01400023 -0.289461 -0.04199999 0.01462668 -0.2905004 -0.04199999 0.006729483 -0.29029 -0.04199999 0.007806718 -0.290725 -0.04199999 0.005660295 -0.2909824 -0.04199999 0.004507482 -0.2913025 -0.04199999 0.003172457 -0.2918813 -0.04199999 9.71552e-4 -0.291574 -0.04199999 0.002111792 -0.292158 -0.04199999 0 -0.2905223 -0.04681503 0.002836287 -0.2907661 -0.04525452 0.003164649 -0.2909473 -0.0468682 0.001254618 -0.2911364 -0.04766142 0 -0.2908755 -0.04872494 -1.98538e-7 -0.2921581 -0.04200029 -9.13883e-7 -0.2918895 -0.04385042 0 -0.2906582 -0.04956358 6.62292e-7 -0.2908282 -0.04423433 0.003661334 -0.2914993 -0.0439102 0.001338839 -0.2915197 -0.04297906 0.001800179 -0.2909852 -0.04297721 0.003885984 -0.2903772 -0.04380333 0.005945205 -0.2906692 -0.04199987 0.005899369 -0.290289 -0.04199981 0.00780642 -0.2914727 -0.04612451 0 -0.2912333 -0.0453571 0.00135678 -0.291681 -0.04504877 0 -0.2911339 -0.04199999 0.003862202 -0.2915645 -0.04200005 0.002142488 -0.2904947 -0.05555176 0.001727044 -0.2899991 -0.04669821 0.01282745 -0.2899997 -0.04535073 0.01342183 -0.29 -0.04580819 0.01324629 -0.2904819 -0.05376058 0.002818703 -0.2905428 -0.05666178 8.77967e-4 -0.2905557 -0.05443388 0.001619398 -0.2906562 -0.04956316 0 -0.2904061 -0.0531556 0.00402683 -0.290416 -0.0543918 0.003046393 -0.2904682 -0.05601513 0.00143665 -0.290502 -0.05640047 0.001113712 -0.290463 -0.05651509 9.19227e-4 -0.290502 -0.05689126 7.35381e-4 -0.2904478 -0.05727231 0 -0.2904491 -0.05677807 5.49549e-4 -0.290502 -0.05739957 3.66971e-4 -0.2902525 -0.053258 0.004849135 -0.2903202 -0.05444389 0.003107726 -0.2903366 -0.05399245 0.003769636 -0.2902435 -0.05388468 0.003665804 -0.2902823 -0.05413776 0.003445923 -0.2903729 -0.05575084 0.001143217 -0.2903478 -0.05609118 0 -0.29 -0.04488527 0.0135743 -0.290193 -0.05206108 0.006588757 -0.2901406 -0.05165934 0.00728476 -0.2901701 -0.05258053 0.005857348 -0.29 -0.04297375 0.01395207 -0.2899998 -0.043935 0.01381027 -0.2899998 -0.04199999 0.01399993 -0.2901388 -0.05079245 0.008303046 -0.2900004 -0.04794919 0.01203751 -0.290256 -0.05268895 0.005574345 -0.290295 -0.05499458 0.001374542 -0.2902346 -0.05475091 0 -0.2901915 -0.05377322 0.002882659 -0.2901226 -0.05343741 0 -0.2900623 -0.05254954 0.004107832 -0.29 -0.05198764 0.004489719 -0.2900007 -0.05199992 0.003999173 -0.2899995 -0.05200004 0 -0.290531 -0.0582441 -1.44946e-7 -0.2904317 -0.05593204 0.001429677 -0.2904137 -0.05504941 0.002435922 -0.29054 -0.05781495 2.75228e-4 -0.290579 -0.05882167 0 -0.290579 -0.05823028 1.83485e-4 -0.290618 -0.0592764 0 -0.290656 -0.05909568 0 -0.290618 -0.05864566 9.17427e-5 -0.290656 -0.05973118 0 -0.2906538 -0.05827432 -2.82514e-7 -0.290618 -0.05802005 1.83845e-4 -0.2906172 -0.05725985 3.0956e-4 -0.2906552 -0.05614596 0 -0.290579 -0.05764377 3.67691e-4 -0.29054 -0.05726754 5.51536e-4 -0.2901769 -0.05317246 0.004658937 -0.290039 -0.05152678 0.007422089 -0.29 -0.05124145 0.007820487 -0.29 -0.05141818 0.007361233 -0.29 -0.05157208 0.006893873 -0.2900632 -0.05220186 0.005859553 -0.29 -0.05189228 0.005459785 -0.29 -0.05195176 0.004976272 -0.2905802 -0.05691486 6.1253e-4 -0.2903822 -0.0549373 0.002575457 -0.2900953 -0.05196326 0.006779909 -0.2899923 -0.05101799 0.00833249 -0.29 -0.05180877 0.005943953 -0.2906122 -0.05542021 6.4333e-4 -0.2903344 -0.05336517 0.004455924 -0.290347 -0.054591 0.002982497 -0.2900555 -0.05091637 0.008545756 -0.29 -0.05057829 0.009138524 -0.29 -0.05170196 0.00642246 -0.29 -0.04833447 0.01173746 -0.29 -0.0487079 0.01141619 -0.29 -0.04906737 0.01107525 -0.2900009 -0.04940581 0.01072037 -0.29 -0.04972767 0.01034665 -0.29 -0.05003207 0.009956479 -0.29 -0.05031538 0.009554088 -0.2902992 -0.05226629 0.005682885 -0.29 -0.04754215 0.0123232 -0.29 -0.04712569 0.01258605 -0.2903514 -0.05039024 0.006042122 -0.2902609 -0.05094951 0.007019817 -0.29 -0.04441189 0.013704 -0.29 -0.04625815 0.01304787 -0.2906556 -0.0534296 0 -0.2903166 -0.04768842 0.007227659 -0.29 -0.04345619 0.01389288 -0.2900001 -0.04248803 0.01398777 -0.2902904 -0.04199999 0.007806718 -0.2407817 -0.1192889 0.01930761 -0.240822 -0.1193084 0.01880353 -0.2483697 -0.09686166 0.02182531 -0.2489636 -0.09621667 0.02181494 -0.2457328 -0.1018676 0.02181518 -0.2479175 -0.09736227 0.02182012 -0.2413048 -0.1109983 0.02180516 -0.2382122 -0.1180484 0.02180463 -0.2379472 -0.1179201 0.02179682 -0.2495964 -0.09554642 0.02177637 -0.245252 -0.1049579 0.02172446 -0.2387842 -0.1183252 0.02171844 -0.2501567 -0.09497368 0.02171736 -0.2505113 -0.09462082 0.02166539 -0.2392259 -0.1185384 0.0215376 -0.2508322 -0.09431022 0.02160871 -0.2513154 -0.0938605 0.02149987 -0.2510863 -0.09407132 0.02155518 -0.2395983 -0.1187183 0.02131253 -0.2515507 -0.09365141 0.02143532 -0.2520248 -0.09325128 0.02127474 -0.2517841 -0.09345006 0.02136194 -0.252274 -0.0930559 0.02116912 -0.2399695 -0.1188985 0.02098762 -0.2525156 -0.09288007 0.02104908 -0.252685 -0.092767 0.02095067 -0.252804 -0.09269267 0.02087295 -0.2402786 -0.1190465 0.02060395 -0.252922 -0.09262496 0.02078747 -0.253149 -0.09251558 0.02058905 -0.253038 -0.09256535 0.02069306 -0.253255 -0.09247756 0.02047479 -0.24699 -0.105797 0.02018368 -0.253353 -0.09245395 0.02034956 -0.2404175 -0.1191146 0.02037829 -0.25344 -0.09244698 0.02021437 -0.253512 -0.09245777 0.02007126 -0.2406702 -0.1192355 0.01979035 -0.253568 -0.09248626 0.01992326 -0.253606 -0.0925309 0.01977396 -0.253628 -0.09258937 0.0196259 -0.253634 -0.09265887 0.01948118 -0.253608 -0.09282165 0.01920557 -0.25358 -0.09291148 0.01907545 -0.253627 -0.09273695 0.01934087 -0.253543 -0.093005 0.01895016 -0.253499 -0.09310156 0.01882958 -0.2125706 -0.1197168 0.01979625 -0.2379716 -0.1195517 0.0213713 -0.103868 -0.121 0.01128286 -0.1038476 -0.1209757 0.01166677 -0.2042693 -0.1201122 0.01898902 -0.2379899 -0.1199793 0.02105659 -0.2137511 -0.1204291 0.01916241 -0.2143046 -0.1206847 0.01877224 -0.2380335 -0.1206048 0.0202946 -0.238008 -0.1203037 0.02073085 -0.2380588 -0.1208143 0.01984947 -0.2033075 -0.120867 0.01767575 -0.2140889 -0.1209678 0.01785284 -0.193372 -0.121 0.01624256 -0.126245 -0.121 0.01250267 -0.2380835 -0.1209452 0.01941078 -0.215746 -0.121 0.01751595 -0.238119 -0.121 0.01880276 -0.2379581 -0.1190891 0.02159923 -0.1823043 -0.1193195 0.01831495 -0.215591 -0.119285 0.02022308 -0.2379527 -0.1187301 0.02170437 -0.2044095 -0.1179544 0.01987421 -0.2222487 -0.1179321 0.02089196 -0.2083751 -0.1183895 0.02007287 -0.1591398 -0.118474 0.01728522 -0.1825765 -0.118875 0.01850587 -0.1675719 -0.1180232 0.01779496 -0.1852291 -0.1179865 0.01878738 -0.1037126 -0.1186699 0.01420027 -0.1192814 -0.1181663 0.01512092 -0.1440498 -0.1180852 0.01648437 -0.1037091 -0.1182245 0.01427495 -0.1333603 -0.118972 0.01573252 -0.2379469 -0.1179199 0.02179861 -0.2379476 -0.1183369 0.02178287 -0.170997 -0.121 0.01498258 -0.1333793 -0.1201561 0.01498138 -0.148621 -0.121 0.01373594 -0.1404688 -0.1204593 0.01499944 -0.1319503 -0.1193986 0.01547074 -0.1038269 -0.1208954 0.01206302 -0.1344245 -0.1207029 0.01424771 -0.1037812 -0.1205201 0.01291555 -0.103765 -0.120292 0.01321619 -0.1372156 -0.1197872 0.01551216 -0.1037302 -0.1195241 0.01386868 -0.1037186 -0.1190545 0.01409226 -0.1038063 -0.1207721 0.01243931 -0.1037471 -0.1199622 0.0135554 -0.103327 -0.120573 0.0127269 -0.102724 -0.120415 0.01264595 -0.103052 -0.1203539 0.01295387 -0.1037787 -0.1204934 0.01296019 -0.1034 -0.120239 0.01322346 -0.1037592 -0.1202071 0.01331752 -0.10282 -0.120083 0.01317077 -0.103191 -0.119996 0.01341807 -0.1037433 -0.1198728 0.01363247 -0.103026 -0.119711 0.01359856 -0.1034107 -0.1194822 0.01385468 -0.102935 -0.119454 0.01373505 -0.1037317 -0.1195673 0.01384109 -0.1031224 -0.119157 0.01395493 -0.103303 -0.118868 0.01409739 -0.1037171 -0.1189845 0.01411807 -0.1034992 -0.1185569 0.01420915 -0.1037087 -0.1182245 0.0142821 -0.1038048 -0.1207641 0.01246637 -0.10302 -0.120652 0.01240086 -0.103353 -0.120825 0.01215147 -0.102732 -0.120669 0.01204925 -0.103083 -0.120851 0.01178729 -0.1038349 -0.1209393 0.01191359 -0.103464 -0.120963 0.01152747 -0.1034373 -0.1209741 0.01128286 -0.1038497 -0.1209833 0.01162374 -0.103868 -0.121 0.01128286 -0.1023885 -0.1203318 0.01246643 -0.1022603 -0.1205459 0.01128298 -0.1022765 -0.1205171 0.01165735 -0.102471 -0.120625 0.01168006 -0.102316 -0.12045 0.01205748 -0.1028643 -0.1208337 0.01128274 -0.1025133 -0.120131 0.0129069 -0.1027142 -0.1198092 0.01338434 -0.2080799 -0.09243309 0.005244731 -0.2029403 -0.09297144 0.00578469 -0.207809 -0.09246349 0.005092024 -0.1263356 -0.05939596 0.04766166 -0.121532 -0.05974203 0.04796308 -0.1263877 -0.06808614 0.04765862 -0.207273 -0.09252285 0.004763484 -0.2070119 -0.09255158 0.004588007 -0.1933651 -0.09377843 0.001989603 -0.189683 -0.09336006 0 -0.194477 -0.09319657 0 -0.1147557 -0.09546965 0.003882348 -0.1158002 -0.09563076 0 -0.1407243 -0.06966859 0.04645365 -0.1384883 -0.06920403 0.04667264 -0.159879 -0.07158106 0.04399257 -0.155095 -0.07170987 0.04466265 -0.1621252 -0.07421338 0.04329729 -0.145519 -0.06938952 0.04594188 -0.150308 -0.06916975 0.04537355 -0.1550943 -0.06900298 0.04475212 -0.1598779 -0.06887698 0.04408186 -0.1383959 -0.06523299 0.04668176 -0.1407434 -0.05861181 0.04645162 -0.2005773 -0.04199999 0.03699862 -0.1382662 -0.05971097 0.04669409 -0.1455201 -0.05844295 0.04594177 -0.1503114 -0.05832344 0.04537326 -0.1550959 -0.05824351 0.04475206 -0.1382014 -0.05692708 0.04670208 -0.1621599 -0.07683819 0.04263943 -0.1670294 -0.07930278 0.04096126 -0.1717023 -0.07405495 0.04178762 -0.1717641 -0.07668459 0.0411241 -0.138588 -0.07343453 0.04647755 -0.140726 -0.07237386 0.04636245 -0.1671981 -0.08405363 0.0382803 -0.1767809 -0.08394104 0.03666436 -0.1671017 -0.08174395 0.03975236 -0.155095 -0.07438707 0.04429215 -0.1768085 -0.0861001 0.03493785 -0.1767069 -0.08162242 0.03814727 -0.1766653 -0.0791707 0.03936147 -0.167253 -0.0862075 0.0365656 -0.179002 -0.08802616 0.03258836 -0.174221 -0.0881012 0.03343498 -0.188565 -0.09092658 0.0263884 -0.183782 -0.091111 0.02724897 -0.188565 -0.09211015 0.02396059 -0.193349 -0.08758747 0.02993005 -0.198135 -0.08898437 0.02691555 -0.198135 -0.08734428 0.0290181 -0.179002 -0.08976167 0.03043067 -0.179001 -0.09124618 0.02810388 -0.174221 -0.08984547 0.03127849 -0.179001 -0.09246355 0.02564239 -0.183782 -0.09231287 0.02480125 -0.202921 -0.0900132 0.02380537 -0.198136 -0.09038019 0.02466398 -0.188565 -0.09301859 0.02144217 -0.19335 -0.09335297 0.01809728 -0.19335 -0.09273719 0.02063608 -0.183782 -0.09323769 0.02225768 -0.188565 -0.09364849 0.01886767 -0.198137 -0.09332627 0.01482909 -0.198137 -0.09299236 0.01733934 -0.1721731 -0.0926069 0.0268436 -0.1721288 -0.09137302 0.02932101 -0.19335 -0.09369575 0.0155431 -0.1981257 -0.09340804 0.01231747 -0.183782 -0.09388089 0.01965165 -0.188565 -0.0940001 0.01627147 -0.212486 -0.09190887 0.008279323 -0.2125913 -0.09189701 0.006911516 -0.2156841 -0.09149634 0.007402837 -0.2150706 -0.09157812 0.007339298 -0.209643 -0.0922538 0.00598669 -0.2102025 -0.092188 0.006203353 -0.2080211 -0.09243869 0.007221341 -0.20754 -0.09249335 0.004931628 -0.206265 -0.09263271 0.004021108 -0.206505 -0.09260678 0.004214942 -0.206755 -0.09257966 0.004404842 -0.20449 -0.09281927 0.001835107 -0.204637 -0.09280419 0.002117812 -0.2029775 -0.09297162 0.00184369 -0.205159 -0.09274989 0.002896189 -0.2053599 -0.09272885 0.003137588 -0.204363 -0.09283238 0.001544177 -0.1992689 -0.09303116 0 -0.20406 -0.09286379 0 -0.204073 -0.0928623 3.19288e-4 -0.204171 -0.09285205 9.42487e-4 -0.2042559 -0.09284329 0.001246392 -0.20411 -0.09285837 6.3345e-4 -0.1790036 -0.09451532 0.002280294 -0.1742147 -0.09465801 0.002392232 -0.175292 -0.09383887 0 -0.184529 -0.09353548 -5.04308e-7 -0.1885797 -0.09408384 0.002077519 -0.1837934 -0.09432655 0.002174973 -0.1048048 -0.095703 0.00410974 -0.08633822 -0.09620606 0.0287652 0.03847301 -0.09978866 0 0.0351991 -0.0998246 0.005179464 0.05398166 -0.1000786 0.005058944 -0.07904541 -0.09534591 0.03651446 -0.08891183 -0.09562206 0.03351449 -0.1142498 -0.08773624 0.04270946 -0.1094341 -0.08962732 0.04145491 -0.1190295 -0.08917433 0.04071897 -0.09834933 -0.09384 0.03683662 -0.09760451 -0.09472244 0.03481262 -0.1011434 -0.09567648 0.02965664 -0.126336 -0.07609146 0.04720175 -0.1286232 -0.07502686 0.0471999 -0.09440815 -0.09295922 0.03906381 -0.09981536 -0.09014707 0.04205477 -0.09507393 -0.08895909 0.04372423 -0.09021204 -0.09071904 0.04252666 -0.1137672 -0.09089845 0.03938072 -0.114346 -0.07962942 0.04726821 -0.121537 -0.08126026 0.0460273 -0.121536 -0.07895737 0.04688507 -0.09975713 -0.09152036 0.04043394 -0.10469 -0.08831316 0.04328382 -0.1094965 -0.08625316 0.04440641 -0.1190872 -0.08561515 0.04383122 -0.114324 -0.08396083 0.04538404 -0.121536 -0.0765407 0.04750406 -0.1143743 -0.07727855 0.04787397 -0.1047313 -0.08474749 0.04582107 -0.1047252 -0.082758 0.04682254 -0.114328 -0.0818603 0.04643344 -0.1047501 -0.08063542 0.04762423 -0.126336 -0.07353335 0.04756855 -0.1285457 -0.07173871 0.04751658 -0.126335 -0.07085359 0.04766178 -0.1023129 -0.07374346 0.04872137 -0.1095555 -0.07540047 0.04842358 -0.1071209 -0.07309186 0.04859435 -0.116732 -0.07454478 0.04812258 -0.121535 -0.0740177 0.04786908 -0.1167314 -0.0718916 0.04821759 -0.1119269 -0.07247334 0.04842716 -0.1215338 -0.0713495 0.04796308 -0.1283728 -0.06437563 0.04751902 -0.1167291 -0.06012421 0.04821759 -0.1119242 -0.06054025 0.04842716 -0.1282029 -0.05716156 0.04752928 -0.123452 -0.05727308 0.04768246 -0.08149611 -0.09623771 0.0320329 -0.2220046 -0.06644743 0.03307825 -0.1000962 -0.09582132 0.02697288 -0.2110121 -0.04199999 0.03503328 -0.08511769 -0.09624797 0.004457592 -0.2172309 -0.04199999 0.03390663 -0.2267513 -0.0657919 0.03229391 -0.07544648 -0.09654664 0.004552423 -0.1260026 -0.08711403 0.04181903 -0.05250507 -0.09730225 0.004711151 -0.05842369 -0.0970866 0 -0.06639271 -0.09683865 0.004350662 -0.06679284 -0.09687209 0 -0.2314839 -0.06500029 0.03156197 -0.02756905 -0.09681618 0.0404604 -0.03709995 -0.0969516 0.03901582 -0.03717297 -0.09640276 0.04025942 -0.006744146 -0.08994358 0.04616034 0.006245851 -0.09231263 0.04534298 0.01807427 -0.06262123 0.04532593 0.02336001 -0.07932084 0.04514801 0.01068592 -0.0891999 0.045587 -6.32379e-4 -0.08833831 0.04602313 -0.231483 -0.06753176 0.03147947 -0.236198 -0.06656736 0.03081089 0.0235663 -0.07053244 0.04514127 -0.240894 -0.06800049 0.02986705 -0.236198 -0.0691471 0.03045719 -0.240893 -0.06543886 0.03021347 0.0228886 -0.06274569 0.04516369 -0.2481665 -0.07107812 0.02752035 -0.2387477 -0.07117366 0.02946317 -0.2386858 -0.07376271 0.02849763 0.02379643 -0.06073009 0.0451337 -0.245569 -0.06927406 0.02872097 -0.25484 -0.06600087 0.0280267 -0.250217 -0.06774336 0.0283212 -0.25484 -0.06864249 0.02709966 -0.2479487 -0.07368332 0.02625721 0.01326394 -0.06247705 0.04549455 0.008450806 -0.06780159 0.04567068 0.01806992 -0.08961945 0.04532605 -0.01392155 -0.09056657 0.04617971 -0.004005908 -0.09256225 0.04538601 -0.00853008 -0.09309697 0.04514104 -0.008488178 -0.09393066 0.04465401 -0.01811361 -0.09318733 0.04499685 -0.01325118 -0.09436309 0.04426777 -0.0228917 -0.0936563 0.04455834 0.02306979 -0.09168154 0.04508692 0.01669979 -0.09173899 0.04524135 0.02304404 -0.09277677 0.04487115 0.02303487 -0.09317326 0.04476314 -0.02281725 -0.09585809 0.04236513 -0.02287244 -0.09518551 0.0431624 -0.03248488 -0.093773 0.04408907 -0.03251653 -0.09288394 0.04482352 -0.01323091 -0.09508389 0.04365873 -0.01320177 -0.09574514 0.04299527 -0.01319122 -0.09635031 0.04227292 -0.03248751 -0.09458452 0.04328471 -0.02279549 -0.09646838 0.0414927 -0.03243112 -0.09600549 0.04143595 -0.01795721 -0.09721297 0.04058015 -0.02752751 -0.09731811 0.03933316 -0.03704291 -0.09739744 0.03761672 -0.04010492 -0.09760957 0.03578573 -0.06766808 -0.09679287 0.0309413 -0.04774463 -0.09740424 0 -0.03975361 -0.09773516 0.004990041 -0.03580725 -0.09776675 0 -0.003256022 -0.09890663 0.03540635 -0.01637387 -0.09850758 0.005341887 -0.01283442 -0.09861665 0.03509515 -0.01250147 -0.09851479 0 -0.003025472 -0.09891337 0.005247414 -0.003305137 -0.09882128 0 0.003184735 -0.09904277 0 0.006562769 -0.09918123 0.004891633 0.01000571 -0.09926629 0 0.07233476 -0.1001105 0 0.07310771 -0.1001628 0.004874348 0.1762176 -0.08716607 0.03952795 0.171946 -0.08909088 0.03941559 0.171946 -0.08763855 0.0397191 0.06846934 -0.1001609 0.03395485 0.05434572 -0.1000828 0.03463107 0.03748053 -0.09027987 0.04470324 0.04371553 -0.0682525 0.04451799 0.03749495 -0.06313472 0.04470378 0.03311651 -0.08981102 0.04483872 0.03339761 -0.07783478 0.04482865 0.03732275 -0.09239238 0.04458665 0.04037129 -0.09363424 0.04421126 0.04444217 -0.09458744 0.04374969 0.04895508 -0.09251952 0.04424351 0.05883109 -0.09368282 0.04367715 0.05407291 -0.09462231 0.04346871 0.05167931 -0.09539985 0.04315507 0.04929441 -0.09606301 0.04280865 0.05134379 -0.09038609 0.04429757 0.0589016 -0.09607851 0.04251801 0.0336281 -0.06802123 0.04482156 0.03379368 -0.06096476 0.04481643 0.0637263 -0.09535795 0.04279762 -0.247911 -0.07825905 0.02281171 -0.250218 -0.07954216 0.02050358 0.04554474 -0.06124067 0.04452401 0.05415004 -0.09669363 0.04220867 0.05413478 -0.09725111 0.04172062 0.06372767 -0.09725868 0.04140609 0.06372135 -0.09778338 0.04086619 0.05410057 -0.09776204 0.04119473 0.04250937 -0.09659767 0.04257351 0.07558923 -0.09716898 0.04101192 0.07334685 -0.09774351 0.04052072 0.07332509 -0.09661048 0.04159331 0.08683848 -0.09724837 0.04039746 0.08294546 -0.09647244 0.04126572 0.09682142 -0.09646058 0.04055851 0.09381729 -0.09688377 0.04039996 0.09021747 -0.09632855 0.04100686 0.09735238 -0.0954563 0.04125517 0.111055 -0.09556567 0.04039996 0.107613 -0.09587597 0.04039996 0.10525 -0.09520161 0.04097485 0.092579 -0.0948134 0.0418871 0.1021675 -0.09452468 0.04155039 0.1118173 -0.09419161 0.04119002 -0.250218 -0.08119928 0.01824867 -0.25484 -0.08138829 0.01523178 -0.25484 -0.07997369 0.01769167 0.117928 -0.09487509 0.04039996 0.1145049 -0.09523195 0.04040169 0.123634 -0.09372508 0.04072409 -0.245568 -0.0666725 0.02935916 -0.2531866 -0.07441985 0.02426683 0.1067702 -0.09347045 0.04181277 -0.259429 -0.0812444 0.01199829 -0.259429 -0.08012199 0.01458936 -0.25484 -0.07821738 0.0200625 0.1269195 -0.0926814 0.04102003 -0.25484 -0.07614207 0.02225726 -0.2432968 -0.07737958 0.0251134 -0.25484 -0.08246707 0.01275527 -0.259429 -0.08202958 0.00948143 0.133486 -0.09233868 0.0407592 0.1260074 -0.09158653 0.04145371 0.138294 -0.0909819 0.0409435 0.138294 -0.09210735 0.04055488 -0.25484 -0.07127118 0.02582269 0.143422 -0.08930861 0.04102551 0.141888 -0.09172338 0.04039996 -0.2384785 -0.07627689 0.02723687 0.166785 -0.0904234 0.03932255 0.171503 -0.09055227 0.03892958 -0.25943 -0.07862597 0.01718574 0.1762402 -0.08621984 0.0396015 0.1685358 -0.08565938 0.03999584 0.1763132 -0.08309268 0.03961926 0.1501109 -0.08677583 0.04084765 0.176411 -0.07895207 0.03961449 -0.263948 -0.08057528 0.008674919 -0.263949 -0.07977408 0.01126718 0.1765537 -0.07286202 0.03960752 0.1766288 -0.06965404 0.03960388 -0.250217 -0.06022995 0.02934205 -0.250216 -0.06263196 0.02926898 -0.25484 -0.06092494 0.02894026 0.1767536 -0.0643211 0.0395978 0.1766887 -0.067124 0.03960096 0.176476 -0.07618767 0.03961133 0.1599802 -0.08835583 0.040286 0.15211 -0.09002268 0.04039996 0.157088 -0.09015858 0.04005777 0.163935 -0.08957737 0.03979617 0.16198 -0.09029215 0.03969866 0.1761747 -0.08899182 0.0391646 0.1761519 -0.08998829 0.03882443 0.176136 -0.09067881 0.03851968 0.147706 -0.09048926 0.04053586 0.08343786 -0.09739476 0.04039996 0.08318567 -0.09762674 0.04017078 0.04487812 -0.09997588 0.03499561 0.04216575 -0.09983342 0.0369724 0.04004311 -0.09529787 0.04350048 0.07327467 -0.09980601 0.03677779 0.07396614 -0.1000598 0.03555399 0.08777564 -0.09569847 0.04159247 0.07813149 -0.09588855 0.04191446 0.05410933 -0.09823185 0.04062414 0.04234218 -0.09714704 0.04209578 0.06376111 -0.09911078 0.03893989 0.06857836 -0.09948527 0.03793817 0.05896931 -0.09945029 0.03835231 0.05423974 -0.09997934 0.03649413 0.04245311 -0.09764558 0.0415802 0.08117204 -0.0994631 0.03733849 0.07340538 -0.09911131 0.03853213 0.05415153 -0.09866374 0.04000109 0.05420196 -0.09972757 0.03764182 0.04232519 -0.09810721 0.04102385 0.04253864 -0.09892153 0.03974026 0.05414497 -0.09905773 0.03931719 0.04235333 -0.09853518 0.0404095 0.0820744 -0.09863722 0.03889679 0.07335329 -0.09869635 0.03925967 0.04935395 -0.09936612 0.03872877 0.04008948 -0.0992369 0.03905647 0.07496452 -0.09823632 0.03984767 0.08102649 -0.09958767 0.03699266 0.08067417 -0.09990805 0.03590047 0.08046799 -0.100096 0.0347408 0.08051908 -0.100049 0.03513199 0.04457956 -0.09997081 0.005125522 0.06139004 -0.1001333 0.03429388 0.06442797 -0.100148 0.004865527 0.06178748 -0.1000454 0 0.08041942 -0.1001387 0 0.02556794 -0.09963881 0.005227148 0.02407759 -0.09955096 0 0.01693779 -0.0994445 0.004975676 0.006319642 -0.09906953 0.03752356 -0.005771636 -0.09809744 0.03971093 -0.005670249 -0.09845542 0.03865957 -0.07625353 -0.09664911 0 -0.08563035 -0.09641933 0 -0.0945031 -0.09619539 0 -0.09477508 -0.09596848 0.004301011 -0.1244439 -0.09527641 0.003594875 -0.127221 -0.095308 0 -0.122405 -0.0954442 0 -0.136848 -0.09502971 0 -0.1359357 -0.09509789 0.003381192 -0.132035 -0.09516978 0 -0.1311451 -0.09516561 0.003498136 -0.146468 -0.09474366 0 -0.1455185 -0.09499627 0.003134548 -0.141659 -0.09488767 0 -0.1407295 -0.09504115 0.003258049 -0.1512759 -0.09459775 0 -0.1550895 -0.0949288 0.002882301 -0.1503053 -0.09496158 0.00300908 -0.156083 -0.09444987 0 -0.1598712 -0.09488999 0.002755999 -0.1646491 -0.09483736 0.002631306 -0.160887 -0.09430009 0 -0.165691 -0.09414827 0 -0.1704919 -0.09399449 0 -0.1694316 -0.09476268 0.002509772 -0.204972 -0.0927695 0.002645671 -0.205573 -0.09270638 0.003372669 -0.205799 -0.09268248 0.003601133 -0.206031 -0.0926578 0.003818035 -0.2029229 -0.0928924 0.01412504 -0.2456184 -0.08621644 0 -0.2086319 -0.09237051 0.005532205 -0.2083539 -0.0924021 0.005391359 -0.209059 -0.09232151 0.005735039 -0.2110942 -0.09208112 0.0065068 -0.210656 -0.09213387 0.006363272 -0.2116906 -0.09200847 0.006682634 -0.212133 -0.09195399 0.006799817 -0.213062 -0.0918377 0.007014274 -0.1789975 -0.09451752 0.0151183 -0.1837762 -0.09432876 0.01439779 -0.213543 -0.0917766 0.007109344 -0.1981499 -0.0934084 0.001909792 -0.2141416 -0.0916996 0.007211923 -0.214607 -0.09163886 0.007280051 -0.1885596 -0.09408539 0.01369142 -0.1933435 -0.09377908 0.01299834 -0.1675494 -0.09470528 0.01963251 -0.174219 -0.09456849 0.01854389 -0.167513 -0.09431666 0.02238017 -0.2163305 -0.09140926 0.007452607 -0.217256 -0.0912823 0.007717669 -0.174219 -0.09419107 0.02124667 -0.179 -0.09405899 0.02044588 -0.1721872 -0.09356516 0.02425831 -0.2169435 -0.09132558 0.007483541 -0.2175434 -0.09124273 0.007498562 -0.202924 -0.09297108 0.01164585 -0.1673358 -0.08817178 0.03461539 -0.1673786 -0.08991903 0.03246343 -0.2181927 -0.09115177 0.007497787 -0.2186509 -0.09108686 0.007486224 -0.2191168 -0.09102028 0.007466077 -0.212485 -0.09190726 0.0103116 -0.207707 -0.092471 0.01097857 -0.2172549 -0.0912804 0.009641051 -0.2197199 -0.09093344 0.007425367 -0.2203657 -0.09083914 0.007363975 -0.2218925 -0.09060788 0.00893718 -0.220974 -0.09074926 0.007288634 -0.2215709 -0.09066015 0.00719738 -0.222651 -0.090496 0.006985723 -0.2230996 -0.09042644 0.006880104 -0.226761 -0.08983868 0.008272826 -0.2267619 -0.089841 0.006586313 -0.2222049 -0.09056389 0.007080733 -0.2361991 -0.08815008 0.006852388 -0.2409052 -0.08721113 0.006103038 -0.2236773 -0.09033733 0.006726324 -0.2455902 -0.08621138 0.005325376 -0.2502542 -0.08514916 0.004507541 -0.2242842 -0.09024208 0.006541788 -0.2248829 -0.09014719 0.006335377 -0.2683393 -0.0794568 2.9197e-4 -0.2639563 -0.08137243 0.001931726 -0.2683493 -0.07946741 0.001296162 -0.2594078 -0.08283305 6.10046e-4 -0.2639272 -0.08137065 4.3687e-4 -0.2725895 -0.0768947 2.15756e-4 -0.2754833 -0.07457369 4.15073e-7 -0.2766376 -0.073484 2.29331e-4 -0.254761 -0.08405894 0 -0.2681646 -0.07950764 0 -0.2589475 -0.08295065 0 -0.2503842 -0.08512747 0 -0.2411604 -0.08717358 0 -0.2321047 -0.0889309 0 -0.236509 -0.08810722 0 -0.2315389 -0.08902043 0.004847586 -0.229813 -0.08932989 0.002941906 -0.229995 -0.08929866 0.0026775 -0.23044 -0.0892226 0.001848936 -0.230557 -0.0892027 0.001554667 -0.230733 -0.08917289 9.42218e-4 -0.23079 -0.0891633 6.2649e-4 -0.2308239 -0.08915776 3.1371e-4 -0.230836 -0.08915621 0 -0.2624996 -0.08183813 1.41664e-7 -0.264406 -0.08116906 0 -0.2697933 -0.07866215 5.32594e-7 -0.2661093 -0.08046638 4.40517e-7 -0.2712297 -0.07778793 2.36433e-7 -0.2804242 -0.06917929 3.49449e-4 -0.2735643 -0.07615572 -1.92717e-7 -0.274613 -0.07531648 0 -0.272436 -0.0769723 0 -0.2769964 -0.07313817 0 -0.2782126 -0.07184296 0 -0.2792987 -0.07061183 2.85543e-7 -0.2871243 -0.05829179 0.002333819 -0.280565 -0.06904482 0 -0.281364 -0.06796479 0 -0.2823621 -0.06654232 0 -0.2594473 -0.08282774 0.002754032 -0.2830603 -0.06551092 1.24219e-7 -0.2839179 -0.06411093 5.5119e-4 -0.2871179 -0.05836439 7.73189e-4 -0.2900027 -0.05200117 7.48029e-4 -0.2845513 -0.06312137 0 -0.2859253 -0.06067872 -2.45288e-7 -0.287102 -0.05844092 0 -0.2885591 -0.05536895 0 -0.2900095 -0.05200386 -1.62029e-7 -0.2725791 -0.0769115 8.91341e-4 -0.2260324 -0.08996224 0.005859494 -0.2254601 -0.09005486 0.006110668 -0.272587 -0.07685595 0.002724468 -0.268348 -0.07941615 0.003203392 -0.2548831 -0.08402931 0.003646433 -0.263947 -0.08107221 0.00622332 -0.268349 -0.07917016 0.005490541 -0.263946 -0.08132225 0.003929913 -0.259428 -0.08277738 0.004805326 -0.259428 -0.08252459 0.007076323 -0.25484 -0.08398228 0.005730926 -0.25484 -0.08372718 0.007972002 -0.2455684 -0.06168973 0.02977257 -0.25484 -0.08323496 0.01032239 -0.272595 -0.05728989 0.02612018 -0.268363 -0.05715805 0.02755558 -0.268362 -0.05964267 0.02704596 -0.268356 -0.07297146 0.01885366 -0.268357 -0.07051509 0.02131247 -0.263953 -0.07267916 0.02172809 -0.2840586 -0.04199987 0.02009457 -0.283828 -0.04244089 0.02028256 -0.2803596 -0.04712116 0.02301442 -0.280374 -0.059035 0.01968765 -0.276609 -0.05974447 0.02287465 -0.276609 -0.06233614 0.02142798 -0.289355 -0.04199993 0.01474845 -0.287061 -0.04288607 0.0172227 -0.268361 -0.06227868 0.02622139 -0.272594 -0.05982655 0.02535438 -0.272593 -0.06250667 0.02421939 -0.272593 -0.06525576 0.02265095 -0.2683659 -0.05270367 0.0278663 -0.272597 -0.05072599 0.02686744 -0.2683746 -0.04317378 0.0278663 -0.2725985 -0.04258072 0.02686858 -0.2664291 -0.04199999 0.02816206 -0.272596 -0.05492329 0.02658659 -0.276607 -0.0548889 0.024598 -0.276606 -0.05271005 0.02501356 -0.272596 -0.05273514 0.02681797 -0.280334 -0.04279631 0.02302193 -0.276593 -0.04284471 0.02526533 -0.278413 -0.04199999 0.02427577 -0.2774206 -0.04199993 0.02484756 -0.2793685 -0.04199999 0.02367407 -0.2639698 -0.0423507 0.02843523 -0.2642487 -0.04199993 0.02840012 -0.2711518 -0.04200005 0.0272783 -0.268928 -0.04199993 0.02775406 -0.2728901 -0.04199993 0.02676039 -0.2746028 -0.04200011 0.02615064 -0.2618504 -0.04199999 0.0286048 -0.2594418 -0.04274892 0.02875584 -0.268365 -0.05484277 0.02781099 -0.276606 -0.05070585 0.02521824 -0.2532032 -0.04199999 0.02911275 -0.2639595 -0.05472588 0.0284354 -0.263959 -0.05695939 0.02837496 -0.2594321 -0.05671125 0.0287562 -0.26836 -0.06502979 0.02501904 -0.263955 -0.06732547 0.02543979 -0.268358 -0.06781578 0.02338725 -0.2549564 -0.04199999 0.02900063 -0.2502138 -0.04357504 0.02934211 -0.263956 -0.06457889 0.02668297 -0.263954 -0.07006305 0.02378785 -0.263952 -0.07504028 0.01932245 -0.268354 -0.07504808 0.01614189 -0.259432 -0.06940358 0.02565109 -0.276608 -0.05723994 0.02390849 -0.259433 -0.06404221 0.02781879 -0.259432 -0.06670778 0.02691668 -0.259431 -0.07452726 0.02199995 -0.25943 -0.07674849 0.01969397 -0.263951 -0.077035 0.01668739 -0.25484 -0.06341147 0.02862805 -0.26395 -0.07860988 0.01396399 -0.259431 -0.07204347 0.02400708 -0.250217 -0.06514728 0.02894306 -0.228038 -0.08963108 0.004687964 -0.227776 -0.08967489 0.004873037 -0.228531 -0.08954811 0.004301786 -0.229622 -0.08936268 0.003194868 -0.2303079 -0.0892452 0.002133309 -0.230655 -0.08918595 0.001252055 -0.204796 -0.09278768 0.002387166 -0.04406386 -0.09758627 0.0331757 -0.02587008 -0.09819859 0.03446513 0.080419 -0.1001402 0.03394383 -0.29 -0.05198734 0.004492163 -0.287117 -0.05823767 0.004001975 -0.2899972 -0.05199873 0.003994286 -0.226718 -0.0898503 0.005515873 -0.2269909 -0.08980518 0.005364477 -0.227514 -0.08971858 0.005047738 -0.22829 -0.08958876 0.004497706 -0.228991 -0.08947008 0.003886461 -0.228765 -0.08950847 0.004098296 -0.22942 -0.08939707 0.003435313 -0.2301599 -0.08927059 0.002408504 -0.1458985 -0.09499293 0.02026242 -0.15887 -0.09490126 0.01824581 -0.1384291 -0.09506493 0.02141863 -0.12884 -0.09519898 0.02287006 -0.1192697 -0.09537273 0.02428585 -0.1096774 -0.095582 0.02565658 -0.1288257 -0.08365356 0.04400873 -0.126338 -0.08519858 0.04328435 -0.128847 -0.08456939 0.04341775 0.008960604 -0.09924715 0.03559976 0.03083109 -0.09974581 0.03541123 0.02013766 -0.0995205 0.03565657 0.03732508 -0.0998609 0.03523504 0.08043467 -0.100126 0.03434544 0.07579189 -0.100158 0.03356659 -0.29 -0.05195105 0.004980981 -0.29 -0.05189108 0.005466461 -0.287114 -0.05806636 0.005354821 -0.28711 -0.05773305 0.006805837 -0.29 -0.05170005 0.006427466 -0.276615 -0.07321161 0.0046947 -0.276615 -0.07344168 0.002589643 -0.280397 -0.06911396 0.002815604 -0.22644 -0.0898959 0.005660951 -0.22921 -0.08943289 0.003665983 0.0171529 -0.09934598 0.03749829 0.02288544 -0.09953314 0.03699982 -0.29 -0.05180746 0.005948662 -0.268351 -0.0786755 0.007955133 -0.272587 -0.0766164 0.004955708 -0.272588 -0.0761314 0.007374167 -0.227256 -0.08976149 0.005208849 -0.1742169 -0.09466028 0.01584738 -0.1675996 -0.09479951 0.01688122 -0.1195581 -0.09413534 0.03232765 -0.29 -0.0515691 0.006901979 -0.29 -0.0508185 0.008711695 -0.29 -0.05057615 0.009138762 -0.287102 -0.05644327 0.009899556 -0.287106 -0.05720239 0.008332848 -0.29 -0.0510388 0.008274614 -0.276613 -0.07198005 0.009443938 -0.276614 -0.07274699 0.006983041 -0.280391 -0.06846517 0.006789743 -0.2314929 -0.08902466 0.007567107 -0.183781 -0.09424126 0.01701635 -0.179 -0.09442806 0.01777487 -0.05867719 -0.09697759 0.03432559 -0.005277752 -0.09874081 0.03737014 0.0228877 -0.09943521 0.03769928 0.04242539 -0.09957998 0.03811222 0.06379789 -0.1000445 0.03606224 -0.29 -0.05141538 0.007366776 -0.29 -0.05123835 0.007824778 -0.283906 -0.06399929 0.003316938 -0.29 -0.05031317 0.009554088 -0.287099 -0.05544477 0.01144087 -0.250219 -0.08509796 0.006627142 -0.245572 -0.08615398 0.007483005 -0.2409 -0.08714908 0.008303046 -0.222014 -0.09051966 0.01131725 -0.217254 -0.0912075 0.01202708 -0.2362059 -0.08808368 0.009091973 -0.212484 -0.09183245 0.01272869 -0.231492 -0.08895736 0.009854257 -0.207706 -0.09239429 0.01342648 -0.22676 -0.08976948 0.01059448 -0.179 -0.0934031 0.02307909 -0.2029229 -0.0925672 0.01659065 -0.198136 -0.09239089 0.0198397 -0.1628546 -0.09367686 0.02585339 -0.158587 -0.0948044 0.02109897 -0.1439969 -0.09490269 0.02344089 -0.1338703 -0.09501546 0.02501773 -0.1200697 -0.09524106 0.02706992 -0.1103506 -0.09503412 0.03102344 0.005997538 -0.09718233 0.04195964 0.006011247 -0.09765195 0.04128742 -0.02151614 -0.09823232 0.03683477 0.01522552 -0.09904015 0.03869587 0.006093025 -0.09879976 0.03874099 0.03288406 -0.09971147 0.037 0.03288662 -0.0995993 0.03767901 0.0637958 -0.09979164 0.03722625 -0.283902 -0.06380176 0.00496459 -0.29 -0.04940956 0.01071476 -0.29 -0.04907238 0.01106995 -0.287095 -0.05422377 0.01287835 -0.280394 -0.06889748 0.004720211 -0.276612 -0.06926697 0.0146926 -0.276612 -0.0708394 0.01204377 -0.280385 -0.06670808 0.01135057 -0.268352 -0.07786709 0.01058346 -0.250219 -0.08483988 0.008847594 -0.245572 -0.0858919 0.009694457 -0.240899 -0.08688217 0.01051604 -0.212484 -0.0915243 0.01510679 -0.217253 -0.09090739 0.01436477 -0.236205 -0.08781129 0.01131576 -0.193349 -0.09068417 0.02552574 -0.198136 -0.09151905 0.02229368 -0.231491 -0.08867877 0.012097 -0.207706 -0.09207767 0.01584756 -0.22676 -0.08948427 0.01286327 -0.2220129 -0.09022718 0.01361805 -0.202922 -0.09112757 0.02146857 -0.202922 -0.09197998 0.01905095 -0.153986 -0.09372192 0.02733141 -0.1536898 -0.09273701 0.02995502 -0.1584284 -0.09440314 0.02390247 -0.1440643 -0.09448808 0.02621263 -0.1295219 -0.09465193 0.02842324 -0.1171261 -0.09325993 0.03494435 -0.1131697 -0.09223932 0.03749078 -0.06883126 -0.0962767 0.03543651 -0.05052125 -0.09691888 0.03683173 -0.02744859 -0.09773403 0.03805637 -0.01779443 -0.09806299 0.03839093 0.006042659 -0.09846454 0.03971207 0.006031095 -0.09808027 0.0405457 0.02289241 -0.09923839 0.03854686 0.03289222 -0.09936165 0.03859227 0.08077627 -0.0998153 0.03627306 0.08058875 -0.09998577 0.03552025 -0.29 -0.0500316 0.009954512 -0.283898 -0.0634135 0.006747424 -0.29 -0.04795938 0.0120331 -0.29 -0.04755747 0.01231676 -0.287091 -0.05283987 0.01413267 -0.280388 -0.06775635 0.009011149 -0.272589 -0.0753321 0.009968757 -0.268353 -0.0766769 0.01334095 -0.250219 -0.0843482 0.01115566 -0.245572 -0.08539819 0.01197516 -0.240899 -0.08638405 0.01278275 -0.236205 -0.08730679 0.0135805 -0.217253 -0.09036117 0.01671129 -0.212483 -0.09096497 0.01748865 -0.231491 -0.08816599 0.01437026 -0.207705 -0.09150469 0.01826798 -0.226759 -0.0889616 0.015154 -0.222012 -0.08969336 0.01593369 -0.1626962 -0.09145355 0.03093194 -0.1627685 -0.09270095 0.02845752 -0.140727 -0.09013009 0.03647607 -0.1407939 -0.09159457 0.03426516 -0.1385965 -0.09381878 0.02972841 -0.12634 -0.09046679 0.03816169 -0.12634 -0.09186166 0.03608906 -0.07977783 -0.0945487 0.0383014 -0.06046032 -0.09604179 0.03785431 -0.04668998 -0.09657794 0.03860354 -0.01789772 -0.09767431 0.03955793 -0.005851924 -0.09767943 0.04062288 0.01539289 -0.09872323 0.03962016 0.03289991 -0.09903532 0.03945475 0.08089476 -0.09970748 0.03663796 -0.29 -0.04972988 0.01034206 -0.283893 -0.06278455 0.008648574 -0.287088 -0.05137449 0.01515215 -0.27259 -0.07414507 0.01270568 -0.250218 -0.08359259 0.01352077 -0.245571 -0.0846492 0.01429134 -0.240898 -0.08563655 0.01506727 -0.236204 -0.08655619 0.01584845 -0.217252 -0.08956408 0.01902717 -0.212482 -0.09015047 0.01983535 -0.23149 -0.08740836 0.01663506 -0.207705 -0.09067159 0.02064925 -0.226758 -0.08819347 0.01742696 -0.222012 -0.08891201 0.01822435 -0.193349 -0.09184658 0.02312427 -0.1579044 -0.08997225 0.03401118 -0.1389581 -0.08919298 0.03792822 -0.140727 -0.0884599 0.03848725 -0.1379356 -0.09284609 0.03232884 -0.1289818 -0.09031558 0.03798156 -0.1289592 -0.08935636 0.03916907 -0.126339 -0.08888286 0.04005557 -0.06599885 -0.09513187 0.0391308 -0.06128013 -0.09454298 0.04080438 -0.05641025 -0.09555238 0.03959739 -0.04679375 -0.09597873 0.03997296 -0.003605782 -0.09564131 0.04340559 -0.01318931 -0.09690248 0.04148262 -0.003557264 -0.09730136 0.04141163 0.01529532 -0.09835559 0.04040974 0.0154097 -0.09795206 0.04111278 0.02291506 -0.09827268 0.0407598 0.02290153 -0.0988478 0.03965318 0.03291296 -0.09847897 0.04053384 0.0822857 -0.09844255 0.03917509 0.06376707 -0.09870767 0.03964185 0.0806024 -0.0990737 0.03821289 0.08133226 -0.09930956 0.03767246 -0.29 -0.0487169 0.01140958 -0.29 -0.04834538 0.01173114 -0.283889 -0.06186658 0.01063305 -0.280382 -0.0652731 0.01372277 -0.276611 -0.06725847 0.01724797 -0.27259 -0.07251 0.01549476 -0.250218 -0.08254796 0.01590269 -0.245571 -0.08362805 0.01660215 -0.240898 -0.08462929 0.01732808 -0.236203 -0.08555406 0.01807796 -0.217251 -0.08851909 0.02127158 -0.212482 -0.08908408 0.02210676 -0.231489 -0.08640408 0.01884955 -0.207704 -0.08958166 0.02295219 -0.226758 -0.08718049 0.01964056 -0.222011 -0.08788508 0.02044868 -0.1837829 -0.08964186 0.02956688 -0.188565 -0.08947747 0.02869057 -0.1837829 -0.08792108 0.03171998 -0.1577228 -0.08629482 0.03805577 -0.1576187 -0.08416831 0.03975033 -0.1578149 -0.08823829 0.03613656 -0.1483538 -0.08832603 0.03750729 -0.1389357 -0.08824819 0.03898167 -0.138916 -0.0874046 0.0398187 -0.1534034 -0.09148949 0.03243333 -0.1348052 -0.09168148 0.03506278 -0.08051359 -0.09359127 0.03993612 -0.07088154 -0.0940597 0.04041975 -0.05164945 -0.09503531 0.04109829 -0.04206562 -0.09552395 0.04130643 -0.03245294 -0.09532964 0.04240298 -0.04209321 -0.09477579 0.04237776 0.005984127 -0.0961129 0.04314392 0.005992054 -0.09550619 0.04366809 0.0154196 -0.09592384 0.04337608 -0.003577888 -0.09679549 0.04213488 0.0637533 -0.09826558 0.04027974 0.08168387 -0.09898978 0.03830736 0.0818755 -0.09881556 0.03860777 0.08150219 -0.099155 0.03799575 -0.29 -0.04714286 0.01257979 -0.283885 -0.06062829 0.01262456 -0.29 -0.04490357 0.01357215 -0.29 -0.04443114 0.01370286 -0.287076 -0.04716318 0.01685845 -0.28038 -0.06345248 0.01599848 -0.27661 -0.0648964 0.01953738 -0.272591 -0.07041847 0.01819294 -0.245571 -0.08232748 0.01886069 -0.2408969 -0.08336108 0.01952278 -0.236203 -0.08430427 0.02022999 -0.207704 -0.08824646 0.02514225 -0.212481 -0.08777755 0.02426868 -0.231489 -0.08516037 0.02097725 -0.20292 -0.08704251 0.02810394 -0.198135 -0.08547395 0.03094458 -0.226757 -0.08593249 0.02175974 -0.202921 -0.08864766 0.02602618 -0.22201 -0.0866239 0.02257245 -0.217251 -0.08723789 0.02341049 -0.193349 -0.08925998 0.02780526 -0.13885 -0.08458554 0.04214274 -0.138873 -0.08558499 0.04138827 -0.140727 -0.08455979 0.04190886 -0.140727 -0.0865975 0.04030227 -0.1486161 -0.09002745 0.03540962 -0.138976 -0.08993309 0.037 -0.134121 -0.09047645 0.037 -0.128998 -0.0910179 0.037 -0.1289367 -0.08838856 0.04022812 -0.1253581 -0.0831601 0.04468894 -0.09015882 -0.0920034 0.04101324 -0.08055126 -0.09252446 0.04147911 -0.07093536 -0.09307283 0.04184037 -0.06133908 -0.09363669 0.04210448 -0.05171316 -0.09420835 0.04228127 -0.003619313 -0.09498512 0.04396647 -0.003581106 -0.09624379 0.04279619 0.0154801 -0.09750729 0.04175239 0.005985736 -0.09666997 0.04257595 0.03292793 -0.09783989 0.04144299 -0.287084 -0.0499078 0.0159288 -0.29 -0.04671645 0.01282137 -0.29 -0.04627686 0.01304244 -0.28388 -0.05907827 0.01451605 -0.29 -0.0439527 0.01381015 -0.287073 -0.04592329 0.01708555 -0.272592 -0.06794929 0.02062439 -0.24557 -0.08074527 0.0210253 -0.2408969 -0.08183157 0.02161985 -0.236202 -0.08280795 0.02227985 -0.231488 -0.08368015 0.02299797 -0.21248 -0.08623999 0.02629995 -0.226756 -0.08445376 0.02376645 -0.222009 -0.0851345 0.02457797 -0.2077029 -0.08667629 0.02719545 -0.2172499 -0.08572798 0.02542495 -0.188565 -0.08777767 0.03083264 -0.138821 -0.08334678 0.04297149 -0.140727 -0.08236396 0.04329454 -0.1388962 -0.08655166 0.04059249 -0.1289114 -0.08730888 0.04127097 -0.12889 -0.08640277 0.04205077 -0.08062195 -0.09133058 0.0428822 -0.07101786 -0.09197157 0.0431326 -0.06140732 -0.09262925 0.04328787 -0.05174702 -0.09329497 0.04335796 -0.04211008 -0.09395056 0.04335325 -0.02284491 -0.09445732 0.04389005 0.01537972 -0.0970236 0.04233545 0.02293002 -0.0976355 0.04169034 0.0329467 -0.09704077 0.04233217 0.08295756 -0.0978316 0.03994309 0.08272707 -0.09804117 0.03969806 0.08250308 -0.09824478 0.03944206 -0.28708 -0.04849416 0.01648497 -0.29 -0.04582828 0.01324129 -0.29 -0.04537099 0.01341766 -0.283876 -0.05728775 0.01618725 -0.280377 -0.06132584 0.01802498 -0.280368 -0.05450946 0.02184998 -0.259433 -0.06146359 0.02839505 -0.263957 -0.06190758 0.02755206 -0.2385948 -0.08056259 0.02387911 -0.231487 -0.08195495 0.02489489 -0.226755 -0.08273625 0.02564728 -0.21248 -0.08447188 0.02818477 -0.222009 -0.0834105 0.02645266 -0.207702 -0.084876 0.02909255 -0.217249 -0.08398616 0.02730166 -0.20292 -0.08520716 0.03001564 -0.1863065 -0.08146172 0.03641855 -0.183784 -0.08382385 0.03540199 -0.188565 -0.08371508 0.03451067 -0.193349 -0.08568477 0.03186994 -0.188565 -0.08584809 0.03278237 -0.1837829 -0.08597195 0.03367459 -0.1574965 -0.08188587 0.04120576 -0.1479189 -0.08210653 0.04247748 -0.1387908 -0.08206492 0.04371559 -0.1387602 -0.08077406 0.04435938 -0.1481784 -0.08642423 0.0393905 -0.1288699 -0.08553612 0.04273509 -0.126337 -0.08089798 0.04570418 -0.08544403 -0.08965706 0.04404008 -0.07583326 -0.0903902 0.04424285 -0.07105916 -0.08944648 0.045363 -0.06621712 -0.09114646 0.04434543 -0.05419009 -0.09210336 0.04435467 -0.04213964 -0.09304612 0.04424262 0.001138567 -0.09456557 0.04431658 0.01545679 -0.09649676 0.04287701 0.03997927 -0.09596657 0.04308897 -0.29 -0.04346746 0.01389437 -0.283872 -0.05537235 0.01755177 -0.259434 -0.05901229 0.02869087 -0.263958 -0.05935806 0.02809798 -0.2338569 -0.07953137 0.0262956 -0.2244415 -0.08111524 0.02776068 -0.202919 -0.08315056 0.03173696 -0.207702 -0.08284747 0.03081125 -0.2005704 -0.08101296 0.03369027 -0.217249 -0.08200228 0.02902054 -0.2124789 -0.0824685 0.02990227 -0.198134 -0.0833888 0.03266906 -0.193349 -0.08357328 0.03359717 -0.1574336 -0.0794683 0.04240071 -0.1387265 -0.0793218 0.04497712 -0.140727 -0.07757085 0.04534935 -0.1386989 -0.07816988 0.04539275 -0.1525766 -0.07707077 0.04398071 -0.140727 -0.08002805 0.04444599 -0.1480279 -0.08434444 0.04105198 -0.128801 -0.08260905 0.0446071 -0.1287767 -0.08158588 0.04513359 -0.126337 -0.0785501 0.0465756 -0.09989732 -0.08697152 0.04483366 -0.09028124 -0.08775502 0.04512661 -0.08067595 -0.08858478 0.04529833 -0.06144267 -0.09032279 0.04533439 -0.05182123 -0.09119808 0.04522609 -0.04215693 -0.09205943 0.04505074 -0.0373966 -0.09144985 0.04563874 0.02299422 -0.09490317 0.0440216 0.01080608 -0.09436404 0.0444287 0.01294976 -0.09368127 0.04474258 0.01305538 -0.09520018 0.04391366 0.02297466 -0.09573423 0.04349291 0.02295267 -0.09666985 0.04273909 0.03297239 -0.0959472 0.04323375 0.06372678 -0.09668594 0.04190665 0.09036058 -0.09707748 0.04039996 -0.283867 -0.0534507 0.01858758 -0.2881764 -0.04199999 0.01605284 -0.2872329 -0.04200011 0.01704615 -0.280371 -0.0567283 0.02095198 -0.280409 -0.04199999 0.02297335 -0.245568 -0.06413215 0.02969646 -0.2291354 -0.0781666 0.02853679 -0.2196588 -0.07952415 0.03010582 -0.2101353 -0.08043783 0.03185099 -0.1908182 -0.07635986 0.03773581 -0.190933 -0.07891005 0.0367701 -0.193349 -0.08128029 0.03508478 -0.138674 -0.07707321 0.0457375 -0.138647 -0.07594519 0.04602736 -0.1478592 -0.07973015 0.04365396 -0.1287438 -0.08016723 0.04576063 -0.128678 -0.07736945 0.04669588 -0.09512233 -0.08561521 0.04611235 -0.08551979 -0.08654284 0.04627257 -0.07590925 -0.08751332 0.0463171 -0.06627649 -0.08850955 0.04626077 -0.05664819 -0.08950984 0.04611891 -0.04700875 -0.09049755 0.04590612 -0.02774739 -0.09235459 0.04532998 0.001158118 -0.09380203 0.0447719 0.03300905 -0.09439367 0.04410284 0.0330742 -0.09161078 0.04480063 0.06853282 -0.09601753 0.04222071 0.09727096 -0.09666687 0.04039996 0.100722 -0.0964266 0.04039996 0.104169 -0.09616285 0.04039996 -0.29 -0.04199999 0.01399999 -0.287065 -0.04371815 0.0172227 -0.29 -0.04249238 0.01398885 -0.283863 -0.05160397 0.01932346 -0.254842 -0.05856919 0.02900958 -0.2408953 -0.06296318 0.03029209 -0.2291587 -0.07573521 0.02981483 -0.2196919 -0.07710635 0.03136986 -0.210084 -0.07802528 0.03311425 -0.2004672 -0.07858896 0.0349465 -0.183784 -0.07905745 0.03809398 -0.140726 -0.07501268 0.04599225 -0.1287115 -0.07880288 0.04626607 -0.09514111 -0.08374142 0.04706114 -0.08553743 -0.0847941 0.04716628 -0.08555972 -0.08291697 0.04789322 -0.0759347 -0.0858919 0.04715418 -0.0663352 -0.08701401 0.04704105 -0.05668604 -0.08814555 0.0468418 -0.04706144 -0.08925592 0.04657429 -0.0374121 -0.09033018 0.04625332 -0.02780359 -0.09133929 0.04589778 -0.01816481 -0.09226983 0.04552119 0.03299498 -0.09498661 0.04381459 0.03305131 -0.09258615 0.04467284 0.07331174 -0.09524017 0.0425077 0.08296799 -0.09505498 0.04220455 0.08294719 -0.09421169 0.04261243 0.12136 -0.09449487 0.04039996 -0.2858374 -0.04200011 0.01845431 -0.2838057 -0.04305261 0.02030479 -0.283859 -0.04987525 0.0198127 -0.2826297 -0.04200005 0.0212965 -0.280365 -0.05243396 0.02244597 -0.2320875 -0.04199999 0.03146928 -0.2293568 -0.07314467 0.03076529 -0.2199433 -0.07452702 0.0323044 -0.1948388 -0.07097339 0.03800338 -0.1999712 -0.07344073 0.03665989 -0.2003328 -0.07604533 0.03592801 -0.2099702 -0.07548683 0.03410363 -0.1763957 -0.07131451 0.04136353 -0.1813067 -0.0739175 0.04013478 -0.1813646 -0.07654589 0.03946977 -0.1385399 -0.07138049 0.04659843 -0.1386241 -0.0749666 0.046238 -0.145518 -0.07733529 0.04483425 -0.12865 -0.07618957 0.0469771 -0.1284973 -0.06967967 0.04755365 -0.09514588 -0.08174049 0.04782676 -0.07593888 -0.08414804 0.04784059 -0.06632316 -0.08540469 0.04768598 -0.05671983 -0.08666163 0.04744708 -0.05671501 -0.08504211 0.04792088 -0.04709088 -0.08790057 0.04713976 -0.03749758 -0.08908963 0.0467832 -0.02785694 -0.09021526 0.04639142 -0.01817327 -0.09125119 0.04598146 0.02301245 -0.09412455 0.04440581 0.0330249 -0.09371137 0.04436558 0.0636816 -0.09456318 0.04318982 0.07332265 -0.09442222 0.04290574 0.092583 -0.09394329 0.04230338 0.1247889 -0.09409129 0.04039996 0.128215 -0.0936644 0.04039996 0.131638 -0.09321409 0.04039996 -0.29 -0.04298138 0.0139538 -0.287069 -0.04477494 0.0171985 -0.283854 -0.04827517 0.02010679 -0.280362 -0.05051565 0.0228036 -0.2408889 -0.04439085 0.03029239 -0.2293334 -0.07053679 0.03143668 -0.2200155 -0.07190442 0.03296297 -0.2107864 -0.07280284 0.03462183 -0.1906617 -0.0737397 0.03842258 -0.150308 -0.07454788 0.04491299 -0.145518 -0.07475388 0.04548084 -0.1285879 -0.07355368 0.04739338 -0.1047745 -0.0783894 0.04821175 -0.09516662 -0.07960933 0.04839402 -0.0855686 -0.08090978 0.04843831 -0.07595306 -0.08226734 0.04836249 -0.06633412 -0.0836538 0.04818415 -0.04709249 -0.08640587 0.04759043 -0.03747916 -0.08771693 0.04721081 -0.02787238 -0.08894908 0.04679971 0.02310609 -0.09013599 0.04515618 0.07813698 -0.0933547 0.04311782 0.09255754 -0.09292572 0.04266828 0.1067523 -0.09241515 0.04218578 0.135058 -0.09274047 0.04039996 0.138474 -0.09224361 0.04039996 -0.2838425 -0.04658991 0.02027344 -0.280359 -0.04875385 0.02297925 -0.276605 -0.04887294 0.02526187 -0.2366586 -0.04199999 0.03082668 -0.2361991 -0.06405961 0.03089159 -0.226751 -0.0683459 0.03220999 -0.2199597 -0.06929069 0.0333392 -0.2098956 -0.07025283 0.03515285 -0.1858969 -0.07117635 0.03967279 -0.1909614 -0.06843638 0.03882348 -0.1837856 -0.06853741 0.04014217 -0.1668584 -0.07144558 0.04294013 -0.1694422 -0.06871104 0.04261088 -0.1646625 -0.06878328 0.04336643 -0.150308 -0.07187891 0.04528379 -0.145518 -0.07209748 0.04585146 -0.09994846 -0.0766648 0.04867571 -0.09033805 -0.07803344 0.04878032 -0.08070045 -0.0794807 0.04875504 -0.07109296 -0.08096837 0.04861837 -0.06147915 -0.08247315 0.04838788 -0.05186361 -0.08396506 0.04808157 -0.04223489 -0.08541673 0.04771679 -0.02860927 -0.08736234 0.04713672 0.06837677 -0.0923348 0.04368996 0.0878514 -0.09180718 0.04311144 0.1065464 -0.09109908 0.04248744 0.1258067 -0.09022736 0.04175966 0.1262039 -0.08802688 0.04185897 0.145298 -0.09117978 0.04039996 0.148706 -0.09061288 0.04039996 -0.242159 -0.04199999 0.03014034 -0.2455358 -0.04199999 0.02977454 -0.2172415 -0.06698119 0.03390657 -0.2124711 -0.06741678 0.03476834 -0.2067514 -0.06782644 0.03583097 -0.1790035 -0.0685966 0.04099458 -0.1742271 -0.06865489 0.04181808 -0.1284634 -0.06823265 0.04751461 -0.097503 -0.07442414 0.0488103 -0.09269255 -0.07513022 0.04886335 -0.08788007 -0.07585793 0.04888296 -0.08306783 -0.07660305 0.04887127 -0.07825237 -0.07736241 0.04883044 -0.07343775 -0.07813149 0.04876279 -0.06862151 -0.07890707 0.04867058 -0.06380498 -0.07968479 0.04855597 -0.05679273 -0.08081394 0.04835581 -0.04724681 -0.08232516 0.04802387 -0.03779864 -0.08376491 0.04764723 -0.02862191 -0.08508342 0.04725146 -0.01259458 -0.08712089 0.04653656 0.07449305 -0.09005129 0.04363453 0.08858919 -0.08961832 0.04320675 0.0974102 -0.08928889 0.04292058 0.1069853 -0.08890217 0.04258853 0.1166595 -0.08847808 0.04223144 0.1358196 -0.08754318 0.04146468 -0.2267089 -0.04199999 0.03229743 -0.2217441 -0.04199999 0.03311973 -0.1810455 -0.05805933 0.04063737 -0.159881 -0.05819392 0.04408156 -0.107118 -0.06098669 0.04859435 -0.1023095 -0.06146091 0.04872137 -0.09750002 -0.06195956 0.0488103 0.09268802 -0.06716102 0.04308015 -0.276325 -0.04199999 0.02540355 -0.248875 -0.04199999 0.02945613 -0.1981327 -0.05768656 0.03746509 -0.191078 -0.05800372 0.03880029 -0.1908898 -0.05568981 0.03891503 -0.1696523 -0.05618846 0.04257583 -0.1742258 -0.05812913 0.04181861 -0.1646692 -0.05816113 0.04336565 -0.1480375 -0.05669587 0.04558014 -0.06380212 -0.06179082 0.04855597 -0.2814412 -0.04199999 0.02223104 -0.09268844 -0.05895406 0.04886335 -0.08787661 -0.05940097 0.04888296 -0.0830633 -0.0598616 0.04887127 -0.07824909 -0.06033349 0.04883044 -0.07343417 -0.06081408 0.04876279 -0.06861841 -0.06130069 0.04867058 -0.05898517 -0.06228172 0.0484212 -0.05416774 -0.06277078 0.04826855 -0.04934978 -0.06325578 0.04810029 -0.044532 -0.06373387 0.04791855 -0.03971421 -0.06420254 0.04772567 -0.03489607 -0.06465905 0.04752379 -0.03007805 -0.06510096 0.04731518 -0.02433341 -0.06558424 0.0470609 -0.007987856 -0.06690394 0.04633396 -0.001177489 -0.06729984 0.04604804 0.003636896 -0.06756681 0.04585486 -0.2756 -0.04199999 0.02573907 -0.2005794 -0.05546236 0.03699994 -0.196707 -0.05555325 0.03778225 -0.1833875 -0.05586594 0.04029178 -0.1757388 -0.05604559 0.04160517 -0.1643804 -0.05631226 0.04337972 -0.1560623 -0.0565074 0.04455339 -0.118701 -0.05738466 0.04781925 -0.11395 -0.05749619 0.0479415 -0.1068508 -0.05766248 0.048101 -0.09969729 -0.05783075 0.04822045 0.0759586 -0.06872308 0.04359132 0.1072176 -0.06268852 0.04257833 0.1213425 -0.06796711 0.04205346 0.1403172 -0.0678271 0.04127627 0.1639698 -0.06402093 0.0402134 -0.0949465 -0.05794227 0.04828429 -0.09019589 -0.05805385 0.04833346 -0.08544528 -0.05816537 0.04836809 -0.08069467 -0.05827689 0.04838806 -0.0759443 -0.05838847 0.04839348 -0.07119399 -0.05849999 0.04838418 -0.06644368 -0.05861145 0.04836034 -0.06169348 -0.05872297 0.04832196 -0.05694335 -0.05883449 0.04826897 -0.05219328 -0.05894607 0.04820138 -0.04744338 -0.05905759 0.04811918 -0.04269349 -0.05916905 0.04802227 -0.03794366 -0.05928057 0.04791086 -0.033194 -0.05939209 0.04778486 -0.02629631 -0.05955398 0.0475772 -0.01679414 -0.05977696 0.04723817 -0.006486773 -0.06001901 0.04680585 5.18404e-5 -0.06017255 0.04649388 0.004800915 -0.06028407 0.04625105 0.06490588 -0.06169515 0.0439828 0.08013093 -0.0620526 0.04351353 0.1253158 -0.06311345 0.04188519 0.1452751 -0.063582 0.04105299 0.009549915 -0.06039559 0.04599356 0.01429885 -0.06050705 0.04572159 0.01904767 -0.06061857 0.04543495 0.09422039 -0.06238347 0.0430423 0.08061486 -0.1001753 9.3599e-4 0.08041906 -0.1001421 0 0.08149427 -0.1006455 7.82007e-4 0.0815674 -0.1007607 0 0.08117109 -0.1004301 0 0.08126121 -0.1004603 8.19502e-4 0.08183676 -0.1008219 0.001609683 0.08221918 -0.100644 0.002994954 0.08241605 -0.1004213 0.003691077 0.08267307 -0.100704 0.003608942 0.08189254 -0.1006508 0.002294003 0.08233356 -0.1008144 0.002891421 0.081968 -0.1004252 0.003067195 0.08157032 -0.1004027 0.002394676 0.08284336 -0.100599 0.003962814 0.0815187 -0.1005418 0.001585245 0.08277577 -0.1002566 0.004322946 0.08301126 -0.100486 0.00431025 0.08159667 -0.100775 4.12088e-4 0.08075159 -0.1002205 0 0.08093798 -0.1002808 8.6585e-4 0.08124595 -0.1003632 0.00165838 0.08157628 -0.1002051 0.003204882 0.08123159 -0.1002377 0.002509474 0.08059638 -0.100129 0.002739846 0.08069682 -0.1000832 0.003525733 0.0811389 -0.1000848 0.003375947 0.08086478 -0.1001453 0.002635598 0.08064532 -0.1001611 0.001822829 0.08041936 -0.1001394 0.002129256 0.08085286 -0.0999822 0.004313349 0.08062565 -0.100047 0.004434823 0.08065807 -0.09996253 0.005198359 0.08102411 -0.09980756 0.004958748 0.0804193 -0.10014 0.005387842 0.08041936 -0.10014 0.004329741 0.08109617 -0.0999509 0.004192829 0.08128905 -0.09976369 0.004814326 0.08095556 -0.1002366 0.001741349 0.08172559 -0.1008059 0.001224815 0.08163768 -0.100786 8.22333e-4 0.08208459 -0.1008413 0.002313435 0.08041936 -0.10014 0.003335654 0.08172589 -0.1000285 0.003925442 0.08209717 -0.100198 0.003791153 0.08134961 -0.09995645 0.004076838 0.08202189 -0.09984183 0.004501163 0.08240288 -0.1000038 0.004390716 0.08160233 -0.09975874 0.004664003 -0.1026106 -0.1207276 0.01128286 -0.1022606 -0.1205455 0 -0.102266 -0.120536 0.01128286 -0.1031395 -0.1209132 0.01128286 -0.1029239 -0.120851 0 -0.1038674 -0.1210108 0.01128286 -0.103478 -0.1209776 0 -0.103868 -0.121 0 -0.1721428 -0.1200737 0 -0.1722485 -0.1195954 0.009499967 -0.171961 -0.121 0.009499967 -0.171961 -0.121 0 -0.1726852 -0.1180467 0.009499967 -0.1728428 -0.1175674 0 -0.1724483 -0.1188414 0 -0.1733039 -0.1163331 0 -0.1731139 -0.1168161 0.009499967 -0.1737228 -0.1153611 0.009499967 -0.173727 -0.115363 0 -0.1729059 -0.1140242 0.009499967 -0.1730309 -0.1141126 0 -0.172556 -0.1138581 0.009499967 -0.1726168 -0.1138753 0 -0.172196 -0.1137744 0.009499967 -0.1721631 -0.11377 0 -0.1718038 -0.1137502 0.009499967 -0.1714932 -0.1137594 0 -0.171494 -0.11377 0.009499967 -0.1732664 -0.1143341 0.009499967 -0.1733007 -0.1143834 0 -0.1735057 -0.1147105 0 -0.1735208 -0.114741 0.009499967 -0.1736492 -0.115067 0 -0.1737373 -0.1153604 0.009499967 -0.173727 -0.115363 0 -0.16793 -0.115586 0.009499967 -0.16793 -0.115586 0 -0.171494 -0.11377 0 -0.171494 -0.11377 0.009499967 -0.1674759 -0.114695 0.009499967 -0.1674759 -0.114695 0 -0.16793 -0.115586 0 -0.16793 -0.115586 0.009499967 -0.202226 -0.09699088 0.009499967 -0.202226 -0.09699088 0 -0.1674759 -0.114695 0 -0.1674759 -0.114695 0.009499967 -0.2026799 -0.09788185 0.009499967 -0.2026799 -0.09788185 0 -0.202226 -0.09699088 0 -0.202226 -0.09699088 0.009499967 -0.199116 -0.0996977 0.009499967 -0.199116 -0.0996977 0 -0.2026799 -0.09788185 0 -0.2026799 -0.09788185 0.009499967 -0.1990701 -0.1018142 0.009499967 -0.1988894 -0.101542 0 -0.1988745 -0.1015127 0.009499967 -0.1990903 -0.1018387 0 -0.1994418 -0.1021822 0.009499967 -0.1993521 -0.1021015 0 -0.1997926 -0.1024184 0 -0.2000725 -0.1025701 0.009499967 -0.2005481 -0.1027846 0 -0.20055 -0.10278 0.009499967 -0.1987417 -0.101126 0 -0.1987351 -0.1010833 0.009499967 -0.1987398 -0.1006673 0 -0.1987442 -0.1006361 0.009499967 -0.1988733 -0.1001573 0 -0.1988365 -0.1002726 0.009499967 -0.1991075 -0.09969276 0.009499967 -0.199116 -0.0996977 0 -0.2029647 -0.103568 0 -0.2020838 -0.1032402 0.009499967 -0.20055 -0.10278 0.009499967 -0.2015709 -0.1030761 0 -0.20055 -0.10278 0 -0.204336 -0.1041544 0 -0.2037872 -0.1039071 0.009499967 -0.2056565 -0.1048237 0 -0.2051378 -0.1045483 0.009499967 -0.2081686 -0.1064181 0 -0.2067806 -0.1054746 0.009499967 -0.2069512 -0.105588 0 -0.2086302 -0.1067578 0.009499967 -0.2100331 -0.1079323 0.009499967 -0.2093354 -0.1073283 0 -0.2115016 -0.1093856 0 -0.2111178 -0.108981 0.009499967 -0.2104555 -0.1083241 0 -0.2130336 -0.1112259 0.009499967 -0.2127122 -0.1107979 0 -0.2121105 -0.1100711 0.009499967 -0.2139 -0.1124693 0.009499967 -0.2138071 -0.1123273 0 -0.2147655 -0.113903 0 -0.2146662 -0.1137349 0.009499967 -0.2153545 -0.1150597 0.009499967 -0.2155997 -0.1155892 0 -0.2159546 -0.1164234 0.009499967 -0.2161715 -0.1169836 0 -0.2165876 -0.1181893 0.009499967 -0.2167401 -0.1187044 0 -0.2170572 -0.1199759 0.009499967 -0.2172695 -0.1209981 0 -0.21726 -0.121 0.009499967 -0.171961 -0.121 0.009499967 -0.103868 -0.121 0.01128286 -0.126245 -0.121 0.01250267 -0.170997 -0.121 0.01498258 -0.193372 -0.121 0.01624256 -0.148621 -0.121 0.01373594 -0.21726 -0.121 0 -0.21726 -0.121 0.009499967 -0.238119 -0.121 0 -0.238119 -0.121 0.01880276 -0.103868 -0.121 0 -0.171961 -0.121 0 -0.215746 -0.121 0.01751595 -0.2387819 -0.1209285 0.01880276 -0.23883 -0.1209172 0 -0.2381195 -0.1210105 0 -0.2381193 -0.1210066 0.01880276 -0.239213 -0.1207939 0 -0.2395795 -0.1206234 0.01880276 -0.2396225 -0.120599 0 -0.239213 -0.1207939 0.01880276 -0.2400335 -0.1203129 0.01880276 -0.2400714 -0.120281 0 -0.2405933 -0.1197015 0.01880276 -0.2406208 -0.1196606 0 -0.240353 -0.120003 0 -0.240353 -0.120003 0.01880276 -0.240819 -0.119307 0 -0.240819 -0.119307 0.01880276 -0.249757 -0.100836 0.005377352 -0.249619 -0.1011199 0.005667448 -0.2531406 -0.0938431 0.007063925 -0.2469249 -0.106689 0.01881664 -0.246832 -0.106881 0.007350802 -0.24665 -0.107258 0.007253646 -0.2531419 -0.09384036 0.00370413 -0.249887 -0.100567 0.005069673 -0.250123 -0.1000789 0.004406988 -0.250009 -0.100315 0.004746913 -0.250228 -0.09986126 0.004052996 -0.250324 -0.09966278 0.003687441 -0.250412 -0.09948259 0.003307461 -0.250489 -0.09932237 0.002917647 -0.253142 -0.09383958 0 -0.250741 -0.09880179 4.30257e-4 -0.250614 -0.09906357 0.002111077 -0.250699 -0.09888929 0.001278698 -0.250662 -0.09896558 0.001696884 -0.250557 -0.09918296 0.002519965 -0.250725 -0.09883469 8.56495e-4 -0.250747 -0.09879046 0 -0.253226 -0.09366577 0.01570725 -0.253278 -0.09355878 0.01648646 -0.249475 -0.101418 0.005937814 -0.2531333 -0.093858 0.008958756 -0.249324 -0.10173 0.00619024 -0.249167 -0.1020539 0.006421983 -0.249005 -0.102389 0.006632089 -0.2488369 -0.1027359 0.006821751 -0.253134 -0.09385639 0.01020079 -0.248666 -0.103091 0.006988406 -0.253137 -0.09384965 0.01103276 -0.2531287 -0.09386783 0.01253998 -0.24849 -0.103454 0.007132053 -0.248311 -0.103825 0.007253348 -0.248129 -0.1042 0.007350265 -0.253137 -0.09385055 0.01337516 -0.247946 -0.104579 0.007423162 -0.253156 -0.09381169 0.01415169 -0.247759 -0.104964 0.007472395 -0.253185 -0.09375005 0.01492899 -0.247574 -0.105347 0.007496774 -0.2472 -0.106119 0.007472455 -0.2473869 -0.105733 0.007496774 -0.247016 -0.106501 0.007423818 -0.246471 -0.107626 0.007133364 -0.253341 -0.09342908 0.01726657 -0.240819 -0.119307 0.01880276 -0.246295 -0.107989 0.006989479 -0.245956 -0.108691 0.006634056 -0.246123 -0.108346 0.006822407 -0.245636 -0.109352 0.006191372 -0.245486 -0.109663 0.005940377 -0.2457939 -0.109027 0.006423354 -0.245341 -0.109962 0.005668997 -0.253415 -0.09327667 0.01804757 -0.245203 -0.110246 0.00537908 -0.245074 -0.110514 0.005072772 -0.244951 -0.110767 0.004748463 -0.240819 -0.119307 0 -0.244837 -0.111003 0.004409193 -0.244732 -0.11122 0.004056513 -0.2446359 -0.11142 0.003688812 -0.244549 -0.1116 0.003310263 -0.244471 -0.111759 0.002921402 -0.244403 -0.1119 0.002520978 -0.244346 -0.112019 0.002114295 -0.244298 -0.112117 0.001700758 -0.244261 -0.112194 0.001279234 -0.244235 -0.112249 8.56495e-4 -0.244219 -0.112282 4.30257e-4 -0.244213 -0.112293 0 -0.253499 -0.09310156 0.01882958 -0.2122445 -0.09194034 0.006830751 -0.245875 -0.1088591 0.006535172 -0.246123 -0.108346 0.006822407 -0.2112204 -0.09206581 0.006546437 -0.245636 -0.109352 0.006191372 -0.210519 -0.09215027 0.006316542 -0.2099083 -0.09222269 0.00609219 -0.2454105 -0.1098188 0.005806565 -0.2093376 -0.09228926 0.005858361 -0.2087576 -0.09235614 0.005594193 -0.245139 -0.1103789 0.005235731 -0.2082165 -0.09241771 0.005319774 -0.2076674 -0.09247928 0.005009829 -0.2448923 -0.1108883 0.004584431 -0.2071465 -0.09253674 0.00468111 -0.2066268 -0.09259349 0.004310369 -0.2446842 -0.1113194 0.003884792 -0.206265 -0.09263271 0.004021108 -0.206031 -0.0926578 0.003818035 -0.205799 -0.09268248 0.003601133 -0.2445091 -0.1116813 0.003127634 -0.205573 -0.09270638 0.003372669 -0.2053599 -0.09272885 0.003137588 -0.205159 -0.09274989 0.002896189 -0.204972 -0.0927695 0.002645671 -0.204796 -0.09278768 0.002387166 -0.2443702 -0.1119684 0.002307116 -0.204637 -0.09280419 0.002117812 -0.20449 -0.09281927 0.001835107 -0.2442752 -0.1121641 0.00147432 -0.204363 -0.09283238 0.001544177 -0.2042559 -0.09284329 0.001246392 -0.204171 -0.09285205 9.42487e-4 -0.20411 -0.09285837 6.3345e-4 -0.2442246 -0.1122706 6.42383e-4 -0.204073 -0.0928623 3.19288e-4 -0.244213 -0.112293 0 -0.20406 -0.09286379 0 -0.2463839 -0.1078052 0.007068216 -0.2133332 -0.09180331 0.007070183 -0.2145367 -0.09164845 0.00727427 -0.24665 -0.107258 0.007253646 -0.246936 -0.1066662 0.007398307 -0.2162728 -0.09141761 0.00745517 -0.2472898 -0.1059334 0.007489681 -0.2179139 -0.09119117 0.007502019 -0.247659 -0.1051707 0.007491767 -0.2191345 -0.09101802 0.007467389 -0.247946 -0.104579 0.007423162 -0.2200403 -0.09088683 0.007396996 -0.24822 -0.1040124 0.007307589 -0.2208573 -0.0907666 0.007305145 -0.24849 -0.103454 0.007132053 -0.2219238 -0.09060692 0.007137179 -0.2487475 -0.1029216 0.006915032 -0.2228097 -0.09047162 0.00695008 -0.2234234 -0.09037685 0.006796598 -0.2490849 -0.1022236 0.006535828 -0.2239746 -0.09029084 0.006638824 -0.2245626 -0.09019804 0.006449043 -0.2251518 -0.09010428 0.006234109 -0.2494015 -0.10157 0.006068229 -0.2257163 -0.09001344 0.00600183 -0.2263092 -0.08991724 0.005727291 -0.2496903 -0.1009732 0.005525946 -0.2268515 -0.08982825 0.005444049 -0.2273942 -0.08973854 0.005125105 -0.2500098 -0.1003133 0.004756093 -0.227928 -0.0896492 0.004768848 -0.22829 -0.08958876 0.004497706 -0.228531 -0.08954811 0.004301786 -0.2502789 -0.0997557 0.00387144 -0.228765 -0.08950847 0.004098296 -0.228991 -0.08947008 0.003886461 -0.22942 -0.08939707 0.003435313 -0.22921 -0.08943289 0.003665983 -0.2504529 -0.09939754 0.003114998 -0.229622 -0.08936268 0.003194868 -0.229813 -0.08932989 0.002941906 -0.2505886 -0.09911686 0.002313375 -0.229995 -0.08929866 0.0026775 -0.2301599 -0.08927059 0.002408504 -0.2303079 -0.0892452 0.002133309 -0.23044 -0.0892226 0.001848936 -0.2506852 -0.09891808 0.001467823 -0.230557 -0.0892027 0.001554667 -0.230655 -0.08918595 0.001252055 -0.230733 -0.08917289 9.42218e-4 -0.2507353 -0.09881329 6.44862e-4 -0.23079 -0.0891633 6.2649e-4 -0.250747 -0.09879046 0 -0.2308239 -0.08915776 3.1371e-4 -0.230836 -0.08915621 0 0.1507989 -0.110944 0 0.1509842 -0.1108904 0.02799999 0.1505754 -0.1109675 0.02799999 0.150575 -0.110957 0 0.1512555 -0.1107283 0.02799999 0.1513509 -0.110638 0 0.151104 -0.1108333 0 0.1515259 -0.1103749 0 0.1515901 -0.1101896 0.02799999 0.151466 -0.1104869 0.02799999 0.1516132 -0.1098701 0.02799999 0.1516153 -0.1098986 0 0.1516 -0.110127 0 0.1515464 -0.1095891 0 0.1515356 -0.109564 0.02799999 0.1513251 -0.10924 0 0.1513221 -0.1092426 0.02799999 0.09727919 -0.1088527 0.007793366 0.08623611 -0.09755337 0.00764048 0.08687466 -0.0969727 0.007857382 0.09650671 -0.1088223 0.007643997 0.09576773 -0.108793 0.007460594 0.08562546 -0.0981087 0.007332503 0.0952183 -0.108771 0.007295906 0.09459805 -0.1087467 0.007081151 0.08503603 -0.09864473 0.006930232 0.09393072 -0.1087206 0.006810903 0.09319192 -0.1086908 0.006455183 0.08447873 -0.09915155 0.006436526 0.09256416 -0.1086665 0.006102144 0.08385318 -0.09972053 0.005722641 0.09206825 -0.108647 0.005782425 0.09175026 -0.108634 0.005556881 0.09144246 -0.108622 0.005319178 0.08330458 -0.1002194 0.004880487 0.09114235 -0.10861 0.005069255 0.09085345 -0.108599 0.004807114 0.08301126 -0.100486 0.00431025 0.0905779 -0.108588 0.004532694 0.09031325 -0.108578 0.004245579 0.08284336 -0.100599 0.003962814 0.08982861 -0.1085579 0.003635406 0.09006226 -0.108568 0.003946185 0.08267307 -0.100704 0.003608942 0.08960956 -0.10855 0.00331217 0.08940666 -0.108542 0.002977132 0.08249056 -0.100765 0.00322318 0.0892269 -0.108535 0.002632498 0.08231079 -0.100817 0.00283569 0.08214157 -0.100836 0.002441763 0.089078 -0.108529 0.00227499 0.08885496 -0.1085206 0.001556634 0.08186483 -0.1008271 0.001705348 0.08163768 -0.100786 8.22333e-4 0.08860838 -0.1085066 -4.20158e-7 0.08159667 -0.100775 4.12088e-4 0.0887416 -0.108516 0.001158297 0.08172559 -0.1008059 0.001224815 0.08156198 -0.100766 0 0.0981146 -0.108886 0.007910847 0.08752173 -0.09638422 0.00797683 0.09919071 -0.1089282 0.007989525 0.08819442 -0.09577262 0.00799936 0.1002922 -0.1089713 0.007996559 0.1014726 -0.1090178 0.007917284 0.08901739 -0.0950241 0.007887482 0.102359 -0.1090531 0.007793843 0.08980035 -0.09431207 0.007622838 0.103118 -0.109083 0.007647335 0.09043222 -0.09373748 0.007295846 0.1038901 -0.1091137 0.007455646 0.1045461 -0.1091396 0.007256448 0.09103971 -0.09318506 0.00686568 0.105157 -0.1091639 0.007036626 0.1057138 -0.1091857 0.006807506 0.1064285 -0.1092141 0.00646615 0.0915727 -0.0927003 0.006378293 0.1071065 -0.1092409 0.006082594 0.09205871 -0.09225827 0.005823791 0.107571 -0.109259 0.005782365 0.09262049 -0.09174746 0.005008041 0.107888 -0.109272 0.005556702 0.108496 -0.109296 0.005069613 0.108197 -0.109284 0.005319297 0.108784 -0.109307 0.004807472 0.109061 -0.109318 0.004533171 0.09317529 -0.09124296 0.003892302 0.109325 -0.109328 0.004246592 0.109574 -0.109338 0.003947734 0.109809 -0.109347 0.003636598 0.0935344 -0.09091639 0.002835333 0.110029 -0.109356 0.003313779 0.110228 -0.109364 0.002980053 0.110572 -0.109378 0.002279162 0.110409 -0.109371 0.002634882 0.09377712 -0.09069561 0.001757383 0.110709 -0.109383 0.00191605 0.110824 -0.109388 0.00154376 0.110913 -0.109391 0.001161932 0.09389477 -0.09058856 6.85475e-4 0.1110358 -0.109397 0 0.09391599 -0.09056937 0 0.13963 -0.0976848 0.02799999 0.09820187 -0.0965535 0.02799999 0.08520179 -0.108376 0.02799999 0.150575 -0.110957 0.02799999 0.150735 -0.110951 0.02799999 0.150891 -0.1109189 0.02799999 0.151179 -0.110783 0.02799999 0.1513029 -0.110682 0.02799999 0.151041 -0.110863 0.02799999 0.15141 -0.110563 0.02799999 0.15156 -0.110282 0.02799999 0.1514959 -0.110429 0.02799999 0.151614 -0.109968 0.02799999 0.1516 -0.110127 0.02799999 0.151566 -0.1096529 0.02799999 0.151603 -0.109808 0.02799999 0.1515049 -0.1095049 0.02799999 0.151317 -0.109247 0.02799999 0.151422 -0.109368 0.02799999 0.13963 -0.0976848 0.02799999 0.151317 -0.109247 0 0.13963 -0.0976848 0 0.151317 -0.109247 0.02799999 0.13963 -0.0976848 0 0.151317 -0.109247 0 0.111037 -0.109396 0 0.09358906 -0.09008187 0 0.09391599 -0.09056937 0 0.09368336 -0.09025716 0 0.09379237 -0.0904197 0 0.09345048 -0.08968865 0 0.0935111 -0.08989191 0 0.0934121 -0.08947867 0 0.09339606 -0.08926397 0 0.09340345 -0.08904677 0 0.09343397 -0.08883368 0 0.0934872 -0.08862519 0 0.0935626 -0.08842378 0 0.20638 -0.09150469 0 0.2077 -0.09205108 0 0.207534 -0.09191018 0 0.2065809 -0.09152019 0 0.206778 -0.09155559 0 0.20697 -0.09161078 0 0.207164 -0.09168857 0 0.207354 -0.09178841 0 0.20785 -0.09220975 0 0.207983 -0.0923835 0 0.208094 -0.09256899 0 0.208184 -0.0927639 0 0.2082509 -0.09296298 0 0.208296 -0.09315925 0 0.20832 -0.09335666 0 0.208325 -0.0935586 0 0.2081609 -0.09955638 0 0.151422 -0.109368 0 0.1515049 -0.109504 0 0.151614 -0.109967 0 0.1516 -0.110127 0 0.150575 -0.110957 0 0.151566 -0.109652 0 0.15156 -0.110281 0 0.151497 -0.110428 0 0.15118 -0.110783 0 0.151041 -0.110862 0 0.15141 -0.110563 0 0.151304 -0.110682 0 0.150891 -0.1109189 0 0.150735 -0.110951 0 0.151603 -0.109808 0 0.38341 -0.135217 0.004999995 0.349684 -0.119871 0.004999995 0.341093 -0.12046 0.004999995 0.36686 -0.118639 0.004999995 0.358272 -0.119264 0.004999995 0.38403 -0.117336 0.004999995 0.375446 -0.117996 0.004999995 0.401195 -0.115961 0.004999995 0.392613 -0.116657 0.004999995 0.409775 -0.1152459 0.004999995 0.434379 -0.141104 0.004999995 0.418354 -0.114514 0.004999995 0.426932 -0.113764 0.004999995 0.435507 -0.112996 0.004999995 0.444082 -0.11221 0.004999995 0.452655 -0.111406 0.004999995 0.455 -0.06205195 0.006858885 0.455 -0.06240534 0.006542146 0.455 -0.07932728 0.0136674 0.455 -0.074225 0.002999961 0.455 -0.08068937 0.009465575 0.455 -0.08056318 0.01008635 0.455 -0.07091319 0.02189069 0.455 -0.07033181 0.02213895 0.455 -0.05963045 0.008330762 0.455 -0.06974309 0.02236658 0.455 -0.08079367 0.008841693 0.455 -0.06274199 0.00620681 0.455 -0.08004266 0.0119099 0.455 -0.07982486 0.01250296 0.455 -0.06434667 0.003877699 0.455 -0.06413209 0.004298448 0.455 -0.0790472 0.01423388 0.455 -0.07874488 0.01479065 0.455 -0.0795865 0.01308965 0.455 -0.06129884 0.007433116 0.455 -0.06168377 0.007155299 0.455 -0.07808059 0.01586675 0.455 -0.07842236 0.0153355 0.455 -0.07516396 0.01918339 0.455 -0.06048935 0.007925391 0.455 -0.07563406 0.01875877 0.455 -0.07733839 0.0168913 0.455 -0.07771885 0.01638627 0.455 -0.07652127 0.01785749 0.455 -0.06089955 0.007690727 0.455 -0.07693976 0.01738095 0.455 -0.0760858 0.01831698 0.455 -0.07366806 0.02034986 0.455 -0.06006586 0.008138954 0.455 -0.07314217 0.02070099 0.455 -0.07260376 0.0210306 0.455 -0.07418119 0.01997756 0.455 -0.07148516 0.02162349 0.455 -0.07467949 0.01958966 0.455 -0.08023965 0.01130855 0.455 -0.06305921 0.005856037 0.455 -0.08041369 0.0107004 0.455 -0.06363767 0.005103647 0.455 -0.06335777 0.005488157 0.455 -0.06389576 0.004707098 0.455 -0.06453937 0.00344485 0.455 -0.06471025 0.002999961 0.455 -0.07204866 0.02133685 0.455 -0.08087641 0.008216083 0.455 -0.08097517 0.006957173 0.455 -0.08093696 0.007587075 0.455 -0.08099037 0.006339192 0.455 -0.06914645 0.0225743 0.455 -0.06854128 0.02276325 0.455 -0.06793099 0.02292835 0.455 -0.0809735 0.004445612 0.455 -0.0673148 0.02306848 0.455 -0.08095818 0.003526687 0.455 -0.06669247 0.02318328 0.455 -0.06606799 0.02327746 0.455 -0.05918866 0.008497893 0.455 -0.06544077 0.02334827 0.455 -0.06418067 0.02343207 0.455 -0.06352609 0.02344757 0.455 -0.06481111 0.02339696 0.455 -0.08093112 0 0.455 -0.05873715 0.008642017 0.455 -0.05827647 0.008763015 0.455 -0.057814 0.008858501 0.455 -0.074225 0 0.455 -0.05734574 0.008929729 0.455 -0.05091035 0.02344816 0.455 -0.05405014 0.008733093 0.455 -0.05451428 0.008835732 0.455 -0.05592638 0.008994817 0.455 -0.0563997 0.008998215 0.455 -0.05687177 0.008976638 0.455 -0.05281162 0.02344745 0.455 -0.05545139 0.008966565 0.455 -0.05498087 0.008913516 0.455 -0.05179226 0.02345544 0.455 -0.0502786 0.02343505 0.455 -0.04964697 0.02341514 0.455 -0.04901546 0.02338826 0.455 -0.05359315 0.008606553 0.455 -0.05270308 0.008282065 0.455 -0.05314487 0.008456349 0.455 -0.05185216 0.007866084 0.455 -0.05227106 0.008084893 0.455 -0.0510475 0.00736159 0.455 -0.05144369 0.007624626 0.455 -0.05030339 0.006777167 0.455 -0.05066835 0.00707972 0.455 -0.04962319 0.006116747 0.455 -0.0499531 0.006454706 0.455 -0.04931056 0.005760788 0.455 -0.04901522 0.005387008 0.455 -0.074225 0.002999961 0.48 -0.074225 0.002999961 0.48 -0.074225 0 0.455 -0.074225 0 0.48 -0.074225 0 0.48 -0.07958817 0 0.48 -0.074225 0.002999961 0.48 -0.07961416 0.003827154 0.48 -0.07961606 0.003191709 0.48 -0.06314265 0.02181816 0.48 -0.06186759 0.02188068 0.48 -0.06250619 0.02186065 0.48 -0.07959216 0.00446403 0.48 -0.0795052 0.005735516 0.48 -0.07955807 0.005100488 0.48 -0.07933628 0.007000565 0.48 -0.07943016 0.006368756 0.48 -0.06128066 0.007445752 0.48 -0.06087946 0.007702767 0.48 -0.07804858 0.01126438 0.48 -0.07891577 0.008866608 0.48 -0.06272977 0.006219744 0.48 -0.06239324 0.006553769 0.48 -0.07684469 0.01351505 0.48 -0.05960488 0.008341073 0.48 -0.07649546 0.01404935 0.48 -0.0771746 0.01296859 0.48 -0.06004106 0.008150815 0.48 -0.05915826 0.008508324 0.48 -0.07573956 0.01507997 0.48 -0.07612717 0.01457077 0.48 -0.03463166 0.005740225 0.48 -0.03471004 0.006374299 0.48 -0.04870295 0.004941225 0.48 -0.05870574 0.008651256 0.48 -0.0376687 0.01405358 0.48 -0.05354517 0.008591532 0.48 -0.05309516 0.00843811 0.48 -0.05061936 0.007040917 0.48 -0.03563147 0.01008677 0.48 -0.05099946 0.007327377 0.48 -0.05180168 0.007837891 0.48 -0.03611129 0.01127058 0.48 -0.03638207 0.01184839 0.48 -0.04431575 0.0198909 0.48 -0.04488879 0.02017337 0.48 -0.05294167 0.02188241 0.48 -0.05588334 0.008993446 0.48 -0.05541026 0.008962988 0.48 -0.04111087 0.01780426 0.48 -0.05493557 0.0089069 0.48 -0.0406239 0.01739197 0.48 -0.06869578 0.02043515 0.48 -0.0606966 0.0218932 0.48 -0.05683547 0.008979141 0.48 -0.0594663 0.02188289 0.48 -0.06628459 0.0212692 0.48 -0.0656656 0.02142357 0.48 -0.06750428 0.02089327 0.48 -0.06689715 0.02109289 0.48 -0.06377905 0.02175319 0.48 -0.06441205 0.02166575 0.48 -0.06504046 0.02155607 0.48 -0.06810349 0.02067399 0.48 -0.0692811 0.02017694 0.48 -0.05635839 0.008998811 0.48 -0.06985515 0.01989805 0.48 -0.04375278 0.01958876 0.48 -0.04320019 0.01927059 0.48 -0.04265779 0.01893377 0.48 -0.04161328 0.01820057 0.48 -0.03803759 0.01457446 0.48 -0.03842455 0.01508128 0.48 -0.03883105 0.01557564 0.48 -0.05400508 0.008721888 0.48 -0.03698688 0.01297438 0.48 -0.05265527 0.008261799 0.48 -0.03667408 0.01241648 0.48 -0.03969407 0.01651656 0.48 -0.04015165 0.01696288 0.48 -0.0544672 0.008826553 0.48 -0.04666805 0.02088075 0.48 -0.04547119 0.02043306 0.48 -0.0460661 0.02066725 0.48 -0.0472753 0.02107506 0.48 -0.0478881 0.021254 0.48 -0.05165988 0.02184128 0.48 -0.04975879 0.02164745 0.48 -0.04850578 0.02140986 0.48 -0.04912889 0.02154159 0.48 -0.05039036 0.02173376 0.48 -0.05102419 0.02179795 0.48 -0.0522964 0.0218718 0.48 -0.03925436 0.01605439 0.48 -0.03731828 0.01351976 0.48 -0.05222219 0.008060574 0.48 -0.05139505 0.007594227 0.48 -0.03586107 0.01068228 0.48 -0.05025619 0.00673598 0.48 -0.03542256 0.009483635 0.48 -0.03523439 0.00887221 0.48 -0.0499081 0.00641036 0.48 -0.04957765 0.006067216 0.48 -0.03507035 0.008255898 0.48 -0.04926717 0.005708634 0.48 -0.03492885 0.00763303 0.48 -0.03480947 0.007004559 0.48 -0.04897505 0.005332589 0.48 -0.04845285 0.004537999 0.48 -0.03457629 0.005103707 0.48 -0.04822409 0.004121005 0.48 -0.07491219 0.01605147 0.48 -0.0753346 0.01557356 0.48 -0.04801696 0.003691256 0.48 -0.03454637 0.004466772 0.48 -0.04783368 0.0032534 0.48 -0.03453981 0.003778576 0.48 -0.0476737 0.002806067 0.48 -0.04753708 0.002348661 0.48 -0.03454518 0.002551078 0.48 -0.03456008 0.001717448 0.48 -0.04742509 0.001887202 0.48 -0.04733794 0.00142157 0.48 -0.0472756 9.51839e-4 0.48 -0.0345757 0 0.48 -0.06046527 0.007938325 0.48 -0.04723787 4.77978e-4 0.48 -0.04722499 0 0.48 -0.06335097 0.005497157 0.48 -0.07921886 0.007627189 0.48 -0.05824548 0.008770108 0.48 -0.07447201 0.01651465 0.48 -0.07401639 0.01696109 0.48 -0.06304937 0.005867183 0.48 -0.07907837 0.008248925 0.48 -0.07354438 0.01739156 0.48 -0.05777776 0.00886482 0.48 -0.07305639 0.01780587 0.48 -0.07255548 0.01820057 0.48 -0.0785259 0.01008039 0.48 -0.07873165 0.009476542 0.48 -0.06203728 0.006871163 0.48 -0.07204008 0.01857739 0.48 -0.05730819 0.008934497 0.48 -0.07151126 0.01893609 0.48 -0.06166577 0.007169008 0.48 -0.07829827 0.01067745 0.48 -0.07041889 0.01959717 0.48 -0.07097136 0.0192759 0.48 -0.04212856 0.01857727 0.48 -0.07777708 0.01184278 0.48 -0.0774849 0.01241165 0.48 -0.06363046 0.005114316 0.48 -0.06412988 0.004302561 0.48 -0.06389015 0.004715919 0.48 -0.06453877 0.00344634 0.48 -0.0643453 0.0038805 0.48 -0.06471025 0.002999961 0.473933 -0.1037859 6.21943e-4 0.4483742 -0.1451077 7.03393e-4 0.4744314 -0.1036557 3.73999e-4 0.4746851 -0.1035903 2.44381e-4 0.449355 -0.145388 0 0.4749028 -0.1035349 1.3105e-4 0.4751502 -0.1034717 2.05537e-7 0.4737329 -0.1038389 7.18245e-4 0.4735626 -0.1038843 7.99626e-4 0.4733689 -0.1039367 8.90728e-4 0.4731583 -0.1039932 9.88272e-4 0.4729032 -0.1040623 0.001104295 0.447174 -0.1447642 0.001468658 0.4723337 -0.1042187 0.001355767 0.4720945 -0.1042852 0.001457393 0.4718505 -0.1043532 0.001559257 0.4716264 -0.1044171 0.001651644 0.471352 -0.1044948 0.00176239 0.446132 -0.144466 0.002055287 0.4706925 -0.1046839 0.002018272 0.4704527 -0.1047537 0.002108097 0.4702256 -0.1048206 0.002191305 0.4451089 -0.1441743 0.002575337 0.469929 -0.1049074 0.002297759 0.4696532 -0.1049892 0.002394914 0.4691284 -0.1051461 0.002572953 0.4689183 -0.1052096 0.002641737 0.4687055 -0.1052737 0.002710402 0.4684711 -0.1053447 0.00278449 0.4682169 -0.105423 0.002863466 0.4437347 -0.1437811 0.003180205 0.4678577 -0.1055338 0.002971827 0.4675623 -0.1056248 0.003058195 0.4672481 -0.1057227 0.00314778 0.4670288 -0.1057916 0.003208756 0.4668255 -0.1058553 0.003264129 0.4666481 -0.1059117 0.003311514 0.4664325 -0.1059799 0.003368198 0.4661108 -0.1060826 0.003450751 0.442637 -0.1434659 0.003591895 0.4658182 -0.106176 0.00352329 0.4654325 -0.1063005 0.003616511 0.4650774 -0.1064156 0.003698289 0.4415522 -0.1431567 0.003947973 0.4647534 -0.1065214 0.003770709 0.4644209 -0.1066327 0.003843069 0.4642217 -0.1067016 0.00388509 0.4640059 -0.1067767 0.003929913 0.4633378 -0.1070125 0.004062175 0.4631337 -0.1070855 0.004100024 0.4629085 -0.1071665 0.004141211 0.4626808 -0.107249 0.004181683 0.4400766 -0.1427342 0.004342794 0.4623073 -0.1073859 0.004245996 0.4619361 -0.107522 0.004306375 0.4617568 -0.1075887 0.004334688 0.4615176 -0.1076781 0.004371225 0.4612962 -0.1077612 0.004404127 0.4606294 -0.1080151 0.004497289 0.438946 -0.1424109 0.004577517 0.4601749 -0.1081904 0.004555046 0.4598982 -0.1082978 0.004588544 0.4592327 -0.1085598 0.004661798 0.4377769 -0.1420758 0.004769563 0.4589316 -0.1086797 0.004692196 0.4586617 -0.1087886 0.004718184 0.4584383 -0.1088787 0.00473988 0.4578382 -0.1091253 0.004793822 0.4575773 -0.1092339 0.004814982 0.4572999 -0.10935 0.004836201 0.456991 -0.10948 0.004858493 0.4362867 -0.1416503 0.004929661 0.4565814 -0.1096538 0.004885554 0.456267 -0.1097887 0.00490427 0.4560797 -0.1098697 0.004914641 0.4558672 -0.1099612 0.004925608 0.4556168 -0.1100703 0.004937648 0.4550995 -0.1102974 0.004959285 0.4548967 -0.1103869 0.004966199 0.4546819 -0.1104823 0.004973053 0.4544018 -0.1106078 0.004980802 0.435149 -0.141324 0.004987597 0.4540754 -0.110755 0.004988133 0.4537591 -0.1108979 0.004993796 0.4534913 -0.1110203 0.004997134 0.4532875 -0.1111136 0.004998803 0.434379 -0.141104 0.004999995 0.452921 -0.1112822 0.005000293 0.452655 -0.111406 0.004999995 0.437767 -0.1461369 0.003585338 0.4338784 -0.1454411 0.004004716 0.4438247 -0.1438069 0.003143787 0.442059 -0.144587 0.003479301 0.441794 -0.145812 0.003074765 0.437998 -0.14485 0.004143536 0.4340015 -0.1443768 0.004443287 0.4414591 -0.1431301 0.003976881 0.438202 -0.143541 0.004503667 0.4401463 -0.1427541 0.004326343 0.4341067 -0.1434599 0.004713714 0.4342013 -0.1426435 0.004881203 0.438524 -0.1422901 0.004655957 0.4370526 -0.141868 0.00485444 0.4342876 -0.1418971 0.004972994 0.435461 -0.1414137 0.004976928 0.434379 -0.141104 0.004999995 0.441125 -0.148115 0.001748085 0.444961 -0.147805 8.65046e-4 0.441481 -0.147001 0.002496838 0.437514 -0.147357 0.002829253 0.445876 -0.148393 0 0.445491 -0.1485739 0 0.4337556 -0.1465016 0.003398239 0.443496 -0.149277 0 0.440733 -0.149118 8.41735e-4 0.433664 -0.147294 0.002824485 0.443902 -0.149161 0 0.437246 -0.148465 0.001888334 0.4335799 -0.148023 0.002180278 0.436973 -0.149422 7.88715e-4 0.4399521 -0.1498703 -1.49404e-6 0.4416463 -0.1496716 0 0.4408224 -0.1497854 0 0.4334629 -0.149042 0.001018941 0.4356873 -0.149906 0 0.4367725 -0.1499528 1.29207e-7 0.4348778 -0.149852 -2.12641e-7 0.4333839 -0.1497157 5.37099e-6 0.433987 -0.1497725 0 0.4378128 -0.1499621 0 0.4386377 -0.1499466 0 0.433517 -0.148566 0.001600623 0.439318 -0.1499159 0 0.4424526 -0.1495246 0 0.444303 -0.149034 0 0.4446838 -0.1489058 4.47149e-6 0.446983 -0.147763 0 0.445361 -0.146711 0.001438021 0.442637 -0.1434659 0.003591895 0.448303 -0.146701 0 0.445696 -0.145572 0.00186342 0.4450332 -0.1441527 0.0026111 0.4463729 -0.1445352 0.001928865 0.448873 -0.146071 0 0.449124 -0.1457369 0 0.4483764 -0.1451082 7.00858e-4 0.447454 -0.1448439 0.001295447 0.449355 -0.145388 0 0.446254 -0.1481969 0 0.447992 -0.146992 0 0.443081 -0.149383 0 0.447331 -0.147522 0 0.448601 -0.146392 0 0.445098 -0.1487399 0 0.446624 -0.147988 0 0.447669 -0.147266 0 0.415 -0.147267 5.09898e-4 0.415 -0.146919 0.000999987 0.415 -0.129584 0.000999987 0.415 -0.129584 0 0.415 -0.147584 0 0.415 -0.129584 0.000999987 0.39 -0.127696 0.000999987 0.39 -0.127696 0 0.415 -0.129584 0 0.39 -0.144379 5.09898e-4 0.39 -0.127696 0.000999987 0.39 -0.144032 0.000999987 0.39 -0.127696 0 0.39 -0.1446959 0 0.415 -0.147584 0 0.433385 -0.149707 0 0.4334288 -0.1493346 6.05975e-4 0.415 -0.147267 5.09898e-4 0.4335728 -0.1480842 0.002119362 0.3826559 -0.1417441 0.002542376 0.382572 -0.1424733 0.001833498 0.4334964 -0.1487469 0.001392126 0.3827913 -0.1405753 0.003424108 0.4337474 -0.146573 0.00335133 0.4336564 -0.1473594 0.002771198 0.382718 -0.1412129 0.0029729 0.4339702 -0.1446467 0.004349231 0.3829942 -0.1388217 0.004321575 0.4338472 -0.1457118 0.003861248 0.3828876 -0.1397388 0.003907024 0.4341246 -0.1433043 0.004757523 0.3831013 -0.1378874 0.004634857 0.3832099 -0.1369526 0.004849135 0.4342577 -0.1421554 0.004947423 0.3833205 -0.1359885 0.004972457 0.4343792 -0.1411041 0.005005896 0.38341 -0.135217 0.004999995 0.382513 -0.142983 0.001235842 0.39 -0.144379 5.09898e-4 0.3824603 -0.14344 6.16585e-4 0.39 -0.1446959 0 0.39 -0.144032 0.000999987 0.415 -0.146919 0.000999987 0.382416 -0.14382 0 0.3578419 -0.1367781 0.002921581 0.3578372 -0.1377544 0.002371966 0.354015 -0.1377043 0.001758217 0.3540576 -0.1367989 0.002334296 0.354918 -0.13859 0.001230061 0.3577012 -0.1386752 0.001682043 0.3503764 -0.1368167 0.001676797 0.360523 -0.140485 3.97857e-4 0.358585 -0.140401 0 0.360402 -0.140748 0 0.351248 -0.137667 0.001256227 0.347636 -0.136828 0.001126945 0.347668 -0.1360059 0.001633286 0.349424 -0.137641 9.0189e-4 0.345864 -0.1360459 0.001255095 0.347742 -0.1380259 0 0.345842 -0.136834 7.40719e-4 0.345944 -0.137581 0 0.34415 -0.137122 0 0.34408 -0.136085 8.56887e-4 0.342314 -0.136124 4.38502e-4 0.342357 -0.13665 0 0.3616365 -0.1377959 0.002904474 0.3615625 -0.1387918 0.002236664 0.340568 -0.1361629 0 0.36173 -0.1367542 0.003437399 0.3654754 -0.138904 0.002724647 0.3654565 -0.1399067 0.001934051 0.3655899 -0.137837 0.003377437 0.3656625 -0.1367276 0.003874838 0.3695772 -0.1378724 0.00377804 0.3696938 -0.1366967 0.004239797 0.3828354 -0.1401896 0.003661036 0.380804 -0.139297 0.00399208 0.382764 -0.140811 0.00326395 0.3694419 -0.139012 0.003148198 0.3736453 -0.1379041 0.004111111 0.3737801 -0.1366611 0.004529058 0.3824638 -0.1434105 6.59143e-4 0.38007 -0.1427361 0.001176357 0.380567 -0.1436409 0 0.38263 -0.141972 0.002331972 0.3826959 -0.1414006 0.002830028 0.380661 -0.140584 0.003242313 0.382416 -0.14382 0 0.3735575 -0.1391214 0.003513813 0.3734555 -0.1402716 0.002735197 0.3804797 -0.1417815 0.002269983 0.382568 -0.1425079 0.001796722 0.377828 -0.1379336 0.004377961 0.3776745 -0.139223 0.003811776 0.380956 -0.137951 0.004528701 0.382913 -0.139524 0.004010915 0.3829916 -0.1388446 0.004312992 0.3779379 -0.1366226 0.004744112 0.3737803 -0.1354294 0.004765987 0.3776912 -0.1353433 0.004912793 0.38111 -0.136593 0.00485444 0.383072 -0.138142 0.004556357 0.3831558 -0.137419 0.004754424 0.383239 -0.136699 0.004888057 0.381262 -0.1352649 0.004983901 0.3833231 -0.1359654 0.004974484 0.38341 -0.135217 0.004999995 0.349542 -0.138457 0 0.351346 -0.1388739 0 0.353064 -0.13853 9.08162e-4 0.353151 -0.139277 0 0.349491 -0.135966 0.001991331 0.35496 -0.139666 0 0.351333 -0.1359249 0.00232923 0.356771 -0.1400409 0 0.356764 -0.139486 7.45053e-4 0.353194 -0.135884 0.002647042 0.355074 -0.135843 0.002944707 0.358647 -0.1395789 0.001032829 0.356974 -0.135801 0.003222286 0.3633103 -0.1406679 7.60686e-4 0.364044 -0.1414 0 0.365869 -0.141705 0 0.362222 -0.141081 0 0.3616057 -0.1397247 0.0014503 0.358893 -0.135758 0.003479719 0.36083 -0.135716 0.003717064 0.3675209 -0.1409498 0.001232028 0.367696 -0.141996 0 0.362787 -0.135672 0.003934264 0.36945 -0.1400917 0.002366244 0.365598 -0.1356105 0.004209995 0.369527 -0.142273 0 0.37136 -0.142536 0 0.3715192 -0.1411865 0.001641392 0.3696104 -0.1355212 0.004525959 0.373196 -0.142785 0 0.375035 -0.14302 0 0.3759148 -0.1424443 8.74886e-4 0.3754516 -0.1414479 0.001954197 0.3775841 -0.1404532 0.003049433 0.376876 -0.143241 0 0.37872 -0.1434479 0 0.382513 -0.142983 0.001235842 0.3595308 -0.1357443 0.003563225 0.3076063 -0.1161621 0.004019677 0.302608 -0.115508 0.003681957 0.3634962 -0.1356565 0.004010498 0.3143995 -0.1170465 0.00439763 0.3677968 -0.1355617 0.004394233 0.3714898 -0.13548 0.004645347 0.3216735 -0.117986 0.004698276 0.3757566 -0.1353857 0.004850327 0.3288786 -0.1189091 0.004895687 0.3801012 -0.1352908 0.004969716 0.3358285 -0.1197947 0.004991471 0.38341 -0.135217 0.004999995 0.341093 -0.12046 0.004999995 0.356974 -0.135801 0.003222286 0.299139 -0.115052 0.003420233 0.295674 -0.114595 0.003134787 0.355074 -0.135843 0.002944707 0.292214 -0.114136 0.002825736 0.353194 -0.135884 0.002647042 0.351333 -0.1359249 0.00232923 0.288759 -0.113677 0.002493023 0.285309 -0.1132169 0.002136647 0.349491 -0.135966 0.001991331 0.281864 -0.112756 0.001756608 0.347668 -0.1360059 0.001633286 0.345864 -0.1360459 0.001255095 0.278424 -0.112294 0.001352965 0.274988 -0.111831 9.25647e-4 0.34408 -0.136085 8.56887e-4 0.271557 -0.111366 4.74655e-4 0.342314 -0.136124 4.38502e-4 0.268131 -0.1109009 0 0.340568 -0.1361629 0 0.2139154 -0.0997135 0.006002843 0.2145656 -0.09372901 0.006002843 0.213591 -0.09370243 0.005957961 0.212974 -0.09968781 0.005884587 0.2126628 -0.09367704 0.005773782 0.2120367 -0.09966212 0.005620181 0.2117534 -0.09365224 0.005424618 0.211184 -0.09963887 0.005213141 0.211214 -0.09363746 0.005131363 0.2107596 -0.09362506 0.004830062 0.2105451 -0.09962147 0.004792273 0.2100485 -0.09360569 0.004220545 0.2098144 -0.0996015 0.004148066 0.209351 -0.09958887 0.003587841 0.209516 -0.09359109 0.003589034 0.2090061 -0.09957945 0.003077089 0.2092085 -0.09358268 0.003139793 0.2086604 -0.09956997 0.002403736 0.2088536 -0.09357303 0.002470076 0.2084659 -0.09956467 0.001890122 0.2085794 -0.09356552 0.001741647 0.2082989 -0.09956014 0.001292049 0.2084037 -0.09356069 9.87118e-4 0.208182 -0.09955692 5.39822e-4 0.2083149 -0.09355831 3.33948e-7 0.2081609 -0.09955638 0 0.2148901 -0.09974008 0.005957961 0.215507 -0.09375476 0.005884587 0.2158182 -0.09976547 0.005773782 0.2164442 -0.09378033 0.005620181 0.2167275 -0.09979027 0.005424618 0.217297 -0.09380358 0.005213141 0.217267 -0.09980499 0.005131363 0.2179358 -0.09382098 0.004792332 0.2177214 -0.09981739 0.004830121 0.218355 -0.09383249 0.004441499 0.218303 -0.09983336 0.004341065 0.2189301 -0.09384822 0.00385338 0.2189393 -0.09985065 0.0036363 0.2194747 -0.09386307 0.003077208 0.2195456 -0.09986722 0.002655565 0.2198206 -0.09387254 0.002403557 0.2199014 -0.09987699 0.001742005 0.220015 -0.09387779 0.001890122 0.220182 -0.09388238 0.001292288 0.2200772 -0.09988176 9.87153e-4 0.220299 -0.09388554 5.3956e-4 0.2201661 -0.09988415 3.33889e-7 0.22032 -0.09388619 0 0.2203486 -0.0935713 -2.2119e-7 0.220278 -0.09353756 9.92569e-4 0.208339 -0.09158855 0.004700362 0.207648 -0.09156978 0.003642261 0.207605 -0.09153819 0.00425446 0.208124 -0.09155237 0.004987537 0.208413 -0.0915603 0.005329132 0.2088479 -0.0918402 0.004299461 0.208603 -0.09168606 0.004493534 0.209631 -0.0918616 0.00515002 0.207378 -0.09153199 0.003869414 0.210693 -0.0920906 0.005621075 0.209818 -0.0920667 0.004939913 0.207141 -0.09155589 0.002484798 0.206988 -0.09152126 0.003059625 0.207942 -0.09166806 0.003481984 0.207457 -0.09165477 0.002375483 0.208216 -0.09182286 0.003331601 0.206829 -0.09151697 0.002641975 0.206831 -0.09154736 0.001259565 0.2066822 -0.09153109 0 0.206431 -0.09150606 8.97431e-4 0.20658 -0.09151017 0.001778304 0.206493 -0.09150779 0.001339912 0.206393 -0.09150511 4.50783e-4 0.20638 -0.09150469 0 0.209195 -0.09161198 0.005630254 0.207751 -0.09181016 0.002272844 0.209048 -0.09157758 0.005964756 0.209389 -0.09158688 0.006253242 0.211668 -0.09211719 0.006148874 0.210543 -0.09188646 0.005860149 0.2113029 -0.09166955 0.007008135 0.210192 -0.09163916 0.006406545 0.210507 -0.0916174 0.007000625 0.211883 -0.0929715 0.005605041 0.210923 -0.09262919 0.005247294 0.211833 -0.09265398 0.005739986 0.215888 -0.09276479 0.006076097 0.214891 -0.09245187 0.006445765 0.215945 -0.09248059 0.006269931 0.2148669 -0.09273689 0.006246507 0.213824 -0.09242266 0.006445765 0.212498 -0.09170216 0.007418513 0.213035 -0.09168648 0.007886409 0.213744 -0.09173619 0.007626533 0.21377 -0.09182715 0.007290959 0.2147021 -0.09373289 0.005991578 0.213834 -0.09336155 0.006009757 0.21483 -0.09338879 0.006009757 0.215008 -0.09177076 0.007626533 0.214978 -0.09186017 0.007290959 0.2162539 -0.0918048 0.007418513 0.2161689 -0.09189265 0.007092058 0.215843 -0.09307956 0.005933284 0.214846 -0.09305238 0.0060997 0.217181 -0.09206765 0.00641036 0.218035 -0.09229105 0.005621075 0.21706 -0.09226447 0.006148874 0.215812 -0.09341555 0.005845844 0.2154843 -0.09375411 0.005889654 0.2162086 -0.09377372 0.005698502 0.216753 -0.0934413 0.005522429 0.217311 -0.09192389 0.00669974 0.217449 -0.0918374 0.007008135 0.21856 -0.0918678 0.006406545 0.218374 -0.09195286 0.006124675 0.21891 -0.09231495 0.004939913 0.218197 -0.09209549 0.005860149 0.2191089 -0.0921204 0.00515002 0.2196609 -0.09233546 0.004124045 0.217688 -0.09312999 0.005123913 0.217777 -0.09281629 0.005247294 0.2184849 -0.0931518 0.004503071 0.2202759 -0.0928846 0.0020352 0.220044 -0.09259259 0.003078341 0.220473 -0.09260427 0.00210011 0.219327 -0.09197896 0.005382478 0.219557 -0.09189498 0.005630254 0.219892 -0.0921418 0.004299461 0.2202669 -0.09235209 0.003195703 0.21889 -0.09384709 0.003888487 0.218415 -0.09348666 0.004436671 0.219089 -0.09350508 0.003703892 0.220295 -0.09388536 5.88448e-4 0.22032 -0.09388619 0 0.220735 -0.09261137 0.001064538 0.22053 -0.09289145 0.001031637 0.220033 -0.09353089 0.001958012 0.2198068 -0.09387201 0.002435088 0.2196339 -0.09351998 0.002870142 0.2201769 -0.0938822 0.001317262 0.220488 -0.09312897 0 0.220376 -0.09320336 0.001007378 0.219549 -0.09386509 0.002943873 0.2192364 -0.09385657 0.003446102 0.220656 -0.09283047 0 0.2208521 -0.09193038 0.004117548 0.221147 -0.09190797 0.004258096 0.221376 -0.09191429 0.003870189 0.2179026 -0.09382003 0.004817664 0.2184743 -0.09383583 0.004333555 0.2209849 -0.0923717 0.001105129 0.2208635 -0.09256547 0 0.221272 -0.09217947 0.001152157 0.2212042 -0.09227824 0 0.221581 -0.09191989 0.003472447 0.221612 -0.09195107 0.002484798 0.221925 -0.09192925 0.002642571 0.221764 -0.0919249 0.003063499 0.221604 -0.0920701 0 0.221587 -0.09204065 0.001204133 0.220988 -0.09217166 0.002272844 0.221922 -0.09195959 0.001259565 0.222061 -0.09193295 0.002216219 0.222261 -0.09193837 0.00134021 0.222173 -0.09193599 0.001782298 0.222046 -0.09195429 0 0.222361 -0.09194117 4.50783e-4 0.222324 -0.0919401 8.97431e-4 0.222374 -0.09194147 0 0.220015 -0.09387779 0.001890122 0.220898 -0.09190118 0.004630506 0.21986 -0.09287315 0.002983152 0.2201279 -0.09319657 0.001987338 0.219722 -0.09318548 0.002913057 0.220524 -0.09215897 0.003331601 0.220145 -0.09200125 0.004493534 0.219169 -0.09317046 0.003759324 0.219294 -0.09285777 0.003849804 0.21675 -0.09378868 0.005486369 0.2172734 -0.09380286 0.00522679 0.218593 -0.09283858 0.004611432 0.217629 -0.09346526 0.005048394 0.21946 -0.09257656 0.003972649 0.2187359 -0.09255689 0.004758596 0.216867 -0.09279149 0.005739986 0.216799 -0.09310567 0.005605041 0.2131702 -0.09369087 0.005891382 0.212852 -0.09333479 0.005845844 0.217894 -0.09253388 0.005414664 0.214375 -0.09172308 0.007999837 0.216955 -0.09250819 0.005923092 0.21191 -0.0933091 0.005522429 0.211895 -0.09365606 0.005486488 0.2113658 -0.09364151 0.00522381 0.213832 -0.09270858 0.006246507 0.213836 -0.09302479 0.0060997 0.210249 -0.09326368 0.004436671 0.2107379 -0.09362441 0.004814386 0.21029 -0.09361225 0.004441857 0.2117339 -0.0916509 0.007550179 0.2125779 -0.09179466 0.007092058 0.212812 -0.09268081 0.006076097 0.212839 -0.09299761 0.005933284 0.2124443 -0.09367096 0.005701184 0.211035 -0.0932852 0.005048394 0.2091882 -0.09358215 0.003107607 0.20903 -0.09323036 0.002870142 0.211436 -0.09176349 0.00669974 0.21277 -0.09239387 0.006269931 0.21176 -0.09236639 0.005923092 0.210821 -0.0923407 0.005414664 0.2099789 -0.0923177 0.004758596 0.210106 -0.0926069 0.004611432 0.2088389 -0.09257227 0.002983152 0.208671 -0.09228199 0.003078341 0.209405 -0.0925877 0.003849804 0.20863 -0.09321945 0.001958012 0.208919 -0.09357476 0.002604305 0.2086786 -0.09356832 0.002038002 0.208554 -0.0928806 0.001987338 0.2098802 -0.09360092 0.004035055 0.2095749 -0.09324526 0.003703892 0.2084716 -0.09356254 0.001333653 0.2079293 -0.09230357 0 0.20798 -0.0922631 0.001064538 0.208306 -0.09287381 0.001007378 0.208386 -0.09321278 9.92569e-4 0.208279 -0.09306579 0 0.20832 -0.09335666 0 0.2083541 -0.0935589 6.12014e-4 0.208325 -0.0935586 0 0.220713 -0.09236419 0.002180159 0.221291 -0.09203261 0.002375483 0.220806 -0.09201925 0.003481984 0.219361 -0.09185916 0.006255924 0.220338 -0.09188586 0.00533235 0.218243 -0.0918287 0.007002711 0.220031 -0.09187746 0.005657792 0.220629 -0.09189391 0.004988431 0.217016 -0.0917952 0.00755167 0.219004 -0.0918495 0.006525218 0.219705 -0.09186857 0.00596565 0.2139183 -0.09371143 0.005988657 0.215714 -0.09175968 0.007887184 0.216087 -0.09203785 0.00678575 0.217846 -0.09181785 0.007208228 0.218631 -0.09183925 0.006774246 0.216012 -0.09223586 0.006508946 0.2149479 -0.0920068 0.006976068 0.2165899 -0.09178358 0.007687628 0.217436 -0.0918067 0.007391333 0.214919 -0.092206 0.006691455 0.213792 -0.09197521 0.006976068 0.2152709 -0.09174758 0.007949769 0.2161549 -0.09177166 0.007799565 0.21381 -0.09217566 0.006691455 0.212652 -0.09194409 0.00678575 0.213928 -0.09171086 0.00798732 0.214824 -0.0917353 0.00798732 0.2127169 -0.09214586 0.006508946 0.2115589 -0.09191417 0.00641036 0.212597 -0.0916745 0.007799208 0.2134799 -0.09169858 0.007949352 0.211316 -0.09163945 0.007390737 0.212162 -0.09166258 0.007686674 0.209516 -0.09359109 0.003589034 0.210995 -0.09294718 0.005123913 0.2103739 -0.09173446 0.006124675 0.210122 -0.09160685 0.006773412 0.210906 -0.09162825 0.007206797 0.2071599 -0.09164667 0.001204133 0.2070789 -0.09164828 0 0.210197 -0.09292536 0.004503071 0.209421 -0.09170836 0.005382478 0.209748 -0.09159666 0.006523191 0.209255 -0.09229791 0.003972649 0.209513 -0.09290665 0.003759324 0.209068 -0.0920462 0.004124045 0.208721 -0.0915687 0.005655288 0.207744 -0.09201008 0.001105129 0.2077 -0.09205108 0 0.2089599 -0.09289169 0.002913057 0.208461 -0.09202969 0.003195703 0.207854 -0.09154498 0.004627585 0.208424 -0.09256088 0.0020352 0.2082419 -0.09227025 0.00210011 0.208016 -0.09201747 0.002180159 0.207171 -0.09152626 0.003469049 0.2081699 -0.09255397 0.001031637 0.207468 -0.09180247 0.001152157 0.206692 -0.09151327 0.002212524 0.2081444 -0.09266585 0 0.2074478 -0.09184497 0 0.176136 -0.09067881 0.037 0.157088 -0.09015858 0.04005777 0.16198 -0.09029215 0.03969866 0.171503 -0.09055227 0.03892958 0.176136 -0.09067881 0.03851968 0.20658 -0.09151017 0.001778304 0.206493 -0.09150779 0.001339912 0.09341597 -0.08841985 0.002625763 0.206692 -0.09151327 0.002212524 0.166785 -0.0904234 0.03932255 0.09331017 -0.08841687 0.04039996 0.15211 -0.09002268 0.04039996 0.09331017 -0.08841687 0.004358887 0.0934869 -0.088422 0.001754879 0.206431 -0.09150606 8.97431e-4 0.206393 -0.09150511 4.50783e-4 0.0935412 -0.08842349 8.799e-4 0.20638 -0.09150469 0 0.0935626 -0.08842378 0 0.09335708 -0.08841818 0.003493726 0.217436 -0.0918067 0.007391333 0.2499769 -0.09269529 0.02384978 0.217846 -0.09181785 0.007208228 0.206829 -0.09151697 0.002641975 0.207171 -0.09152626 0.003469049 0.206988 -0.09152126 0.003059625 0.207605 -0.09153819 0.00425446 0.207378 -0.09153199 0.003869414 0.208124 -0.09155237 0.004987537 0.207854 -0.09154498 0.004627585 0.208721 -0.0915687 0.005655288 0.208413 -0.0915603 0.005329132 0.209389 -0.09158688 0.006253242 0.209048 -0.09157758 0.005964756 0.210122 -0.09160685 0.006773412 0.209748 -0.09159666 0.006523191 0.210906 -0.09162825 0.007206797 0.210507 -0.0916174 0.007000625 0.211316 -0.09163945 0.007390737 0.2117339 -0.0916509 0.007550179 0.212162 -0.09166258 0.007686674 0.212597 -0.0916745 0.007799208 0.213035 -0.09168648 0.007886409 0.2479969 -0.09264135 0.02584052 0.2134799 -0.09169858 0.007949352 0.2279559 -0.092094 0.03164047 0.213928 -0.09171086 0.00798732 0.214824 -0.0917353 0.00798732 0.214375 -0.09172308 0.007999837 0.215714 -0.09175968 0.007887184 0.2152709 -0.09174758 0.007949769 0.2165899 -0.09178358 0.007687628 0.2161549 -0.09177166 0.007799565 0.217016 -0.0917952 0.00755167 0.2499769 -0.09269529 0 0.218243 -0.0918287 0.007002711 0.219004 -0.0918495 0.006525218 0.218631 -0.09183925 0.006774246 0.219361 -0.09185916 0.006255924 0.249283 -0.0926764 0.02493309 0.249143 -0.09267258 0.0250563 0.219705 -0.09186857 0.00596565 0.220031 -0.09187746 0.005657792 0.220338 -0.09188586 0.00533235 0.220629 -0.09189391 0.004988431 0.220898 -0.09190118 0.004630506 0.221147 -0.09190797 0.004258096 0.221376 -0.09191429 0.003870189 0.221581 -0.09191989 0.003472447 0.221764 -0.0919249 0.003063499 0.221925 -0.09192925 0.002642571 0.222061 -0.09193295 0.002216219 0.222173 -0.09193599 0.001782298 0.222261 -0.09193837 0.00134021 0.222324 -0.0919401 8.97431e-4 0.222374 -0.09194147 0 0.222361 -0.09194117 4.50783e-4 0.249931 -0.0926941 0.02403146 0.2497709 -0.09268969 0.0243684 0.249862 -0.09269219 0.02420437 0.249665 -0.09268677 0.02452248 0.249547 -0.09268355 0.0246675 0.249419 -0.09268009 0.02480399 0.2489335 -0.09266674 0.02522456 0.2486374 -0.09265881 0.02543771 0.2483245 -0.09265029 0.02564293 0.2475708 -0.09262955 0.0260781 0.2471362 -0.09261775 0.02630048 0.2467129 -0.09260612 0.02650344 0.2461962 -0.092592 0.02673548 0.2456803 -0.09257799 0.02695322 0.2450337 -0.09256035 0.02721065 0.2441743 -0.0925368 0.02753001 0.2433857 -0.09251528 0.02780455 0.2427796 -0.09249883 0.02800565 0.2419294 -0.09247547 0.02827692 0.240994 -0.09245002 0.02856034 0.2403085 -0.0924313 0.02876013 0.2394174 -0.09240692 0.02901095 0.2384241 -0.0923798 0.02927935 0.2376081 -0.09235751 0.02949172 0.2365497 -0.0923286 0.02975904 0.2351837 -0.09229135 0.03008913 0.2339515 -0.09225761 0.0303753 0.231898 -0.09220159 0.0308302 0.229929 -0.09214776 0.03124439 0.2259809 -0.09204 0.03202027 0.222021 -0.09193187 0.03273719 0.224002 -0.091986 0.03238534 0.218053 -0.09182345 0.03340488 0.2200379 -0.09187769 0.0330767 0.2140769 -0.09171485 0.03403055 0.216066 -0.09176915 0.03372269 0.212088 -0.09166055 0.03432929 0.210097 -0.09160619 0.03461927 0.208104 -0.09155178 0.03490096 0.206111 -0.09149736 0.03517484 0.2011517 -0.09136188 0.03582483 0.204117 -0.09144288 0.03544127 0.186132 -0.0909518 0.037 0.1971358 -0.0912522 0.03631931 0.1931443 -0.09114325 0.03678524 0.1891325 -0.09103363 0.03722965 0.186132 -0.0909518 0.03754657 0.51 -0.07533937 0.01069658 0.5025067 -0.07461374 0.01303476 0.51 -0.07479721 0.01156216 0.48 -0.07593935 0.01482862 0.48 -0.0753346 0.01557356 0.487498 -0.0755409 0.01417249 0.4799998 -0.07665723 0.01381087 0.487498 -0.07717186 0.01158219 0.5024728 -0.07631343 0.01034247 0.51 -0.07583498 0.009813964 0.51 -0.07641947 0.008594453 0.5024421 -0.07750183 0.007493317 0.5100001 -0.07689595 0.00740242 0.48 -0.07732534 0.01270759 0.487498 -0.07831937 0.008833944 0.4800001 -0.07794117 0.01150619 0.51 -0.07732588 0.006050467 0.48 -0.07840257 0.01041632 0.5025 -0.07814669 0.004828929 0.5100001 -0.07763558 0.004763722 0.48 -0.07915925 0.007928669 0.4876577 -0.07894736 0.006231546 0.48 -0.07882332 0.009186148 0.51 -0.07786113 0.003391683 0.5025656 -0.07838505 0.002518534 0.5100001 -0.07797741 0.002111673 0.487499 -0.07919996 0.003967642 0.4800002 -0.07954913 0.005286574 0.5099999 -0.07799947 0 0.48 -0.07938033 0.006760358 0.48 -0.07961624 0.003450691 0.4799999 -0.07958751 0 0.48 -0.07471054 0.01627284 0.487498 -0.07350099 0.01644796 0.48 -0.07378214 0.0171824 0.48 -0.07305639 0.01780587 0.51 -0.07400387 0.01266157 0.5025094 -0.07248449 0.0154016 0.51 -0.07266652 0.01420378 0.51 -0.07335865 0.01344299 0.4800001 -0.07233369 0.01837122 0.487497 -0.07110786 0.0183475 0.48 -0.07124096 0.0191127 0.48 -0.07041829 0.01959609 0.51 -0.07169741 0.01513797 0.5024892 -0.06998658 0.01737403 0.51 -0.07091689 0.01579689 0.4800001 -0.06963038 0.02001345 0.51 -0.07010215 0.01641958 0.487497 -0.06844139 0.01981258 0.48 -0.06839942 0.0205599 0.502449 -0.067209 0.01888769 0.51 -0.06839817 0.01750415 0.48 -0.06716895 0.02101325 0.4875822 -0.06583327 0.0207383 0.51 -0.06719875 0.01812666 0.48 -0.06598502 0.02135276 0.5100001 -0.06591725 0.01868516 0.502499 -0.06451129 0.01982927 0.51 -0.06466567 0.01912569 0.48 -0.06503999 0.02155506 0.4878494 -0.06360965 0.02118855 0.48 -0.06409627 0.02171385 0.48 -0.06286096 0.02184337 0.502499 -0.06227099 0.02028596 0.51 -0.06203669 0.01975065 0.5100001 -0.06334096 0.01949036 0.48 -0.06155669 0.02188247 0.488183 -0.061715 0.02135163 0.5100002 -0.05990415 0.0199812 0.51 -0.0610311 0.01988536 0.51 -0.05891811 0.02000021 0.4799999 -0.05074429 0.02177459 0.4886305 -0.05059403 0.02114075 0.487493 -0.05233895 0.02139425 0.51 -0.05517816 0.01999992 0.4799999 -0.05280077 0.02188187 0.51 -0.0480315 0.01868504 0.5100001 -0.04931688 0.01914393 0.5022293 -0.04682844 0.01890128 0.51 -0.05162137 0.01970845 0.502497 -0.04953944 0.01982927 0.51 -0.05061501 0.01950174 0.4876397 -0.04064595 0.0164414 0.48 -0.03946816 0.01628732 0.4799999 -0.04137748 0.01802349 0.4877204 -0.04305219 0.01833951 0.51 -0.04280263 0.01557105 0.502497 -0.04157108 0.01540738 0.4800001 -0.03865033 0.01536661 0.4876303 -0.0386008 0.01416218 0.51 -0.041803 0.01467174 0.4799998 -0.03713768 0.01322853 0.51 -0.04109269 0.01394438 0.502497 -0.03943818 0.01303738 0.51 -0.04041332 0.01317882 0.502497 -0.03773778 0.01033806 0.51 -0.03901594 0.01127177 0.4876964 -0.03697031 0.01156055 0.4799999 -0.03599256 0.01100027 0.51 -0.03958696 0.01211547 0.4877129 -0.03582298 0.00880593 0.48 -0.03552311 0.009789884 0.51 -0.03848284 0.01039433 0.48 -0.03514933 0.008583724 0.51 -0.03731721 0.007943332 0.502497 -0.03654986 0.007481753 0.5100001 -0.03782743 0.009135246 0.48 -0.0349282 0.007633328 0.51 -0.03687191 0.006674051 0.48 -0.03475141 0.006667613 0.4880334 -0.03520423 0.006191253 0.48 -0.03459465 0.005396604 0.48749 -0.03493249 0.003967642 0.502497 -0.03590416 0.004828929 0.5099999 -0.03643184 0.005028486 0.48 -0.03454101 0.004250586 0.51 -0.03614956 0.003364264 0.501704 -0.03562623 0.002602875 0.51 -0.03602731 0.002023279 0.4906845 -0.03507834 0.002448678 0.5099999 -0.03600084 9.61796e-4 0.4799998 -0.0345776 0 0.4978176 -0.03543859 0 0.51 -0.03600025 0 0.48 -0.03652352 0.01213395 0.48 -0.03784888 0.01431792 0.502497 -0.04407548 0.01738029 0.51 -0.04361128 0.01620745 0.51 -0.04558384 0.01750636 0.51 -0.04444086 0.01679831 0.48 -0.04038202 0.01718121 0.5100001 -0.04674476 0.01812052 0.48 -0.04237663 0.01875448 0.487492 -0.04569107 0.01981258 0.48 -0.04320025 0.01926875 0.48 -0.04437667 0.01992624 0.4880574 -0.04834133 0.02070903 0.4800001 -0.04573893 0.02054464 0.502498 -0.05177974 0.02028596 0.48 -0.04692852 0.02096915 0.48 -0.04823231 0.02134805 0.5100001 -0.05392462 0.01997935 0.51 -0.05261766 0.0198636 0.5024231 -0.05361074 0.02045994 0.48 -0.04937142 0.02158844 0.51 -0.06926727 0.0169816 0.411237 -0.04336738 0 0.411237 -0.03536736 0.01099997 0.411237 -0.03536736 0 0.411237 -0.04336738 0.01099997 0.406237 -0.03536736 0 0.406237 -0.03536736 0.01099997 0.406237 -0.04300785 0.01099997 0.406237 -0.04300785 0 0.371237 -0.02918457 0.01099997 0.406237 -0.03536736 0.01099997 0.411237 -0.03536736 0.01099997 0.468035 -0.03543728 0.01099997 0.465043 -0.04400235 0.01099997 0.462051 -0.04405695 0.01099997 0.40189 -0.04264867 0.01099997 0.404064 -0.04284149 0.01099997 0.399714 -0.04242956 0.01099997 0.406237 -0.04300785 0.01099997 0.395356 -0.04191237 0.01099997 0.397536 -0.04218417 0.01099997 0.390989 -0.04128974 0.01099997 0.393173 -0.04161429 0.01099997 0.386614 -0.04056185 0.01099997 0.388802 -0.04093897 0.01099997 0.382231 -0.0397287 0.01099997 0.384423 -0.04015845 0.01099997 0.377839 -0.03878998 0.01099997 0.380036 -0.03927248 0.01099997 0.373439 -0.03774607 0.01099997 0.37564 -0.0382812 0.01099997 0.371237 -0.03718459 0.01099997 0.45906 -0.04410105 0.01099997 0.468035 -0.04393726 0.01099997 0.456069 -0.04413449 0.01099997 0.453078 -0.04415738 0.01099997 0.450087 -0.04416966 0.01099997 0.447097 -0.04417139 0.01099997 0.444107 -0.04416257 0.01099997 0.441117 -0.04414308 0.01099997 0.438128 -0.04411315 0.01099997 0.435139 -0.04407256 0.01099997 0.43215 -0.04402148 0.01099997 0.426173 -0.04388749 0.01099997 0.429161 -0.04395967 0.01099997 0.420198 -0.04371118 0.01099997 0.423185 -0.04380458 0.01099997 0.414223 -0.04349255 0.01099997 0.41721 -0.04360717 0.01099997 0.411237 -0.04336738 0.01099997 0.371237 -0.03718459 0.01999998 0.371237 -0.02918457 0.01099997 0.371237 -0.02918457 0.01999998 0.371237 -0.03718459 0.01099997 0.468035 -0.04393726 0.01999998 0.468035 -0.03543728 0.01099997 0.468035 -0.04393726 0.01099997 0.468035 -0.03543728 0.01999998 0.468035 -0.03543728 0.01999998 0.371237 -0.02918457 0.01099997 0.468035 -0.03543728 0.01099997 0.371237 -0.02918457 0.01999998 0.36 -0.04340416 0.02599996 0.36 -0.04340416 0.003881454 0.36 -0.04493767 0.005414187 0.36 -0.04493767 0.02599996 0.3609766 -0.04564714 0.004704415 0.360977 -0.04393649 0.002999961 0.3604744 -0.04554057 0.004810988 0.36059 -0.04381215 0.002999961 0.3606905 -0.04561126 0.004740297 0.360711 -0.04387629 0.002999961 0.360841 -0.04391878 0.002999961 0.360296 -0.04352694 0.002999961 0.3602433 -0.04540473 0.004946887 0.36048 -0.04373019 0.002999961 0.360382 -0.04363405 0.002999961 0.360145 -0.04340887 0.003153383 0.3600831 -0.04522383 0.005127966 0.360082 -0.0434069 0.003323078 0.360222 -0.04341149 0.002999961 0.3600244 -0.04340499 0.003563106 0.3600124 -0.04505783 0.005294024 0.36 -0.04493767 0.005414187 0.36 -0.04340416 0.003881454 0.455 -0.04651415 0.002999961 0.455 -0.04701435 0.002999961 0.360977 -0.04393649 0.002999961 0.36059 -0.04381215 0.002999961 0.36048 -0.04373019 0.002999961 0.360711 -0.04387629 0.002999961 0.360841 -0.04391878 0.002999961 0.360382 -0.04363405 0.002999961 0.360222 -0.04341149 0.002999961 0.360296 -0.04352694 0.002999961 0.455 -0.04793208 0.003496587 0.455 -0.04811686 0.003905773 0.455 -0.04701435 0.002999961 0.455 -0.04832285 0.004307687 0.455 -0.04776847 0.00308007 0.455 -0.04732578 0.00134319 0.455 -0.04740428 0.001786708 0.455 -0.0475046 0.00222516 0.455 -0.04651415 0.002999961 0.455 -0.04727005 8.99183e-4 0.455 -0.04651415 0 0.455 -0.0472365 4.51443e-4 0.455 -0.04722499 0 0.455 -0.04762595 0.00265628 0.337 -0.02487236 0 0.337 -0.04265129 0.01499998 0.337 -0.02487236 0.01499998 0.337 -0.04265129 0 0.295 -0.02723395 0.02943909 0.295 -0.026847 0.0290389 0.295 -0.02647608 0 0.295 -0.02647608 0.02862 0.295 -0.027637 0.0298205 0.295 -0.02805596 0.03018319 0.295 -0.02849107 0.03052717 0.295 -0.02894216 0.03085249 0.295 -0.02940934 0.0311591 0.295 -0.0298866 0.03144448 0.295 -0.0303747 0.03170907 0.295 -0.0308752 0.03195345 0.295 -0.03138738 0.03217726 0.295 -0.03190475 0.03237748 0.295 -0.0324313 0.03255587 0.295 -0.04127627 0 0.295 -0.03296685 0.03271257 0.295 -0.03405278 0.03295379 0.295 -0.0335083 0.03284567 0.295 -0.03515928 0.03309959 0.295 -0.03460305 0.03303849 0.295 -0.03626817 0.03317755 0.295 -0.03571325 0.03314715 0.295 -0.03680819 0.03318887 0.295 -0.03793859 0.03318917 0.295 -0.03941529 0.03315854 0.295 -0.03849464 0.03318208 0.295 -0.04042077 0.03315466 0.295 -0.04127627 0.03315764 0.3172857 -0.08861571 0.02003121 0.399576 -0.04604959 0.02692806 0.4366749 -0.04979217 0.02461284 0.1960856 -0.04587674 0.03858548 0.1872305 -0.04414701 0.03907835 0.1873995 -0.03696566 0.03906983 0.413758 -0.04615646 0.02599996 0.395809 -0.04457646 0.02706974 0.413667 -0.04603028 0.02599996 0.413936 -0.04658406 0.02599996 0.41395 -0.0467388 0.02599996 0.1874609 -0.03435176 0.03906679 0.412794 -0.04525154 0.02599996 0.4130539 -0.04544126 0.02599996 0.4132934 -0.04563897 0.02599996 0.2281003 -0.04676014 0.03687071 0.2950001 -0.03008997 0.03156274 0.288703 -0.02976155 0.03196495 0.288703 -0.02851015 0.03120118 0.412608 -0.04512637 0.02599996 0.226821 -0.05048829 0.037 0.2034304 -0.04993909 0.03825008 0.413461 -0.04579806 0.02599996 0.413568 -0.04591107 0.02599996 0.413836 -0.04629075 0.02599996 0.413897 -0.04643368 0.02599996 0.413949 -0.04711961 0.0259993 0.4333845 -0.04830771 0.02480274 0.455 -0.04901546 0.02338832 0.413949 -0.04767167 0.02599996 0.37901 -0.04402649 0.02812385 0.1970635 -0.0183773 0.03284364 0.19629 -0.01774358 0.03175276 0.4180485 -0.04889035 0.02578252 0.3995787 -0.04748153 0.02692794 0.4086511 -0.06742584 0.02636921 0.3631278 -0.04477167 0.02914553 0.3811314 -0.06969815 0.02805763 0.3525026 -0.07201075 0.02978354 0.3713391 -0.07420569 0.02828139 0.3525911 -0.07403379 0.02969974 0.3892485 -0.07091617 0.02749693 0.19638 -0.06727844 0.0385698 0.3901724 -0.07427072 0.0266844 0.26088 -0.08581888 0.03345376 0.2422856 -0.08588945 0.03510731 0.2791839 -0.08317655 0.03307318 0.4550002 -0.07259386 0.02104061 0.4342221 -0.07434338 0.02229082 0.436534 -0.07215958 0.02318179 0.455 -0.0744096 0.01980358 0.436535 -0.07602179 0.02082139 0.335039 -0.08522862 0.02496677 0.335259 -0.08420187 0.02623552 0.1861718 -0.08925896 0.03837025 0.1957766 -0.08914405 0.03760612 0.1861501 -0.09016293 0.03797513 0.3527185 -0.08577692 0.0205971 0.3158392 -0.08788269 0.02347618 0.3162772 -0.08718919 0.02491247 0.1957585 -0.08608996 0.03848987 0.1862395 -0.08636438 0.03906548 0.204117 -0.09144288 0.03544127 0.2147729 -0.09006005 0.03528535 0.2145211 -0.09103691 0.03450721 0.2390798 -0.09239774 0.02910339 0.251744 -0.09161978 0.02806788 0.2443953 -0.09254288 0.02744925 0.243906 -0.09252953 0.02762484 0.2515987 -0.09211742 0.02664375 0.3310308 -0.08790749 0.01687055 0.3671849 -0.08584982 0.0139079 0.2450361 -0.09256035 0.02720969 0.245681 -0.09257799 0.02695292 0.246194 -0.092592 0.02673643 0.251744 -0.09243607 0.02495467 0.2474923 -0.09262746 0.02611911 0.270228 -0.09134989 0.02361869 0.2943358 -0.09002715 0.01969677 0.246711 -0.09260612 0.02650433 0.2478297 -0.0926367 0.02593576 0.268622 -0.09156548 0 0.270821 -0.09138739 0.003914654 0.3507752 -0.08674806 0.002751946 0.372217 -0.08549994 0 0.2487801 -0.09266257 0.02533781 0.249283 -0.0926764 0.02493309 0.2490837 -0.09267085 0.02510648 0.3111482 -0.08903002 0 0.249419 -0.09268009 0.02480399 0.249665 -0.09268677 0.02452248 0.2699981 -0.09145134 0.02147489 0.2497709 -0.09268969 0.0243684 0.419713 -0.08287709 0.001756966 0.4074887 -0.08359241 0.0103814 0.4550001 -0.08093231 0 0.4261553 -0.08249688 0 0.249547 -0.09268355 0.0246675 0.2484536 -0.09265375 0.02556037 0.2471389 -0.09261751 0.02629905 0.249976 -0.09269565 0.006501674 0.2499769 -0.09269529 0 0.2430349 -0.09250563 0.02792245 0.2419288 -0.09247559 0.02827709 0.2409925 -0.09244996 0.02856081 0.2401482 -0.09242689 0.02880626 0.4331777 -0.08217376 0.007957875 0.2381266 -0.0923717 0.02935761 0.237236 -0.09234738 0.02958679 0.2364805 -0.09232676 0.02977573 0.2353341 -0.09229558 0.03005379 0.4322916 -0.08216249 0.009889841 0.251744 -0.09101688 0.02932798 0.2339664 -0.09225797 0.03037184 0.231898 -0.09220159 0.0308302 0.229929 -0.09214776 0.03124439 0.233259 -0.09144228 0.03159785 0.2279559 -0.092094 0.03164047 0.2259809 -0.09204 0.03202027 0.2789199 -0.09002339 0.02618592 0.315174 -0.08842265 0.02193993 0.433701 -0.08180212 0.01168906 0.216066 -0.09176915 0.03372269 0.2140769 -0.09171485 0.03403055 0.233259 -0.09066736 0.03257715 0.3725123 -0.08548307 0.01535826 0.4549998 -0.08053863 0.01019638 0.4343351 -0.08121639 0.01365768 0.222021 -0.09193187 0.03273719 0.2793236 -0.08937203 0.02749687 0.436537 -0.08025145 0.01549339 0.455 -0.07952469 0.0132389 0.455 -0.07988339 0.01234954 0.2012013 -0.09136319 0.03581851 0.1971455 -0.09125238 0.03631806 0.455 -0.07913279 0.01406556 0.436536 -0.0790919 0.01747077 0.455 -0.07868856 0.01489442 0.3721517 -0.08297753 0.02232909 0.3991197 -0.08238208 0.01859742 0.3532068 -0.08503156 0.02218472 0.3522164 -0.08631896 0.01893407 0.1931625 -0.09114366 0.03678315 0.436536 -0.07767379 0.01925587 0.4550002 -0.07796585 0.01604485 0.2423872 -0.08822202 0.03375554 0.2239133 -0.08839619 0.03548789 0.2980145 -0.08748221 0.02748173 0.2610336 -0.08974069 0.02987796 0.2610929 -0.08891379 0.03091692 0.2982432 -0.08656072 0.0286172 0.196287 -0.08773559 0.03808528 0.196287 -0.09025496 0.0369758 0.3894683 -0.08371096 0.01755672 0.1891586 -0.09103435 0.03722679 0.2983713 -0.0855239 0.02964162 0.2612323 -0.08797866 0.0318495 0.186132 -0.0909518 0.03754657 0.4550002 -0.07641512 0.01798009 0.455 -0.07728826 0.0169596 0.27971 -0.08567482 0.03163558 0.455 -0.07514256 0.01920598 0.455 -0.07582396 0.01857727 0.2238589 -0.08579826 0.03661894 0.2239083 -0.08160728 0.03709733 0.242264 -0.08272796 0.03598964 0.3722238 -0.08183187 0.02376711 0.455 -0.0736404 0.02037292 0.3167155 -0.08307707 0.02948063 0.1864377 -0.07794058 0.03911811 0.1962689 -0.08351016 0.03857547 0.2978373 -0.08313953 0.03137576 0.1864904 -0.07567644 0.03911542 0.2607346 -0.08309209 0.03461062 0.278952 -0.07995158 0.03395462 0.1866071 -0.07070451 0.03910958 0.233046 -0.06986552 0.03659856 0.2609513 -0.07896834 0.03506273 0.3353217 -0.08304017 0.02737641 0.4089326 -0.07446259 0.02486348 0.1866551 -0.06866621 0.0391072 0.3908176 -0.0776565 0.0250076 0.3723637 -0.08050829 0.02503752 0.3537113 -0.08040726 0.02727371 0.2040822 -0.06496268 0.03821396 0.2147721 -0.06684952 0.03758841 0.455 -0.06919258 0.02256226 0.4550001 -0.07032275 0.0221461 0.4289309 -0.07088351 0.02436089 0.1867516 -0.06455576 0.03910237 0.3719252 -0.07745683 0.02707713 0.3348205 -0.08035486 0.02925211 0.3531283 -0.07736772 0.02886182 0.4328622 -0.06704509 0.02480554 0.436533 -0.06842786 0.02433347 0.3344019 -0.07730174 0.03044599 0.1871705 -0.04671525 0.03908103 0.1871041 -0.04955577 0.03908473 0.19629 -0.01897984 0.03389215 0.2181279 -0.02131521 0.03357052 0.177845 -0.01784718 0.03520154 0.1872808 -0.04202157 0.03907579 0.1873376 -0.03960192 0.03907299 0.1875191 -0.03186553 0.03906387 0.1956459 -0.0293923 0.03861266 0.2547699 -0.0545628 0.03540545 0.1875714 -0.02962219 0.03906124 0.2702134 -0.03527647 0.03454291 0.187618 -0.02765309 0.0390523 0.196289 -0.02678877 0.03848677 0.1876811 -0.02497792 0.03878545 0.187656 -0.02603548 0.03897094 0.196289 -0.02504467 0.03813225 0.288705 -0.0392825 0.03349804 0.288704 -0.03677284 0.03349804 0.295 -0.0385608 0.03317838 0.295 -0.03652256 0.03318721 0.288704 -0.03445446 0.03342688 0.2425025 -0.03306108 0.03608328 0.2243133 -0.02586692 0.03614068 0.2609161 -0.03030896 0.0346468 0.2239742 -0.02726715 0.03665965 0.2603808 -0.03205776 0.03501778 0.295 -0.03215718 0.03246867 0.288704 -0.03265428 0.03309667 0.288704 -0.03113007 0.03259897 0.2246218 -0.02466905 0.03551709 0.2612254 -0.0288521 0.03412806 0.295 -0.02915984 0.03100246 0.25174 -0.02372825 0.03157997 0.2436038 -0.02403992 0.03296101 0.2073761 -0.02137577 0.0350244 0.177833 -0.01838541 0.03585088 0.2615306 -0.02757728 0.03348761 0.2248553 -0.02361249 0.03480893 0.2522185 -0.02294307 0.03054761 0.268542 -0.0243175 0.02999997 0.270221 -0.02505177 0.03046309 0.1778159 -0.01910597 0.03657931 0.196289 -0.02145415 0.03637129 0.182874 -0.0202589 0.037 0.1778039 -0.01959508 0.037 0.2332569 -0.02091968 0.03063267 0.249155 -0.02206677 0.02999997 0.1778681 -0.01688677 0.03376299 0.214774 -0.01904118 0.03061378 0.229748 -0.02002447 0.02999997 0.210321 -0.01819068 0.02999997 0.216799 -0.0187788 0.02999997 0.223275 -0.0193901 0.02999997 0.1778844 -0.01617318 0.03222525 0.17789 -0.0159471 0.03154075 0.19629 -0.01726025 0.03044569 0.197359 -0.017084 0.02999997 0.203841 -0.01762574 0.02999997 0.1778935 -0.01579207 0.0309875 0.190874 -0.01656538 0.02999997 0.184387 -0.01606988 0.02999997 0.177898 -0.01559758 0.02999997 0.177877 -0.0164842 0.03296309 0.275 -0.02599799 0.03092098 0.270222 -0.02601158 0.03141319 0.2899998 -0.02647364 0.02935343 0.2949999 -0.0270496 0.0292561 0.2704496 -0.02705037 0.0322169 0.275 -0.02511399 0.02999997 0.275 -0.02554398 0.03047198 0.280212 -0.02647608 0.03068405 0.285347 -0.02647608 0.02999997 0.29 -0.02712118 0.02999997 0.295 -0.02849107 0.03052717 0.2949997 -0.02769958 0.02987867 0.288703 -0.02738034 0.03031909 0.295 -0.02647608 0.02862 0.295 -0.03112906 0.03207093 0.275 -0.02647608 0.03134715 0.295 -0.03431886 0.03300118 0.2233697 -0.02898883 0.03704327 0.295 -0.03548592 0.03313136 0.196289 -0.02248018 0.03704339 0.196289 -0.0236566 0.03763645 0.1877487 -0.02209609 0.03772032 0.1877251 -0.02309519 0.03819441 0.295 -0.04127627 0.03315645 0.2499755 -0.09269666 0.02050244 0.249862 -0.09269219 0.02420437 0.249931 -0.0926941 0.02403146 0.455 -0.0809679 0.004143714 0.2499769 -0.09269529 0.02384978 0.2481434 -0.09264528 0.02575397 0.455 -0.08098977 0.006270825 0.455 -0.08096641 0.007181465 0.218053 -0.09182345 0.03340488 0.3890334 -0.08426189 0.0157566 0.455 -0.0808891 0.008110404 0.455 -0.08076733 0.00903964 0.2200379 -0.09187769 0.0330767 0.2071726 -0.09152621 0.03503066 0.455 -0.08019775 0.01145064 0.224002 -0.091986 0.03238534 0.211133 -0.09163433 0.03447037 0.1863084 -0.08343976 0.03912538 0.4091836 -0.07944768 0.02120953 0.4091296 -0.08074247 0.01958423 0.1862766 -0.08478718 0.03915363 0.4093157 -0.07794076 0.02263611 0.1863791 -0.08040809 0.03912097 0.1862169 -0.08731716 0.03892379 0.455 -0.06829625 0.0228312 0.186195 -0.08826774 0.03869974 0.4081097 -0.07099539 0.02607578 0.455 -0.0715062 0.02161461 0.3160231 -0.08034461 0.03099757 0.2976081 -0.08025801 0.03255134 0.3157881 -0.07704889 0.03185468 0.455 -0.06736403 0.02306342 0.3163338 -0.07483184 0.0319119 0.4549999 -0.06603711 0.02329909 0.2887179 -0.07692116 0.03349751 0.4359468 -0.06512647 0.02465796 0.4550001 -0.06502246 0.02337694 0.455 -0.06338518 0.0234456 0.226821 -0.0654965 0.037 0.2546008 -0.0632323 0.03541588 0.3071933 -0.04319041 0.03243893 0.3232473 -0.04220098 0.03150832 0.226821 -0.05949068 0.037 0.233258 -0.05675148 0.03658747 0.344139 -0.04547339 0.03027862 0.2886998 -0.04206275 0.03349834 0.3811096 -0.04608333 0.0280587 0.455 -0.05089128 0.02344733 0.3505802 -0.04309582 0.02987623 0.1877033 -0.02403515 0.03853523 0.187765 -0.02137869 0.03729599 0.295 -0.0332387 0.03278571 0.187776 -0.02093738 0.037 0.1778569 -0.01737701 0.0345596 0.262082 -0.02354407 0.02999997 0.242688 -0.0213629 0.02999997 0.25562 -0.02279376 0.02999997 0.236219 -0.02068209 0.02999997 0.412608 -0.04512637 0.02599996 0.360967 -0.04593718 0.02599996 0.412794 -0.04525154 0.02599996 0.36 -0.04493767 0.02599996 0.36 -0.04340416 0.02599996 0.4130539 -0.04544126 0.02599996 0.4132934 -0.04563897 0.02599996 0.413461 -0.04579806 0.02599996 0.413568 -0.04591107 0.02599996 0.413667 -0.04603028 0.02599996 0.413758 -0.04615646 0.02599996 0.413836 -0.04629075 0.02599996 0.413897 -0.04643368 0.02599996 0.413936 -0.04658406 0.02599996 0.4139497 -0.04673737 0.02599996 0.413949 -0.04767167 0.02599996 0.360397 -0.04573518 0.02599996 0.360526 -0.04581815 0.02599996 0.360666 -0.04588037 0.02599996 0.360814 -0.04592037 0.02599996 0.360282 -0.04563337 0.02599996 0.360184 -0.04551506 0.02599996 0.360105 -0.04538315 0.02599996 0.360012 -0.04509097 0.02599996 0.360047 -0.0452407 0.02599996 0.337691 -0.02392137 0 0.337844 -0.02388465 0 0.338 -0.02387237 0 0.487584 -0.03494805 0 0.51 -0.02799999 0 0.495112 -0.03530955 0 0.363 -0.02387237 0 0.411999 -0.02214819 0 0.406237 -0.03536736 0 0.337546 -0.02398139 0 0.337412 -0.02406334 0 0.337293 -0.02416527 0 0.337109 -0.02441835 0 0.337191 -0.0242846 0 0.337049 -0.02456337 0 0.337 -0.02487236 0 0.337012 -0.02471596 0 0.395666 -0.02108216 0 0.379333 -0.01999026 0 0.428332 -0.02318829 0 0.411237 -0.03536736 0 0.363 -0.01887249 0 0.460999 -0.02519065 0 0.444665 -0.02420246 0 0.48 -0.0345757 0 0.477332 -0.02615308 0 0.493666 -0.02708947 0 0.51 -0.03599995 0 0.502584 -0.03566014 0 0.48 -0.04722499 0 0.455 -0.04651415 0 0.411237 -0.04336738 0 0.455 -0.04722499 0 0.337 -0.04265129 0 0.408733 -0.04319846 0 0.406237 -0.04300785 0 0.363 -0.02387237 0.01499998 0.363 -0.01882779 0.01499998 0.363 -0.0188561 0.008881151 0.363 -0.01886975 0.003452956 0.363 -0.02387237 0 0.363 -0.01887249 0 0.337191 -0.0242846 0.01499998 0.334 -0.01688188 0.01499998 0.337293 -0.02416527 0.01499998 0.338 -0.02387237 0.01499998 0.337844 -0.02388465 0.01499998 0.363 -0.01882779 0.01499998 0.363 -0.02387237 0.01499998 0.337691 -0.02392137 0.01499998 0.337546 -0.02398139 0.01499998 0.337412 -0.02406334 0.01499998 0.337109 -0.02441835 0.01499998 0.337049 -0.02456337 0.01499998 0.337 -0.02487236 0.01499998 0.334 -0.04255306 0.01499998 0.337012 -0.02471596 0.01499998 0.337 -0.04265129 0.01499998 0.308 -0.04170185 0 0.295 -0.04127627 0 0.295 -0.02647608 0 0.283 -0.01347607 0 0.308 -0.01514977 0 0.283 -0.02147608 0 0.29 -0.02597606 0 0.275 -0.02597606 0 0.29 -0.02647608 0 0.275 -0.02147608 0 0.283 -0.02147608 0.02999997 0.283 -0.01344305 0.02999997 0.2830001 -0.01346111 0.02153152 0.2830001 -0.01347446 0.00826925 0.283 -0.02147608 0 0.283 -0.01347607 0 0.00173819 0.002714931 0.02999997 0.001835465 0.002808034 0.06499999 0.002807676 0.003676056 0.06499999 0.002680897 0.003571033 0.02999997 0.001109004 0.002061963 0.06499999 0.001109004 0.002061963 0.02999997 0.003838598 0.004464805 0.06499999 0.004754602 0.005067706 0.02999997 0.003686189 0.004355311 0.02999997 0.006403326 0.005995988 0.02999997 0.004927754 0.005174517 0.06499999 0.007591664 0.006604909 0.02999997 0.007787406 0.006699323 0.06499999 0.006624519 0.006114602 0.06499999 0.009693324 0.007563531 0.06499999 0.009261965 0.0073722 0.02999997 0.01098155 0.008089721 0.02999997 0.01338636 0.008983075 0.02999997 0.01241666 0.008639454 0.06499999 0.01517635 0.00958234 0.06499999 0.01568514 0.009742677 0.02999997 0.0182079 0.01049542 0.02999997 0.01764106 0.01033186 0.06499999 0.02100425 0.01124382 0.06499999 0.02099561 0.01123613 0.02999997 0.02351593 0.01183974 0.02999997 0.02420675 0.01199507 0.06499999 0.02682739 0.01255339 0.02999997 0.02686452 0.01255911 0.06499999 0.03048282 0.01323896 0.02999997 0.03070974 0.0132814 0.06499999 0.03364759 0.01376312 0.02999997 0.03459692 0.01390886 0.06499999 0.0374909 0.01431947 0.06499999 0.03654068 0.01418906 0.02999997 0.04005765 0.01464897 0.02999997 0.04103612 0.01476502 0.06499999 0.04494065 0.0151782 0.06499999 0.04458409 0.01514506 0.02999997 0.04879927 0.01552152 0.06499999 0.04906308 0.01554238 0.02999997 0.05271941 0.01579946 0.06499999 0.05295771 0.0158143 0.02999997 0.05702459 0.01603394 0.02999997 0.05703413 0.01603519 0.06499999 0.06200259 0.01620465 0.06499999 0.06143254 0.01618933 0.02999997 0.0655713 0.01626068 0.06499999 0.0646612 0.01625096 0.02999997 0.0681867 0.0162726 0.02999997 0.0688126 0.0162695 0.06499999 0.07236027 0.01622909 0.02999997 0.07270824 0.01622229 0.06499999 0.07591825 0.01613771 0.02999997 0.0772472 0.01609396 0.06499999 0.08010321 0.01597201 0.02999997 0.08243757 0.01585042 0.06499999 0.08449023 0.01572579 0.02999997 0.08793056 0.01548761 0.02999997 0.08804184 0.01548284 0.06499999 0.091802 0.01517498 0.02999997 0.09397333 0.01497989 0.06499999 0.09882068 0.01448673 0.06499999 0.09658986 0.0147227 0.02999997 0.1036421 0.01393443 0.06499999 0.1026449 0.0140562 0.02999997 0.1090691 0.01323658 0.02999997 0.1097175 0.01314884 0.06499999 0.1150578 0.01238244 0.06499999 0.1152703 0.01235377 0.02999997 0.120235 0.01158714 0.06499999 0.1254315 0.0107364 0.06499999 0.122965 0.01114892 0.02999997 0.1338904 0.009278476 0.02999997 0.1312363 0.009743392 0.06499999 0.1420394 0.007801234 0.06499999 0.1455965 0.007136046 0.02999997 0.1573566 0.004891216 0.02999997 0.1554509 0.005259871 0.06499999 0.1679395 0.002820193 0.06499999 0.1741504 0.001592338 0.02999997 0.1987898 -0.003368139 0.02999997 0.1848465 -5.51117e-4 0.06499999 0.2141066 -0.006478607 0.06499999 0.2366445 -0.0112158 0.06499999 0.2363763 -0.01115655 0.03763955 0.2267872 -0.009078741 0.06499999 0.2247797 -0.00865817 0.02999997 0.23237 -0.01027679 0.03514796 0.2322559 -0.01025187 0.03497618 0.2314983 -0.01008677 0.06499999 0.2354237 -0.01094824 0.03726112 0.2345329 -0.01075243 0.03683865 0.2341818 -0.01067507 0.03664702 0.234798 -0.01081085 0.0369727 0.2338237 -0.01059603 0.03643196 0.233235 -0.01046639 0.03601807 0.233076 -0.01043146 0.03588926 0.2334814 -0.01052075 0.0362026 0.232495 -0.01030409 0.0353114 0.232922 -0.01039755 0.03575456 0.232773 -0.01036489 0.03561389 0.232012 -0.01019847 0.03440785 0.23197 -0.01018947 0.03420579 0.2319452 -0.01018357 0.03349292 0.2319377 -0.01018244 0.03144073 0.2319329 -0.01018136 0.02999997 0.23195 -0.01018506 0.03395116 0.23263 -0.01033365 0.03546649 0.232075 -0.01021218 0.03460568 0.232157 -0.01023006 0.03479498 0.2350892 -0.01087492 0.03711175 0.2359079 -0.01105451 0.03746235 0.2367729 -0.0112428 0.03778028 0.237171 -0.01132881 0.03791272 0.2377174 -0.01144582 0.03808248 0.2384445 -0.01160067 0.03828883 0.239169 -0.01175385 0.0384767 0.241118 -0.01217597 0.06499999 0.2399342 -0.0119158 0.03866189 0.2411299 -0.01216864 0.03892797 0.241886 -0.0123316 0.03908467 0.243144 -0.01256155 0.06499999 0.242435 -0.01244366 0.0391829 0.243547 -0.0126394 0.03931826 0.242989 -0.0125463 0.03926014 0.244107 -0.01272535 0.03936237 0.244664 -0.01282227 0.06499999 0.244664 -0.01282227 0.03942304 0.1002522 -0.01016223 0.05132943 0.1015829 -0.01019352 0.06499999 0.001107215 0.002063512 0.06499999 0.001109004 0.002061963 0.02999997 0.1036322 -0.01023846 0.05118215 0.1071172 -0.01031535 0.05102545 0.1104152 -0.01038706 0.0508731 0.1196831 -0.01058459 0.06499999 0.1142101 -0.01046836 0.05069226 0.08055132 -0.009674429 0.06499999 0.1177096 -0.01054245 0.05052042 0.120736 -0.01060581 0.05036777 0.1242051 -0.01067793 0.05018842 0.1305655 -0.01080858 0.04984611 0.08882862 -0.009890317 0.05179721 0.1274522 -0.01074481 0.05001568 0.1496973 -0.01119804 0.06499999 0.1335771 -0.01086997 0.0496779 0.1367527 -0.01093465 0.04949659 0.1395485 -0.01099145 0.04933303 0.1468845 -0.01114082 0.04888796 0.1427413 -0.01105642 0.04914236 0.1503817 -0.01121234 0.04866695 0.1540939 -0.01128864 0.04842662 0.1575497 -0.01136004 0.04819661 0.1612647 -0.01143711 0.04794347 0.1862658 -0.01196616 0.04605436 0.1696345 -0.01161181 0.06499999 0.1650267 -0.01151555 0.04767972 0.1685993 -0.01159042 0.04742306 0.1718897 -0.01165962 0.04718059 0.2025342 -0.01231813 0.04463195 0.1746103 -0.01171714 0.04697597 0.1783135 -0.01179569 0.04669141 0.1826221 -0.01188778 0.04635047 0.1867058 -0.01197516 0.06499999 0.2103787 -0.01248615 0.06499999 0.1904649 -0.01205706 0.04570341 0.1944196 -0.01214301 0.04536283 0.1972988 -0.01220548 0.04510849 0.2058047 -0.01238781 0.04432374 0.1997697 -0.01225882 0.04488581 0.2103319 -0.01248335 0.04388374 0.2080283 -0.01243478 0.04410958 0.2136693 -0.01255238 0.04354852 0.219591 -0.01266533 0.0429216 0.2168858 -0.01261562 0.04321342 0.2204605 -0.01268124 0.06499999 0.2217661 -0.01270115 0.04267728 0.2235491 -0.01272737 0.04247027 0.2265923 -0.01276469 0.06499999 0.2258448 -0.01275509 0.04219245 0.2279031 -0.01277261 0.04192972 0.2298356 -0.01278173 0.04166918 0.2317764 -0.01278316 0.06499999 0.2420766 -0.01273328 0.06499999 0.2315314 -0.01278162 0.0414254 0.2330637 -0.0127747 0.04119247 0.2349308 -0.01276004 0.04089421 0.2370404 -0.01274585 0.06499999 0.2372432 -0.01274579 0.04051786 0.239585 -0.01274168 0.0401411 0.2408649 -0.01273834 0.03992724 0.2419148 -0.01273041 0.03974163 0.2424283 -0.01273351 0.03966045 0.242771 -0.01274049 0.0396139 0.2432062 -0.01275265 0.06499999 0.2431281 -0.01275205 0.03957176 0.2434804 -0.01276797 0.03953731 0.2440519 -0.01279926 0.03949087 0.2446638 -0.01282662 0.06499999 0.244664 -0.01282095 0.03942304 6.08689e-5 4.56992e-4 0.02999997 8.20828e-5 5.27532e-4 0.06499999 0.07281136 -0.009452164 0.06499999 0.09637808 -0.01007288 0.05149346 0.09223163 -0.009974122 0.05166274 0.0886957 -0.009887874 0.06499999 0.08531999 -0.00980103 0.05193185 0.08162611 -0.009703278 0.052069 0.07770353 -0.009594857 0.05220991 0.07345098 -0.009470343 0.05235695 0.06907629 -0.009334206 0.05250269 0.06594759 -0.009230732 0.06499999 0.06472647 -0.009188592 0.05264216 0.05932092 -0.008993089 0.06499999 0.06013691 -0.009023129 0.05278432 0.05459946 -0.008802473 0.05294895 0.05099529 -0.008646667 0.06499999 0.0496847 -0.008583903 0.05308836 0.04548728 -0.00837624 0.05320185 0.04471015 -0.008335828 0.06499999 0.0419234 -0.008183062 0.0532937 0.04016053 -0.008081257 0.06499999 0.03839695 -0.007972955 0.05337888 0.03494668 -0.007748126 0.06499999 0.03539103 -0.007776677 0.05344557 0.03270262 -0.007585108 0.05349916 0.03040623 -0.007408738 0.06499999 0.02992397 -0.00736922 0.05354696 0.02663302 -0.007085919 0.06499999 0.02750754 -0.007163226 0.05357968 0.0258817 -0.007014453 0.05359625 0.02408516 -0.006840348 0.05360883 0.02320945 -0.006752133 0.06499999 0.02230864 -0.006655454 0.05361318 0.02034479 -0.006437003 0.06499999 0.02078777 -0.006487071 0.0536102 0.01941412 -0.006324529 0.05360019 0.01748889 -0.006080269 0.06499999 0.01792603 -0.006137013 0.05358111 0.01642137 -0.005931079 0.05354934 0.01519185 -0.005750775 0.06499999 0.01544862 -0.005789339 0.05352175 0.0145356 -0.005649745 0.05349016 0.01313072 -0.005422174 0.06499999 0.013314 -0.005451798 0.05343782 0.01210719 -0.005242168 0.05337256 0.01095634 -0.005030512 0.06499999 0.01102733 -0.005042791 0.05330169 0.009929835 -0.004827618 0.0532152 0.009166419 -0.004670262 0.06499999 0.008910357 -0.004613637 0.05311894 0.008185803 -0.004449188 0.05303704 0.007595419 -0.004306495 0.05296087 0.007593572 -0.004308402 0.06499999 0.007054626 -0.00416696 0.05288147 0.00601685 -0.00387597 0.06499999 0.006499528 -0.004013955 0.05278849 0.005947113 -0.003850281 0.05268245 0.00540018 -0.003675997 0.05256187 0.004587113 -0.003395676 0.06499999 0.005009531 -0.003543376 0.0524646 0.004608929 -0.003401517 0.05235582 0.004213273 -0.00325495 0.05223745 0.00382322 -0.003105401 0.05211114 0.003305494 -0.00289905 0.05192589 0.003400146 -0.002938389 0.06499999 0.002789914 -0.002685844 0.05172115 0.002093195 -0.002388954 0.06499999 0.002262234 -0.002459406 0.05148744 0.001938045 -0.002311289 0.05132359 0.001704812 -0.002196371 0.05119025 0.001372456 -0.002019882 0.06499999 0.001481831 -0.002076566 0.05104476 0.001273214 -0.001950323 0.05088388 0.001080095 -0.001819074 0.05070817 7.61449e-4 -0.001564502 0.06499999 9.06818e-4 -0.001683592 0.05051589 7.52466e-4 -0.001545369 0.05030888 6.19159e-4 -0.001407504 0.05008846 5.04947e-4 -0.001270532 0.04985564 4.04666e-4 -0.001132011 0.06499999 4.08044e-4 -0.001138091 0.04961389 3.27452e-4 -0.001009702 0.04936307 2.07722e-4 -7.85775e-4 0.06499999 2.59101e-4 -8.88098e-4 0.04910629 2.03408e-4 -7.72586e-4 0.04884308 1.19499e-4 -5.63902e-4 0.04830336 1.56632e-4 -6.64648e-4 0.04857569 8.9132e-5 -4.71148e-4 0.04802799 4.03742e-5 -2.99561e-4 0.06499999 6.61491e-5 -3.86281e-4 0.04774898 4.82358e-5 -3.10213e-4 0.04746747 3.57548e-5 -2.42419e-4 0.04718327 2.58571e-5 -1.82132e-4 0.04689764 1.51031e-5 -8.75745e-5 0.04632097 1.94442e-5 -1.29934e-4 0.04661005 8.89341e-6 1.34424e-4 0.06499999 1.31291e-5 -5.4164e-5 0.04603016 1.07963e-5 -9.56399e-6 0.04544734 1.14554e-5 -2.79169e-5 0.04573917 1.12688e-5 2.91784e-6 0.04461836 1.04242e-5 1.98968e-7 0.0451554 1.07596e-5 -3.95553e-7 0.04424488 6.44515e-6 0 0.02999997 2.66358e-4 9.67176e-4 0.02999997 2.34366e-4 8.92411e-4 0.06499999 5.21453e-4 0.001355111 0.06499999 7.10547e-4 0.001599371 0.02999997 0.04703527 -0.006395399 0.02999997 -0.003762245 -0.0108332 0.02999997 -0.009289622 -0.01062166 0.02999997 0.236219 -0.02068209 0.02999997 0.275 -0.02147608 0.02999997 0.242688 -0.0213629 0.02999997 0.2020842 -0.00403732 0.02999997 0.170091 -0.00248754 0.02999997 0.268542 -0.0243175 0.02999997 0.262082 -0.02354407 0.02999997 0.275 -0.02511399 0.02999997 0.25562 -0.02279376 0.02999997 0.249155 -0.02206677 0.02999997 0.2319329 -0.01018136 0.02999997 0.247061 -0.01113098 0.02999997 0.203841 -0.01762574 0.02999997 0.229748 -0.02002447 0.02999997 0.264083 -0.01221817 0.02999997 0.283 -0.01344305 0.02999997 0.170373 -0.01130837 0.02999997 0.17024 -0.01098167 0.02999997 0.226105 -0.008940875 0.02999997 0.2290289 -0.009556889 0.02999997 0.1705279 -0.01162296 0.02999997 0.177928 -0.01433068 0.02999997 0.171612 -0.01299577 0.02999997 0.171358 -0.0127539 0.02999997 0.1699336 -0.009238541 0.02999997 0.170705 -0.01192736 0.02999997 0.169983 -0.00996077 0.02999997 0.169946 -0.009612023 0.02999997 0.223184 -0.008334994 0.02999997 0.184387 -0.01606988 0.02999997 0.177898 -0.01559758 0.02999997 0.190874 -0.01656538 0.02999997 0.171883 -0.01322066 0.02999997 0.173102 -0.01391136 0.02999997 0.172781 -0.01377165 0.02999997 0.158922 -0.0134322 0.02999997 0.156834 -0.01383548 0.02999997 0.159245 -0.01327979 0.02999997 0.174816 -0.01425766 0.02999997 0.174464 -0.01423674 0.02999997 0.174116 -0.01419168 0.02999997 0.173773 -0.01412236 0.02999997 0.173435 -0.01402896 0.02999997 0.172468 -0.01360887 0.02999997 0.172169 -0.01342505 0.02999997 0.1582469 -0.01366585 0.02999997 0.1579 -0.0137459 0.02999997 0.171121 -0.01249325 0.02999997 0.170903 -0.01221776 0.02999997 0.2176697 -0.007204473 0.02999997 0.170131 -0.01064848 0.02999997 0.170045 -0.01030749 0.02999997 0.1575469 -0.01380127 0.02999997 0.157192 -0.01383095 0.02999997 0.08439826 -0.009134054 0.02999997 0.104703 -0.01219528 0.02999997 0.09957337 -0.01208436 0.02999997 0.07106935 -0.01085716 0.02999997 0.07062739 -0.01062065 0.02999997 0.0697804 -0.01008164 0.02999997 0.06937837 -0.009781301 0.02999997 0.06705266 -0.007172405 0.02999997 0.06679999 -0.006738245 0.02999997 0.07340127 -0.008875906 0.02999997 0.192177 -0.002032518 0.02999997 0.16993 -0.001554131 0.02999997 0.170008 -0.001859724 0.02999997 0.1798924 4.41266e-4 0.02999997 0.1698279 -0.001254081 0.02999997 0.1697019 -9.63498e-4 0.02999997 0.169384 -4.16226e-4 0.02999997 0.1695539 -6.83772e-4 0.02999997 0.168983 7.39299e-5 0.02999997 0.169193 -1.63714e-4 0.02999997 0.168509 4.94668e-4 0.02999997 0.1687549 2.93011e-4 0.02999997 0.167975 8.35428e-4 0.02999997 0.16825 6.74934e-4 0.02999997 0.1673949 0.001087367 0.02999997 0.1676909 9.72457e-4 0.02999997 0.166782 0.001244723 0.02999997 0.1720597 0.002002835 0.02999997 0.167092 0.001178085 0.02999997 0.165835 0.001295387 0.02999997 0.1662207 0.003157377 0.02999997 0.166469 0.001286625 0.02999997 0.1090666 0.01323384 0.02999997 0.05940645 0.00920099 0.02999997 0.0589596 0.009312331 0.02999997 0.06416779 0.005779325 0.02999997 0.13555 0.008976817 0.02999997 0.13848 0.008447468 0.02999997 0.06501424 0.01625472 0.02999997 0.06823074 0.01626974 0.02999997 0.06307983 0.01622509 0.02999997 0.05713355 0.009511172 0.02999997 0.03720664 0.01427942 0.02999997 0.03883278 0.01449376 0.02999997 0.1486104 0.006565511 0.02999997 0.08463299 8.63139e-4 0.02999997 0.05805176 0.009461164 0.02999997 0.09984129 0.01437395 0.02999997 0.06556457 -0.001886844 0.02999997 0.07363599 0.001121282 0.02999997 0.06862229 -0.009121596 0.02999997 0.06826949 -0.008764028 0.02999997 0.07245939 -0.01143026 0.02999997 0.0719881 -0.01126307 0.02999997 0.07905226 -0.0118134 0.02999997 0.07293856 -0.01157355 0.02999997 0.07342576 -0.01169306 0.02999997 0.07152479 -0.01107209 0.02999997 0.08418327 -0.0118553 0.02999997 0.07019805 -0.01036238 0.02999997 0.06793648 -0.008390188 0.02999997 0.130342 -0.01300829 0.02999997 0.1618109 -0.0100131 0.02999997 0.161715 -0.0103569 0.02999997 0.1252149 -0.01281118 0.02999997 0.120087 -0.01263135 0.02999997 0.161929 -0.009311735 0.02999997 0.140594 -0.01345425 0.02999997 0.160403 -0.01245439 0.02999997 0.1601369 -0.01269066 0.02999997 0.161282 -0.01133495 0.02999997 0.161094 -0.01163697 0.02999997 0.135468 -0.01322269 0.02999997 0.158589 -0.01356089 0.02999997 0.159853 -0.01290845 0.02999997 0.159556 -0.01310485 0.02999997 0.1606529 -0.01219797 0.02999997 0.160883 -0.01192617 0.02999997 0.16145 -0.01101905 0.02999997 0.161594 -0.01069289 0.02999997 0.161882 -0.009664714 0.02999997 0.1619499 -0.008954226 0.02999997 0.114959 -0.01246869 0.02999997 0.109831 -0.01232337 0.02999997 0.07392096 -0.01178866 0.02999997 0.06899285 -0.009461581 0.02999997 0.08931368 -0.01191437 0.02999997 0.06732589 -0.007591843 0.02999997 0.06762117 -0.007998704 0.02999997 0.06656879 -0.006291329 0.02999997 0.09444379 -0.01199078 0.02999997 0.06636166 -0.005835771 0.02999997 0.06617701 -0.005368888 0.02999997 0.162097 -0.0026955 0.02999997 0.04434728 -0.009225666 0.02999997 0.01835495 -0.01144385 0.02999997 0.04474246 -0.008931696 0.02999997 0.06587898 -0.004410564 0.02999997 0.06601536 -0.004891932 0.02999997 0.06576657 -0.003921508 0.02999997 0.04030209 -0.01090687 0.02999997 0.03834515 -0.01105368 0.02999997 0.04078358 -0.01081049 0.02999997 0.06561565 -0.002929031 0.02999997 0.06567829 -0.003425359 0.02999997 0.03932827 -0.01102834 0.02999997 0.03883838 -0.01105296 0.02999997 0.03496736 -0.01097434 0.02999997 0.04264318 -0.01019364 0.02999997 0.04219108 -0.01038157 0.02999997 0.06557786 -0.002428889 0.02999997 0.16211 -0.002377688 0.02999997 1.06042e-5 -2.6572e-7 0.02999997 -0.03691446 -0.009210646 0.02999997 -0.05899995 -0.005724668 0.02999997 0.162147 -0.002064168 0.02999997 0.16221 -0.001752614 0.02999997 1.63217e-5 1.91332e-4 0.02999997 0.04864293 0.001459777 0.02999997 0.162407 -0.001151263 0.02999997 0.1622959 -0.00144869 0.02999997 0.06563121 0.001011312 0.02999997 0.162541 -8.64551e-4 0.02999997 0.04941779 0.004582226 0.02999997 0.004520952 0.004918158 0.02999997 0.005069732 0.005253612 0.02999997 0.162874 -3.26305e-4 0.02999997 0.162697 -5.88672e-4 0.02999997 0.06561839 0.001473844 0.02999997 0.06558108 0.001932263 0.02999997 0.163072 -7.88719e-5 0.02999997 0.06551915 0.002386569 0.02999997 0.163522 3.65381e-4 0.02999997 0.163773 5.59926e-4 0.02999997 0.1544485 0.005450963 0.02999997 0.1603688 0.004303991 0.02999997 0.164037 7.33008e-4 0.02999997 0.06543278 0.002836823 0.02999997 0.06532186 0.003282964 0.02999997 0.06518638 0.003724992 0.02999997 0.06502807 0.004155874 0.02999997 0.1427524 0.007663369 0.02999997 0.06484645 0.004578113 0.02999997 0.06464129 0.004992246 0.02999997 0.06389838 0.006154656 0.02999997 0.06361055 0.006512939 0.02999997 0.132618 0.009498178 0.02999997 0.06441527 0.005392134 0.02999997 0.06227707 0.007776498 0.02999997 0.06297725 0.007181584 0.02999997 0.129685 0.01001077 0.02999997 0.0633037 0.006854891 0.02999997 0.06070137 0.008725047 0.02999997 0.1175671 0.01200205 0.02999997 0.06151455 0.008293867 0.02999997 0.1222851 0.01125538 0.02999997 0.05984747 0.009065449 0.02999997 0.1150965 0.01237624 0.02999997 0.06027859 0.008907139 0.02999997 0.1071051 0.01349467 0.02999997 0.1106774 0.0130127 0.02999997 0.09441661 0.01493412 0.02999997 0.09598851 0.0147804 0.02999997 0.1045736 0.01381748 0.02999997 0.05850869 0.009398818 0.02999997 0.08675926 0.01557213 0.02999997 0.05759245 0.009498775 0.02999997 0.090927 0.01524764 0.02999997 0.09250426 0.01511079 0.02999997 0.07655102 0.01611542 0.02999997 0.08225363 0.01585733 0.02999997 0.06020081 0.01615142 0.02999997 0.07301533 0.01621395 0.02999997 0.05858653 0.01609534 0.02999997 0.04326748 0.01500761 0.02999997 0.05029511 0.0156331 0.02999997 0.03031796 0.01320767 0.02999997 0.03158098 0.01342552 0.02999997 0.05667269 0.009498775 0.02999997 0.03436863 0.01387226 0.02999997 0.0562132 0.009461581 0.02999997 0.02626669 0.01243478 0.02999997 0.02777254 0.01273548 0.02999997 0.05356287 0.00872606 0.02999997 0.016285 0.009926378 0.02999997 0.01731389 0.01023393 0.02999997 0.02152544 0.0113663 0.02999997 0.05530565 0.009312808 0.02999997 0.05065435 0.006515622 0.02999997 0.05036467 0.006155669 0.02999997 0.009028911 0.007266938 0.02999997 0.05198907 0.007779419 0.02999997 0.05163007 0.007490873 0.02999997 0.01263856 0.008713603 0.02999997 0.001550376 0.002524375 0.02999997 0.04868137 0.001932263 0.02999997 0.001109004 0.002061963 0.02999997 0.002966642 0.003802835 0.02999997 0.04894167 0.003287255 0.02999997 0.002479195 0.003394782 0.02999997 6.34983e-4 0.001500666 0.02999997 8.86994e-4 0.001807928 0.02999997 2.50473e-4 9.21271e-4 0.02999997 1.64979e-4 7.44242e-4 0.02999997 3.50267e-4 0.001094698 0.02999997 9.54136e-5 5.63601e-4 0.02999997 4.488e-5 3.7929e-4 0.02999997 0.04822099 -0.003710865 0.02999997 0.0483396 -0.003235518 0.02999997 0.04843449 -0.002755939 0.02999997 0.04807877 -0.004181802 0.02999997 -0.05899995 -0.007658004 0.02999997 -0.05347979 -0.008081495 0.02999997 -0.04243695 -0.008857786 0.02999997 -0.04795879 -0.008481442 0.02999997 -0.05249649 0.001362383 0.02999997 -0.03499358 9.2959e-4 0.02999997 -0.01749116 4.75366e-4 0.02999997 0.04728645 -0.005975425 0.02999997 0.04751759 -0.005541324 0.02999997 -0.01481616 -0.01038658 0.02999997 0.04616028 -0.007578432 0.02999997 0.0458312 -0.007942318 0.02999997 0.007294774 -0.01118564 0.02999997 0.046763 -0.006803929 0.02999997 0.04647016 -0.007200002 0.02999997 0.04512107 -0.008620321 0.02999997 0.01282447 -0.01132655 0.02999997 0.04352027 -0.009750664 0.02999997 0.04394018 -0.009498417 0.02999997 0.03981506 -0.01097989 0.02999997 0.04125809 -0.01069116 0.02999997 0.04172849 -0.01054769 0.02999997 0.04308664 -0.009983181 0.02999997 0.02388638 -0.01153767 0.02999997 0.02941846 -0.011608 0.02999997 0.04548305 -0.008291542 0.02999997 0.001765847 -0.01102119 0.02999997 -0.02034187 -0.0101279 0.02999997 -0.02586686 -0.009845674 0.02999997 0.04772716 -0.005096793 0.02999997 -0.03139108 -0.009539961 0.02999997 0.04791408 -0.004644334 0.02999997 -0.06999999 -0.005724668 0.02999997 0.03495138 -0.01165467 0.02999997 4.6183e-4 0.001264572 0.02999997 -0.06999999 0.001773774 0.02999997 0.04883056 0.002840816 0.02999997 0.002007126 0.002968668 0.02999997 0.04874318 0.002386569 0.02999997 0.003469407 0.004192709 0.02999997 0.003987491 0.004564464 0.02999997 0.04907619 0.003725588 0.02999997 0.005942583 0.005742788 0.02999997 0.04962146 0.004993081 0.02999997 0.04923588 0.00415951 0.02999997 0.007910251 0.006755352 0.02999997 0.05009716 0.00578314 0.02999997 0.007332801 0.006475925 0.02999997 0.006761968 0.006184637 0.02999997 0.04984915 0.005395293 0.02999997 0.00966221 0.007544279 0.02999997 0.05096185 0.006858289 0.02999997 0.05128616 0.007182657 0.02999997 0.01084458 0.00803107 0.02999997 0.05236166 0.008047044 0.02999997 0.01324176 0.008928954 0.02999997 0.01416343 0.009245276 0.02999997 0.04850566 -0.002272009 0.02999997 0.04857718 -0.001291155 0.02999997 0.04855328 -0.001783728 0.02999997 0.01025158 0.007791936 0.02999997 0.01184844 0.008420586 0.02999997 0.05275076 0.008295476 0.02999997 0.01536852 0.00964117 0.02999997 0.05315178 0.008522152 0.02999997 0.05398684 0.008908152 0.02999997 0.01842951 0.01055383 0.02999997 0.05441939 0.009066998 0.02999997 0.0196067 0.01087409 0.02999997 0.05485808 0.009201705 0.02999997 0.02060019 0.01113319 0.02999997 0.05575835 0.009399592 0.02999997 0.02279245 0.01167035 0.02999997 0.02371156 0.0118823 0.02999997 0.02464222 0.01209002 0.02999997 0.0290814 0.01298356 0.02999997 0.03283208 0.01363193 0.02999997 0.03598833 0.01411014 0.02999997 0.04043424 0.0146901 0.02999997 0.04168349 0.01483488 0.02999997 0.04491442 0.01517397 0.02999997 0.04614949 0.01529067 0.02999997 0.04742515 0.0154041 0.02999997 0.04869985 0.01551008 0.02999997 0.05220955 0.01576554 0.02999997 0.05383443 0.01586556 0.02999997 0.05508518 0.01593506 0.02999997 0.05666798 0.01601409 0.02999997 0.07172125 0.01623797 0.02999997 0.06149464 0.01618862 0.02999997 0.06661456 0.01626718 0.02999997 0.07015103 0.01625841 0.02999997 0.07463163 0.01617509 0.02999997 0.0781483 0.01605486 0.02999997 0.08006256 0.01597088 0.02999997 0.08448684 0.01572501 0.02999997 0.08902102 0.01540356 0.02999997 0.09766048 0.01460927 0.02999997 0.1020531 0.01412093 0.02999997 0.1125797 0.01274424 0.02999997 0.06111478 0.008519887 0.02999997 0.1197212 0.01166588 0.02999997 0.06190216 0.008045971 0.02999997 0.1257414 0.01068437 0.02999997 0.06263506 0.007488727 0.02999997 0.1643159 8.85726e-4 0.02999997 0.164604 0.001015067 0.02999997 0.1649039 0.001121759 0.02999997 0.165521 0.001262187 0.02999997 0.1652089 0.001204133 0.02999997 0.166152 0.001303493 0.02999997 0.170062 -0.00217086 0.02999997 0.197359 -0.017084 0.02999997 0.210321 -0.01819068 0.02999997 0.216799 -0.0187788 0.02999997 0.223275 -0.0193901 0.02999997 0.283 -0.02147608 0.02999997 0.163289 1.52518e-4 0.02999997 -0.06999999 -0.005724668 0 -0.06999999 0.001775264 0 -0.06999999 0.001773774 0.02999997 -0.06999999 -0.005724668 0.02999997 -0.07699996 -0.01322466 0 -0.08099997 -0.01372468 0 -0.08099997 -0.006209254 0 -0.06999999 -0.005724668 0 -0.07699996 -0.01372468 0 -0.05899995 -0.01322466 0 -0.08121776 0.002021253 0 -0.08611798 -0.0058766 0 -0.09123456 -0.005570232 0 -0.116797 -0.004433274 0 -0.103637 0.002447724 0 -0.111687 -0.004608035 0 -0.09634989 -0.00529021 0 -0.101464 -0.005036532 0 -0.09242999 0.002245426 0 -0.121906 -0.004284799 0 -0.114838 0.002628147 0 -0.127013 -0.004162669 0 -0.126033 0.002786695 0 -0.1321189 -0.004066824 0 -0.137223 -0.003997266 0 -0.106576 -0.004809141 0 -0.139963 -0.006048381 0 -0.1519888 -0.006048381 0 -0.137223 0.002923369 0 -0.139964 0.002951443 0 -0.06999999 0.001775264 0 -0.05899995 -0.005724668 0 -0.137223 0.002923369 0 -0.139964 0.002951443 0 -0.139964 0.002951443 0.03299999 -0.137223 0.002923309 0.03299999 -0.137223 0.002923309 0.03299999 -0.137223 0.002890348 0.03042256 -0.137223 0.002914726 0.02785468 -0.137223 0.002922892 0.02528202 -0.137223 0.002855181 0.03299999 -0.137223 0.002923309 0.03299999 -0.139964 0.002951443 0.03299999 -0.1401 0.002849698 0.03299999 -0.137223 0.002855181 0.03299999 -0.1401849 0.002786099 0.03360176 -0.1401 0.002849698 0.03299999 -0.151383 -0.005595147 0.04199999 -0.1399639 0.002951383 0 -0.151383 -0.005595147 0 -0.1627414 -0.0140962 0.05125373 -0.188 -0.03299999 0.04199999 -0.188 -0.03299999 0.04834479 -0.1802125 -0.02717167 0.04968631 -0.1769856 -0.02475666 0.05023777 -0.1735832 -0.02220982 0.05081218 -0.1721383 -0.02112895 0.05103951 -0.1709681 -0.02025282 0.05118602 -0.1716639 -0.02077406 0.05110287 -0.1699596 -0.01949834 0.05128878 -0.1690064 -0.01878523 0.05136042 -0.1680396 -0.01806104 0.0514096 -0.1670665 -0.01733285 0.05143511 -0.1660789 -0.01659417 0.05143713 -0.165123 -0.01587861 0.0514149 -0.164409 -0.01534396 0.05138188 -0.1636939 -0.01480907 0.05133658 -0.1617998 -0.01339089 0.05114674 -0.1608394 -0.0126723 0.05101144 -0.1601279 -0.01213985 0.05089378 -0.1594224 -0.01161164 0.05076271 -0.1586999 -0.0110715 0.05061119 -0.1582249 -0.01071578 0.05050325 -0.157748 -0.01035857 0.05038678 -0.157269 -0.01000034 0.05026227 -0.15679 -0.009641468 0.05012995 -0.156309 -0.009281933 0.04999005 -0.155833 -0.008925199 0.04984259 -0.15536 -0.008571803 0.04968768 -0.15489 -0.008220076 0.04952526 -0.1544229 -0.007870018 0.04935526 -0.153952 -0.007517755 0.04917466 -0.153475 -0.007160425 0.04898118 -0.152995 -0.006801366 0.0487774 -0.152513 -0.00644052 0.0485633 -0.1520349 -0.00608319 0.04834127 -0.151576 -0.005739629 0.04811537 -0.151124 -0.005401432 0.04788225 -0.15068 -0.005068659 0.04764187 -0.150242 -0.004741251 0.04739415 -0.149812 -0.004419267 0.04713928 -0.149389 -0.004102647 0.04687708 -0.148973 -0.003791451 0.04660767 -0.148564 -0.003485321 0.04633045 -0.148147 -0.003173351 0.0460335 -0.147732 -0.002862334 0.04572427 -0.147318 -0.00255233 0.04540276 -0.146905 -0.00224328 0.04506909 -0.146507 -0.001945555 0.04472875 -0.146118 -0.001654326 0.04437935 -0.145736 -0.001368761 0.04402029 -0.145362 -0.001088738 0.04365158 -0.144991 -8.10875e-4 0.04326367 -0.144623 -5.35732e-4 0.04285818 -0.1442599 -2.64273e-4 0.04243785 -0.143903 3.50054e-6 0.04200267 -0.1435599 2.60171e-4 0.04155856 -0.143234 5.03852e-4 0.04110729 -0.14292 7.38567e-4 0.04064536 -0.142619 9.64315e-4 0.04017299 -0.1423299 0.00118041 0.03968769 -0.142055 0.001386165 0.03918737 -0.141793 0.001582264 0.03867429 -0.141544 0.001768767 0.0381484 -0.14131 0.001944005 0.03761094 -0.1410959 0.002103984 0.03706508 -0.140898 0.002251863 0.03650826 -0.140717 0.002387583 0.03594058 -0.1405529 0.002510488 0.03536325 -0.140411 0.002616465 0.03478348 -0.1402879 0.002708375 0.03419625 -0.139964 0.002951443 0.03299999 -0.1930665 -0.04199999 0.04745328 -0.194073 -0.04199999 0.04727315 -0.204724 -0.04199999 0.04547178 -0.206232 -0.04199999 0.04520809 -0.20015 -0.04199999 0.04622757 -0.199147 -0.04199999 0.04640829 -0.215885 -0.04199999 0.04366236 -0.218406 -0.04199999 0.04324799 -0.212317 -0.04199999 0.04421496 -0.210303 -0.04199999 0.04455649 -0.227056 -0.04199999 0.04193788 -0.230597 -0.04199999 0.04139286 -0.224499 -0.04199999 0.04230725 -0.221469 -0.04199999 0.04278957 -0.236698 -0.04199999 0.04050457 -0.238237 -0.04199999 0.0402981 -0.242803 -0.04199999 0.03964257 -0.232645 -0.04199999 0.04110735 -0.248912 -0.04199999 0.03880685 -0.24383 -0.04199999 0.03950995 -0.2499495 -0.04199999 0.03867197 -0.187999 -0.04199999 0.04833972 -0.1879996 -0.03299999 0.0483427 -0.2125953 -0.03299999 0.0441842 -0.2024277 -0.04199999 0.0458523 -0.201444 -0.03299999 0.04601746 -0.2247514 -0.04199999 0.04228413 -0.2237655 -0.03299999 0.04243439 -0.2135804 -0.04199999 0.04402643 -0.2468181 -0.03299999 0.03909391 -0.247416 -0.04199999 0.03901302 -0.2359074 -0.04199999 0.04063016 -0.2349205 -0.03299999 0.04077303 -0.255026 -0.04199999 0.03799736 -0.255026 -0.03299999 0.03799736 -0.188 -0.03299999 0 -0.3000003 -0.03299999 0 -0.221469 -0.03299999 0.04278957 -0.215885 -0.03299999 0.04366236 -0.295498 -0.03299999 0.009909749 -0.2900008 -0.03299999 0.0219987 -0.289505 -0.03299999 0.02275878 -0.285105 -0.03299999 0.02793288 -0.258078 -0.03299999 0.03768128 -0.285696 -0.03299999 0.0273689 -0.25656 -0.03299999 0.03784996 -0.284502 -0.03299999 0.02847248 -0.26542 -0.03299999 0.03651875 -0.263985 -0.03299999 0.03679388 -0.262533 -0.03299999 0.03704756 -0.269627 -0.03299999 0.03556615 -0.281982 -0.03299999 0.0304203 -0.270996 -0.03299999 0.03520607 -0.268241 -0.03299999 0.035905 -0.283887 -0.03299999 0.02898836 -0.283262 -0.03299999 0.02948498 -0.273685 -0.03299999 0.03442209 -0.272349 -0.03299999 0.03482466 -0.277902 -0.03299999 0.03276926 -0.280658 -0.03299999 0.03127217 -0.278604 -0.03299999 0.03242015 -0.277191 -0.03299999 0.03310167 -0.276471 -0.03299999 0.03341728 -0.275742 -0.03299999 0.03371596 -0.2750048 -0.03299999 0.03399801 -0.279298 -0.03299999 0.0320543 -0.279982 -0.03299999 0.03167158 -0.281325 -0.03299999 0.03085589 -0.282627 -0.03299999 0.0299623 -0.266839 -0.03299999 0.03622257 -0.261065 -0.03299999 0.03728008 -0.25958 -0.03299999 0.03749126 -0.286276 -0.03299999 0.02678287 -0.255026 -0.03299999 0.03799736 -0.286844 -0.03299999 0.02617478 -0.287402 -0.03299999 0.02554476 -0.288478 -0.03299999 0.02420204 -0.287946 -0.03299999 0.02488648 -0.288997 -0.03299999 0.02349287 -0.249427 -0.03299999 0.03874307 -0.24383 -0.03299999 0.03950995 -0.238237 -0.03299999 0.0402981 -0.232645 -0.03299999 0.04110735 -0.227056 -0.03299999 0.04193788 -0.210303 -0.03299999 0.04455649 -0.204724 -0.03299999 0.04547178 -0.199147 -0.03299999 0.04640829 -0.193572 -0.03299999 0.04736596 -0.188 -0.03299999 0.04834479 -0.2841268 -0.04199999 0.02880632 -0.2839359 -0.03299999 0.02895861 -0.2853518 -0.03299999 0.02770555 -0.2859281 -0.04199999 0.02715939 -0.2865248 -0.03299999 0.02652502 -0.2872701 -0.04199999 0.02570575 -0.2876336 -0.03299999 0.02527445 -0.2886902 -0.03299999 0.0239219 -0.2885836 -0.04199999 0.0240736 -0.290005 -0.03299999 0.02200323 -0.2900028 -0.04199999 0.0220018 -0.2826644 -0.04199999 0.02994656 -0.2822611 -0.03299999 0.03022915 -0.281 -0.04199999 0.03107517 -0.2807447 -0.03299999 0.03122729 -0.2794612 -0.04199999 0.03197544 -0.2789716 -0.03299999 0.03223192 -0.2780112 -0.04199999 0.03271806 -0.2775896 -0.03299999 0.0329203 -0.2761062 -0.03299999 0.03357249 -0.2767087 -0.04199999 0.03331792 -0.2750049 -0.04199999 0.03400057 -0.275004 -0.03299999 0.03399825 -0.295861 -0.04440045 0.00879997 -0.2954753 -0.04176008 0.01001971 -0.2975028 -0.04133862 0.005586862 -0.2928863 -0.06235116 8.98787e-4 -0.291581 -0.06460112 7.05573e-4 -0.2922112 -0.05158185 0.01584851 -0.292804 -0.04830276 0.01530128 -0.294884 -0.04466354 0.01099997 -0.294673 -0.04759085 0.01092946 -0.293738 -0.04794687 0.01311534 -0.29 -0.05570107 0.02000808 -0.29 -0.0550704 0.02029949 -0.290814 -0.05539149 0.01790875 -0.297476 -0.04652315 0.004371762 -0.296542 -0.04687905 0.006557643 -0.297815 -0.0438742 0.004399955 -0.2955922 -0.03883689 0.009941995 -0.299634 -0.04430949 0 -0.298411 -0.04616719 0.002185881 -0.298792 -0.04361104 0.002199947 -0.299055 -0.04098784 0.002199947 -0.300021 -0.04129785 0 -0.29 -0.05442929 0.02056896 -0.29088 -0.05227249 0.01904755 -0.300086 -0.03405845 0 -0.3000047 -0.03299969 2.13456e-6 -0.293907 -0.0449267 0.01319998 -0.291869 -0.04865866 0.01748716 -0.2924039 -0.04545074 0.01657748 -0.296838 -0.04413735 0.006599962 -0.2965956 -0.03577363 0.007751882 -0.29 -0.05245405 0.02124208 -0.29 -0.05178558 0.02141916 -0.298554 -0.04918795 0 -0.297918 -0.04867726 0.002116382 -0.2988628 -0.0479893 0 -0.2984132 -0.03568387 0.003828346 -0.300149 -0.03511077 0 -0.2934606 -0.04225021 0.01442068 -0.290935 -0.04901456 0.01967304 -0.29 -0.0511105 0.02157306 -0.300187 -0.03615719 0 -0.300159 -0.03925979 0 -0.2989205 -0.03833717 0.002767622 -0.2968522 -0.03299999 0.006929993 -0.300202 -0.03719735 0 -0.300193 -0.03823167 0 -0.299916 -0.04230779 0 -0.300102 -0.04028189 0 -0.299787 -0.04331165 0 -0.29 -0.04837805 0.02195274 -0.29 -0.04906308 0.02189356 -0.2945492 -0.03588038 0.01217198 -0.29 -0.04769039 0.02198815 -0.290977 -0.04571604 0.01979994 -0.2948837 -0.03299999 0.01126116 -0.2915307 -0.04261618 0.01864874 -0.2921003 -0.03941941 0.01747 -0.2923302 -0.03299999 0.01687806 -0.291936 -0.03573459 0.01781278 -0.2899962 -0.03299999 0.02199822 -0.293519 -0.0509243 0.01269835 -0.296627 -0.053523 0.001809358 -0.2975484 -0.05243897 0 -0.2967872 -0.0544756 3.6176e-7 -0.290736 -0.05827909 0.01628458 -0.29 -0.0598095 0.01735937 -0.29 -0.05926257 0.01779937 -0.29 -0.05812597 0.01861965 -0.29 -0.05869847 0.01822179 -0.294399 -0.05047488 0.01058197 -0.297039 -0.04912668 0.004232764 -0.296159 -0.0495761 0.006349146 -0.295607 -0.04723495 0.008743584 -0.299256 -0.04628688 0 -0.2936776 -0.05351614 0.01090461 -0.292067 -0.05456614 0.01484632 -0.29 -0.06134998 0.01593089 -0.29 -0.06085175 0.01642668 -0.290649 -0.06084918 0.01422065 -0.2961441 -0.05604916 0 -0.2948319 -0.05818372 0.001686394 -0.29 -0.06183159 0.0154168 -0.29 -0.06229335 0.01488816 -0.295695 -0.05219739 0.005969583 -0.297322 -0.05113267 0.001989841 -0.2918422 -0.05738472 0.01356911 -0.2933277 -0.05618053 0.009920656 -0.2953411 -0.05784207 0 -0.294881 -0.05272966 0.007959485 -0.2981574 -0.05057436 0 -0.2947948 -0.05499786 0.006315767 -0.2942312 -0.05738908 0.005495727 -0.295279 -0.05002546 0.008465588 -0.290551 -0.06302559 0.01177966 -0.29 -0.06430906 0.01201909 -0.29 -0.0639472 0.01261949 -0.2955931 -0.05603986 0.002229273 -0.29 -0.06356328 0.01320886 -0.29 -0.06315737 0.01378726 -0.2945186 -0.0595175 1.35364e-7 -0.2939019 -0.0603221 0.00128597 -0.2911235 -0.06387913 0.007507324 -0.2914026 -0.06206607 0.009765565 -0.2924956 -0.06084126 0.007165968 -0.292923 -0.06158417 0.003450751 -0.2936115 -0.05958306 0.004525005 -0.2935781 -0.06128662 0 -0.29 -0.06526648 0.0101431 -0.29 -0.06496858 0.01078134 -0.290444 -0.06474566 0.009038031 -0.2916441 -0.05988496 0.01179885 -0.29 -0.06579196 0.008844852 -0.29 -0.0655409 0.009497582 -0.291831 -0.06422257 3.34465e-4 -0.2925593 -0.06306058 0 -0.2912229 -0.06519675 -5.31957e-7 -0.290601 -0.06612962 0 -0.29 -0.06601959 0.00818485 -0.2903311 -0.06596499 0.006054818 -0.29 -0.06640648 0.006833314 -0.29 -0.06622511 0.007510721 -0.29 -0.06656366 0.006152629 -0.29 -0.06669676 0.005468666 -0.29 -0.06689047 0.004090964 -0.29 -0.06680566 0.004781424 -0.29 -0.06698757 0.002700269 -0.29 -0.06699997 0.001999974 -0.29 -0.06695115 0.003397226 -0.2900006 -0.06700038 0 -0.299457 -0.04530119 0 -0.2899981 -0.04699516 0.02199912 -0.29 -0.04974538 0.02181077 -0.29 -0.05042874 0.02170389 -0.29 -0.05753958 0.01899749 -0.29 -0.05377775 0.02081638 -0.29 -0.0569393 0.01935529 -0.29 -0.0531159 0.02104187 -0.2929331 -0.05864226 0.008659303 -0.296508 -0.05166506 0.003979682 -0.29 -0.06033915 0.01690185 -0.29 -0.05632489 0.01969289 -0.29589 -0.0541175 0.003618776 -0.29 -0.06273525 0.01434499 -0.29 -0.0646491 0.01140767 -0.2920176 -0.06273967 0.005490005 -0.2915005 -0.06431311 0.003680229 -0.291145 -0.06524777 0.001451492 -0.2902762 -0.06653177 0.002940297 -0.290656 -0.05972379 0 -0.28658 -0.05942904 0 -0.285722 -0.06103229 0 -0.292786 -0.06267446 0 -0.288189 -0.0561707 0 -0.2878 -0.05699175 0 -0.2904714 -0.05755132 0 -0.285279 -0.06182736 0 -0.284827 -0.06261628 0 -0.292277 -0.06352651 0 -0.290289 -0.05540466 0 -0.293279 -0.06181699 0 -0.295103 -0.05833786 0 -0.29552 -0.05745375 0 -0.293758 -0.06095379 0 -0.288569 -0.05534517 0 -0.28894 -0.05451536 0 -0.29422 -0.06008505 0 -0.29467 -0.05921494 0 -0.2901443 -0.05370235 0 -0.289302 -0.05368125 0 -0.289656 -0.05284279 0 -0.29592 -0.05656266 0 -0.2900002 -0.05199956 0 -0.261032 -0.08886969 0 -0.2546232 -0.08412551 0 -0.26007 -0.0892353 0 -0.299787 -0.04331165 0 -0.292054 -0.0427652 0 -0.29194 -0.04352825 0 -0.287402 -0.05780857 0 -0.286996 -0.05862098 0 -0.286155 -0.06023287 0 -0.282907 -0.06570279 0 -0.2899984 -0.06700277 0 -0.2902967 -0.06656962 0 -0.283402 -0.06493985 0 -0.281354 -0.06794577 0 -0.288835 -0.06880277 0 -0.281886 -0.06721037 0 -0.289425 -0.06791126 0 -0.282402 -0.06645977 0 -0.286969 -0.07135885 0 -0.279685 -0.0701012 0 -0.286316 -0.0721715 0 -0.28081 -0.06867277 0 -0.280254 -0.06939119 0 -0.287607 -0.07052659 0 -0.277275 -0.07282328 0 -0.284262 -0.07449066 0 -0.277902 -0.07216757 0 -0.278513 -0.07149559 0 -0.285647 -0.07296431 0 -0.279105 -0.07080256 0 -0.282066 -0.07663226 0 -0.275978 -0.0740956 0 -0.275307 -0.07471209 0 -0.283546 -0.07522428 0 -0.276634 -0.073466 0 -0.282814 -0.07593816 0 -0.273203 -0.07644808 0 -0.278953 -0.0792424 0 -0.279748 -0.07861346 0 -0.274623 -0.07531547 0 -0.280531 -0.0779674 0 -0.281303 -0.07730668 0 -0.276488 -0.0810256 0 -0.270953 -0.07798808 0 -0.270172 -0.07846289 0 -0.278144 -0.07985407 0 -0.272469 -0.07698071 0 -0.271719 -0.07749396 0 -0.267771 -0.07976007 0 -0.273059 -0.08319801 0 -0.27393 -0.08267515 0 -0.269377 -0.0789178 0 -0.27479 -0.08213776 0 -0.27564 -0.08158546 0 -0.266951 -0.08015048 0 -0.266119 -0.08052027 0 -0.271286 -0.08419919 0 -0.272177 -0.0837059 0 -0.265276 -0.08086955 0 -0.263704 -0.08147168 0 -0.270384 -0.08467769 0 -0.269475 -0.08514428 0 -0.268563 -0.08560365 0 -0.261857 -0.08212149 0 -0.26099 -0.08239799 0 -0.266718 -0.0864858 0 -0.262717 -0.08182895 0 -0.267644 -0.08605086 0 -0.2633076 -0.08796012 0 -0.2575265 -0.08337801 0 -0.264842 -0.08731895 0 -0.265783 -0.08690845 0 -0.260118 -0.08265858 0 -0.261989 -0.0884943 0 -0.256607 -0.08362567 0 -0.255727 -0.08385288 0 -0.2530701 -0.08448946 0 -0.259102 -0.08959108 0 -0.25813 -0.08993726 0 -0.257153 -0.09027367 0 -0.256763 -0.09042155 0 -0.2508804 -0.08501607 0 -0.256381 -0.09059339 0 -0.2491024 -0.08543032 0 -0.256007 -0.09079009 0 -0.255642 -0.09101051 0 -0.246491 -0.08602041 0 -0.255292 -0.09125238 0 -0.254633 -0.09180349 0 -0.254953 -0.0915187 0 -0.2446246 -0.08643263 0 -0.254331 -0.09210675 0 -0.254048 -0.09242928 0 -0.253788 -0.0927639 0 -0.2428125 -0.08682405 0 -0.25355 -0.09311038 0 -0.2411431 -0.08717519 0 -0.253335 -0.09346896 0 -0.253142 -0.09383958 0 -0.2393343 -0.08754605 0 -0.2370784 -0.08799481 0 -0.250747 -0.09879046 0 -0.2348617 -0.08842027 0 -0.2330681 -0.08875411 0 -0.2308372 -0.0891568 0 -0.299916 -0.04230779 0 -0.26858 -0.07934916 0 -0.277323 -0.0804485 0 -0.273922 -0.07589626 0 -0.284962 -0.07373738 0 -0.288229 -0.06967461 0 -0.2906306 -0.06608647 0 -0.283887 -0.06417119 0 -0.291212 -0.06521356 0 -0.291752 -0.06437277 0 -0.284362 -0.06339669 0 -0.296305 -0.05566459 0 -0.296673 -0.0547595 0 -0.290656 -0.04956316 0 -0.297025 -0.05384737 0 -0.297369 -0.05293196 0 -0.297694 -0.05200827 0 -0.297999 -0.05107647 0 -0.291215 -0.04731476 0 -0.291039 -0.04806625 0 -0.298802 -0.04823136 0 -0.290853 -0.04881566 0 -0.298286 -0.05013638 0 -0.298554 -0.04918795 0 -0.291681 -0.04504877 0 -0.299457 -0.04530119 0 -0.291815 -0.04428958 0 -0.299256 -0.04628688 0 -0.291536 -0.04580605 0 -0.29138 -0.04656147 0 -0.299634 -0.04430949 0 -0.292158 -0.04199999 0 -0.300021 -0.04129785 0 -0.300102 -0.04028189 0 -0.300159 -0.03925979 0 -0.300193 -0.03823167 0 -0.300202 -0.03719735 0 -0.300187 -0.03615719 0 -0.300149 -0.03511077 0 -0.300086 -0.03405845 0 -0.3 -0.03299999 0 -0.188 -0.03299999 0 -0.185392 -0.03104835 0 -0.173367 -0.03104835 0 -0.188 -0.04199999 0 -0.299032 -0.04726648 0 -0.253763 -0.09274768 0.01555997 -0.2539339 -0.0923317 0.01858699 -0.2552279 -0.09130442 0.0125584 -0.2552036 -0.09131252 0 -0.2543997 -0.09202784 0 -0.254451 -0.09190487 0.01542168 -0.2545417 -0.0915485 0.01832032 -0.2552202 -0.09090739 0.01808035 -0.253134 -0.09385639 0.01020079 -0.253137 -0.09384965 0.01103276 -0.2536914 -0.09289962 0.003255844 -0.2561627 -0.09070974 0.01255786 -0.2571557 -0.09027397 0.005228102 -0.256158 -0.09070789 0.003142058 -0.2571514 -0.0902692 0 -0.2565453 -0.09051483 0 -0.256188 -0.09058856 0.01516795 -0.257146 -0.09025228 0.01389545 -0.25527 -0.09117621 0.01528936 -0.2558351 -0.09045505 0.01789474 -0.2565665 -0.09003967 0.01770442 -0.257172 -0.09015178 0.01511746 -0.257203 -0.09007245 0.01572448 -0.257245 -0.0899738 0.01632875 -0.257012 -0.08984756 0.01760357 -0.257299 -0.08985567 0.0169304 -0.257364 -0.08971816 0.01752924 -0.2531286 -0.09386771 0.01253998 -0.253137 -0.09385055 0.01337516 -0.253689 -0.09290516 0.01256257 -0.253156 -0.09381169 0.01415169 -0.253185 -0.09375005 0.01492899 -0.253226 -0.09366577 0.01570725 -0.253341 -0.09342908 0.01726657 -0.253278 -0.09355878 0.01648646 -0.2534946 -0.09309923 0.01882958 -0.253415 -0.09327667 0.01804757 -0.2531333 -0.093858 0.00896275 -0.2531411 -0.09384214 0.006918847 -0.2539131 -0.09259307 0 -0.2531408 -0.09383881 0 -0.2534249 -0.09330546 0 -0.25715 -0.09027338 0.01328039 -0.2543914 -0.09204667 0.01255452 -0.257153 -0.0902118 0.01450777 -0.2571654 -0.09027493 0.01268047 -0.2558187 -0.0908966 0 -0.2550233 -0.09099471 0.01861727 -0.2555975 -0.09051859 0.01848912 -0.2552532 -0.09088051 0.01806974 -0.2562277 -0.0901004 0.0183832 -0.2565174 -0.0897302 0.01913833 -0.2560336 -0.09032571 0.01783895 -0.2568948 -0.08975613 0.01828587 -0.2568648 -0.08990567 0.01763558 -0.257396 -0.08962786 0.01789897 -0.257404 -0.08954137 0.01826769 -0.257364 -0.08971816 0.01752924 -0.2558936 -0.09011793 0.01914805 -0.2545786 -0.09150892 0.01830613 -0.2545069 -0.09152543 0.0187624 -0.2547821 -0.09106814 0.01923257 -0.2549715 -0.09070169 0.01964569 -0.2553132 -0.09056454 0.01918333 -0.2548391 -0.09062117 0.02007555 -0.2551925 -0.09009844 0.02047777 -0.2553307 -0.09031075 0.01980954 -0.2542743 -0.09111845 0.02025765 -0.2545471 -0.09057301 0.02062076 -0.2545773 -0.09106409 0.01977336 -0.2544316 -0.09018903 0.02132397 -0.2538763 -0.09061634 0.02138233 -0.2539083 -0.09015589 0.02190977 -0.2539639 -0.09112054 0.02071547 -0.2542437 -0.09056776 0.0210241 -0.252812 -0.0912953 0.02172946 -0.252986 -0.09150475 0.02142375 -0.2533152 -0.0904119 0.02214395 -0.2529833 -0.09083002 0.0219863 -0.2511655 -0.09117072 0.02290242 -0.2520148 -0.09072345 0.02279216 -0.2518826 -0.09124797 0.02241832 -0.2523164 -0.09100073 0.02233457 -0.2506046 -0.09407913 0.02173763 -0.2501893 -0.09392654 0.02191376 -0.2503474 -0.09181213 0.02283167 -0.2501242 -0.09142214 0.02323836 -0.2495036 -0.09207946 0.02301079 -0.2490143 -0.09189552 0.02333909 -0.2507391 -0.09225022 0.02238053 -0.2499501 -0.09226787 0.02271085 -0.2453659 -0.09314084 0.02345788 -0.2458543 -0.09242141 0.02398389 -0.2462475 -0.09271997 0.02358931 -0.2489711 -0.09381556 0.02228659 -0.2484788 -0.09360766 0.02248835 -0.2492453 -0.09312307 0.02250242 -0.2489623 -0.09621804 0.02181339 -0.2484568 -0.09613329 0.02185511 -0.2490743 -0.09550279 0.02186024 -0.2491595 -0.09269529 0.02275174 -0.2482345 -0.09562319 0.02193427 -0.2477273 -0.09411036 0.02242648 -0.2482502 -0.0943399 0.02225089 -0.2479166 -0.09736329 0.02181953 -0.2478365 -0.09672743 0.02182888 -0.2484557 -0.09260702 0.02303433 -0.2483573 -0.0931527 0.02274 -0.2487528 -0.09161472 0.02368342 -0.2473803 -0.09220385 0.02368414 -0.2481349 -0.09230214 0.0233488 -0.2472711 -0.09272217 0.02330374 -0.2464184 -0.09315502 0.02320832 -0.2455774 -0.0935992 0.02306401 -0.2444999 -0.0935682 0.02327841 -0.244755 -0.09404838 0.02287453 -0.2436534 -0.09399789 0.02305299 -0.2442541 -0.09313458 0.02373176 -0.2428691 -0.09324628 0.02396923 -0.242501 -0.09395545 0.02326482 -0.2412959 -0.09394389 0.02350151 -0.2400488 -0.09398847 0.0237618 -0.2412695 -0.09455209 0.02279895 -0.241309 -0.09524744 0.0221315 -0.2404931 -0.09493756 0.02244013 -0.2374643 -0.09468048 0.02340954 -0.2379159 -0.09415388 0.02445906 -0.2389989 -0.09401786 0.02411645 -0.2396343 -0.09470343 0.02280282 -0.2396589 -0.09535056 0.02199321 -0.2383431 -0.09530514 0.02206534 -0.237273 -0.09443247 0.02416825 -0.236338 -0.09484499 0.02367055 -0.238303 -0.095833 0.02129876 -0.237803 -0.0955854 0.02164787 -0.2348819 -0.09550589 0.02265447 -0.235161 -0.0953772 0.02287775 -0.2352445 -0.09566801 0.02185493 -0.235446 -0.09524691 0.02309107 -0.236261 -0.09521347 0.02265763 -0.236413 -0.09560537 0.02168971 -0.2358309 -0.09586709 0.02117532 -0.2350034 -0.09594583 0.02113521 -0.2341009 -0.09587389 0.02191448 -0.2341602 -0.09606915 0.02109605 -0.233864 -0.09598857 0.02164286 -0.233639 -0.09609919 0.02135866 -0.233425 -0.09620577 0.02106189 -0.234613 -0.0956313 0.02241915 -0.236957 -0.09457075 0.02401065 -0.236035 -0.09498035 0.02348679 -0.2420528 -0.09484118 0.02247726 -0.23857 -0.09387385 0.02471995 -0.2439507 -0.09450185 0.02264034 -0.2428349 -0.09442406 0.0227847 -0.2457963 -0.09409266 0.02271664 -0.2474147 -0.09316205 0.02297198 -0.2466023 -0.09362119 0.02286726 -0.2475911 -0.09623134 0.0218755 -0.2488862 -0.09503126 0.02196258 -0.2490888 -0.09427726 0.02210748 -0.2484017 -0.09482914 0.02208137 -0.249538 -0.09446382 0.02195721 -0.249495 -0.09506177 0.02185028 -0.2499998 -0.09266906 0.02246755 -0.2497416 -0.09539693 0.02176189 -0.2500014 -0.09462225 0.02181065 -0.2511205 -0.09169322 0.02253603 -0.250405 -0.092853 0.0222212 -0.2514669 -0.09187239 0.02223229 -0.2511042 -0.09242916 0.02211183 -0.2511582 -0.09360563 0.02163553 -0.2508189 -0.09343063 0.02183234 -0.2521677 -0.09155088 0.02201426 -0.2517225 -0.09315383 0.02148824 -0.2511262 -0.09291177 0.02188163 -0.2517386 -0.09258812 0.02169573 -0.2525018 -0.09040248 0.02278161 -0.2517762 -0.09205228 0.02194768 -0.2524101 -0.09174591 0.02171558 -0.253305 -0.0909999 0.02155029 -0.2536317 -0.09104508 0.02119082 -0.2535811 -0.09147673 0.02083975 -0.2532943 -0.09152275 0.02111339 -0.2548228 -0.09003442 0.02109235 -0.2544232 -0.09147727 0.01928466 -0.2542707 -0.09145575 0.0197435 -0.2539836 -0.09226107 0.01856356 -0.2540521 -0.09211105 0.0189104 -0.2536715 -0.0927779 0.01872885 -0.253499 -0.09310156 0.01882958 -0.257388 -0.08945858 0.01863545 -0.257348 -0.0893796 0.01900237 -0.256971 -0.08944892 0.01933509 -0.257283 -0.08930438 0.01936829 -0.2538059 -0.09240901 0.01931709 -0.253543 -0.093005 0.01895016 -0.25358 -0.09291148 0.01907545 -0.256608 -0.089015 0.02110916 -0.2567856 -0.08905643 0.02077645 -0.2540946 -0.09191429 0.01933026 -0.253608 -0.09282165 0.01920557 -0.257194 -0.08923339 0.01973229 -0.2563254 -0.08957171 0.0199508 -0.2557375 -0.08997142 0.01986849 -0.253627 -0.09273695 0.01934087 -0.257081 -0.0891695 0.020087 -0.2538489 -0.09207153 0.0197761 -0.253634 -0.09265887 0.01948118 -0.253628 -0.09258937 0.0196259 -0.256945 -0.0891112 0.0204364 -0.255956 -0.08892738 0.02203696 -0.2554032 -0.08908969 0.02222067 -0.255705 -0.08891397 0.02232199 -0.2561427 -0.08925276 0.02102857 -0.2553684 -0.0896095 0.02117961 -0.2557103 -0.08965915 0.02063691 -0.2540746 -0.09158086 0.01998031 -0.253606 -0.0925309 0.01977396 -0.2537107 -0.09199696 0.02015936 -0.253568 -0.09248626 0.01992326 -0.256408 -0.08897811 0.02142989 -0.2538609 -0.09154576 0.02039891 -0.253512 -0.09245777 0.02007126 -0.256189 -0.0889486 0.02174025 -0.254874 -0.0889213 0.02309906 -0.255164 -0.08891087 0.02285325 -0.25544 -0.08890849 0.02259445 -0.2551969 -0.08938449 0.02181601 -0.2548517 -0.08970701 0.02160644 -0.2543004 -0.08985626 0.02194452 -0.2534765 -0.09202164 0.0205062 -0.25344 -0.09244698 0.02021437 -0.253353 -0.09245395 0.02034956 -0.2542661 -0.0889604 0.0235514 -0.253951 -0.08899599 0.02376097 -0.254574 -0.08893907 0.02333229 -0.2545078 -0.08940565 0.0224688 -0.2531453 -0.09211492 0.02084296 -0.253255 -0.09247756 0.02047479 -0.253149 -0.09251558 0.02058905 -0.2528279 -0.09198158 0.02123481 -0.253038 -0.09256535 0.02069306 -0.252966 -0.08913117 0.02431446 -0.253301 -0.08907979 0.02414166 -0.2530887 -0.08929026 0.02390789 -0.253628 -0.08903479 0.02395707 -0.2537019 -0.089495 0.02303957 -0.2533879 -0.08998411 0.02259123 -0.2527102 -0.09247267 0.02106785 -0.252922 -0.09262496 0.02078747 -0.2526317 -0.09002965 0.02312856 -0.252685 -0.092767 0.02095067 -0.252804 -0.09269267 0.02087295 -0.251941 -0.08931845 0.02476996 -0.252286 -0.08925056 0.02462869 -0.252628 -0.08918839 0.02447658 -0.2528282 -0.0896427 0.02351403 -0.2523098 -0.09224998 0.02149158 -0.2522412 -0.09277296 0.02130132 -0.252515 -0.09288054 0.02104938 -0.2513911 -0.09009581 0.02390986 -0.2517135 -0.09039777 0.02332127 -0.2522734 -0.09305644 0.02116948 -0.251242 -0.08946818 0.02502447 -0.2510468 -0.08971202 0.02472323 -0.250889 -0.08955007 0.02513736 -0.251593 -0.08939105 0.02490186 -0.2520245 -0.09325134 0.02127462 -0.251476 -0.08983165 0.0242266 -0.2508118 -0.09067559 0.02356886 -0.2517835 -0.09345054 0.021362 -0.249822 -0.08981919 0.02542525 -0.250179 -0.08972549 0.02533787 -0.250535 -0.0896359 0.02524185 -0.2515488 -0.0936532 0.02143603 -0.2489103 -0.09029591 0.02520829 -0.249106 -0.09001606 0.02557718 -0.249428 -0.09099972 0.02397859 -0.249884 -0.091165 0.02358007 -0.2509517 -0.09419649 0.02158534 -0.2513133 -0.09386235 0.02150046 -0.248747 -0.0901196 0.02564138 -0.2504495 -0.09326118 0.02203667 -0.2494376 -0.09039551 0.02472126 -0.248027 -0.09033447 0.02574878 -0.2494243 -0.09068459 0.02434366 -0.2504671 -0.09466356 0.02167314 -0.249464 -0.08991599 0.02550506 -0.247667 -0.09044629 0.02579158 -0.2496903 -0.09331923 0.02227777 -0.249772 -0.09375083 0.02209424 -0.2474318 -0.09138554 0.02449846 -0.2475092 -0.09172952 0.02408498 -0.2500843 -0.09504693 0.02172553 -0.248387 -0.09022569 0.02569866 -0.246948 -0.0906763 0.02585756 -0.247308 -0.09056007 0.025828 -0.2494082 -0.09574437 0.0217902 -0.2473655 -0.09107673 0.02493244 -0.2467682 -0.09098672 0.02541077 -0.245871 -0.09103769 0.02590745 -0.246394 -0.09085941 0.025891 -0.2455856 -0.09172588 0.02491438 -0.2457041 -0.0920552 0.02443677 -0.2475696 -0.09362566 0.02267849 -0.2484159 -0.09681075 0.02182447 -0.244798 -0.09141516 0.02590125 -0.245335 -0.09122371 0.0259118 -0.247539 -0.09487968 0.02217537 -0.247725 -0.09540081 0.02201843 -0.2467897 -0.0941146 0.02257108 -0.2469862 -0.09462815 0.02232217 -0.244679 -0.09173387 0.02537661 -0.243731 -0.09180599 0.02584058 -0.2442681 -0.09160703 0.02587842 -0.247056 -0.0959869 0.02192217 -0.2468405 -0.09543484 0.02206182 -0.2431923 -0.0920087 0.02578973 -0.2442663 -0.09264677 0.02425789 -0.2460272 -0.09461414 0.0224201 -0.2462594 -0.09515875 0.02217763 -0.247444 -0.09723967 0.02179259 -0.247111 -0.09669387 0.02181226 -0.242673 -0.09220749 0.02572625 -0.2438229 -0.09241157 0.02473777 -0.2461555 -0.09600239 0.02191293 -0.246562 -0.09643298 0.02182865 -0.2467707 -0.0970723 0.02175533 -0.2414452 -0.09268909 0.02552497 -0.2421493 -0.0924108 0.02564996 -0.2426158 -0.09252732 0.02512764 -0.2452826 -0.09512174 0.02222812 -0.2455493 -0.09569931 0.02199482 -0.2450164 -0.09456884 0.02252256 -0.2460343 -0.09690213 0.02171248 -0.245649 -0.09643346 0.02177816 -0.2418802 -0.09320765 0.0243436 -0.244253 -0.09505081 0.02228593 -0.2445577 -0.09563517 0.02199649 -0.2450309 -0.09610658 0.02183365 -0.2453513 -0.09675461 0.02167546 -0.2407612 -0.09296411 0.02537804 -0.2435242 -0.09552782 0.02201187 -0.2431778 -0.09495115 0.02236562 -0.2444233 -0.09657293 0.0216248 -0.239571 -0.09345287 0.02505809 -0.240647 -0.09332507 0.02467888 -0.244037 -0.0960161 0.0217995 -0.2390826 -0.09365683 0.02490234 -0.2424153 -0.09540927 0.02204018 -0.2435995 -0.0964269 0.02157783 -0.2400746 -0.09324401 0.02520412 -0.243 -0.09588021 0.02178215 -0.238241 -0.09401398 0.02459329 -0.2428357 -0.09630388 0.02153551 -0.24168 -0.09586763 0.02166616 -0.241721 -0.0961461 0.02147847 -0.2375929 -0.09429347 0.02431768 -0.2406153 -0.09563612 0.02175194 -0.2410068 -0.09605479 0.02143865 -0.236645 -0.0947085 0.02384519 -0.2383444 -0.09473621 0.02298957 -0.2400695 -0.09596174 0.02139019 -0.239233 -0.09557586 0.02171427 -0.239301 -0.0959047 0.02135026 -0.2372045 -0.09524661 0.02228975 -0.238801 -0.09586268 0.02132427 -0.235737 -0.09511458 0.02329415 -0.2375347 -0.0958088 0.02125936 -0.2365694 -0.09582352 0.02121168 -0.234353 -0.0957539 0.02217245 -0.09600055 -0.1133139 0.01423484 -0.09901732 -0.1152346 0.01424694 -0.1205274 -0.1099962 0.0155372 -0.09406751 -0.112084 0.01422178 -0.112818 -0.1102 0.01520937 -0.1218634 -0.1112825 0.01555055 -0.1086354 -0.1147463 0.01474839 -0.1232299 -0.1129929 0.01555114 -0.1167775 -0.1167975 0.01504987 -0.1037095 -0.1182242 0.01427358 -0.102693 -0.110712 0.01471585 -0.107757 -0.110469 0.01496279 -0.0976265 -0.110931 0.01446884 -0.09255707 -0.111124 0.01422154 -0.1245694 -0.1147135 0.01555007 -0.233425 -0.09620577 0.02106189 -0.23682 -0.09581679 0.02122408 -0.237313 -0.09580999 0.02124869 -0.1446304 -0.1126757 0.01663821 -0.1652052 -0.1103626 0.01772654 -0.134393 -0.116238 0.01600563 -0.1454639 -0.1146801 0.01663708 -0.1655362 -0.1126415 0.01772576 -0.2355834 -0.09956496 0.02123844 -0.2453156 -0.09674698 0.02167266 -0.2462572 -0.0969519 0.02172535 -0.1863251 -0.1064847 0.01881307 -0.2429049 -0.09631532 0.02154076 -0.2400302 -0.09595829 0.02138805 -0.240754 -0.09602838 0.02142596 -0.241234 -0.09608286 0.02145135 -0.2189254 -0.1002177 0.02040624 -0.237807 -0.09581536 0.02127349 -0.238303 -0.095833 0.02129876 -0.238801 -0.09586268 0.02132427 -0.23633 -0.0958358 0.02119988 -0.235841 -0.09586697 0.02117609 -0.233905 -0.09611356 0.02108395 -0.234386 -0.09603369 0.02110648 -0.234869 -0.09596586 0.02112936 -0.235354 -0.09591031 0.02115249 -0.239301 -0.0959047 0.02135026 -0.241714 -0.09614425 0.02147686 -0.243628 -0.09643197 0.02157998 -0.2443643 -0.09656149 0.02162015 -0.2034118 -0.1010648 0.01961863 -0.2081953 -0.1034581 0.01990306 -0.208434 -0.100316 0.01985305 -0.2472106 -0.09717994 0.02177923 -0.2479169 -0.09736335 0.02181965 -0.2075177 -0.1063028 0.01990246 -0.1861033 -0.1090441 0.01880979 -0.1577889 -0.1160961 0.01727235 -0.1693484 -0.1147457 0.01791352 -0.187044 -0.1167935 0.01888889 -0.1742849 -0.1180082 0.01817274 -0.1858632 -0.1141669 0.0188139 -0.2054678 -0.114838 0.01989948 -0.219273 -0.1163278 0.0206989 -0.2153055 -0.1179397 0.02049553 -0.2252655 -0.1127131 0.02095991 -0.2379474 -0.1179193 0.02179431 -0.117876 -0.109906 0.01545578 -0.122931 -0.109587 0.01570188 -0.1362557 -0.1101534 0.0162788 -0.1187909 -0.118168 0.01509428 -0.127984 -0.109243 0.01594787 -0.133033 -0.108874 0.01619356 -0.1377699 -0.108586 0.01639246 -0.1632456 -0.1062752 0.01765966 -0.1648277 -0.1080882 0.01772493 -0.1470443 -0.1096915 0.01681876 -0.13808 -0.108479 0.01643908 -0.143124 -0.10806 0.01668435 -0.1370958 -0.118107 0.01610004 -0.1482209 -0.1076087 0.01692527 -0.153203 -0.107145 0.0171743 -0.173327 -0.105014 0.01815146 -0.1683 -0.105584 0.0179075 -0.1582379 -0.1066499 0.01741886 -0.1632699 -0.10613 0.01766335 -0.18839 -0.103151 0.01888209 -0.1910445 -0.1042704 0.01904278 -0.183372 -0.103797 0.01863878 -0.1551076 -0.1180544 0.01709944 -0.178351 -0.104418 0.0183953 -0.218439 -0.09874737 0.02033728 -0.223437 -0.0979253 0.02057898 -0.198418 -0.101784 0.01936799 -0.1860016 -0.1116098 0.01881277 -0.193405 -0.1024799 0.01912516 -0.213438 -0.09954416 0.02009528 -0.2067902 -0.1091428 0.01989907 -0.2061937 -0.1119863 0.01990276 -0.194824 -0.1179695 0.01933014 -0.228433 -0.09707808 0.02082055 -0.2457864 -0.1017571 0.02181494 -0.229568 -0.1039158 0.02101331 -0.2243801 -0.1080838 0.02082091 -0.242276 -0.1089957 0.02180737 -0.2389482 -0.1158564 0.02179908 -0.09219276 -0.1111347 0.01419872 -0.1025797 -0.1200231 0.01309084 -0.10244 -0.1202475 0.01266384 -0.09525656 -0.115368 0.01308149 -0.08839988 -0.111245 0.01280188 -0.1023383 -0.1204137 0.01219689 -0.0881173 -0.111253 0.01251316 -0.08798575 -0.111256 0.01234757 -0.08787316 -0.111259 0.01217907 -0.08769696 -0.111264 0.01181447 -0.08777809 -0.111262 0.01200395 -0.08763891 -0.1112653 0.01162105 -0.1022747 -0.1205195 0.01164817 -0.08825457 -0.111249 0.01266276 -0.08758926 -0.111267 0.01121735 -0.08760118 -0.111267 0.01141798 -0.09537708 -0.116186 0.01124799 -0.102266 -0.120536 0.01128286 -0.0885545 -0.111241 0.01293319 -0.08878773 -0.1112341 0.01310747 -0.09544378 -0.115069 0.01346367 -0.1027715 -0.119717 0.01349008 -0.08913791 -0.1112248 0.01332747 -0.08953374 -0.1112137 0.01353156 -0.1029945 -0.1193597 0.01381456 -0.09566175 -0.114721 0.01377725 -0.08985394 -0.1112045 0.01366901 -0.09032034 -0.1111911 0.01383656 -0.09088504 -0.1111742 0.0139926 -0.1032942 -0.1188824 0.01410055 -0.0915085 -0.1111566 0.01411962 -0.09614688 -0.113951 0.01416319 -0.1037093 -0.118224 0.01427233 -0.09738326 -0.1141936 0.01423889 -0.09255713 -0.111124 0.01422148 -0.102266 -0.120536 0 -0.0875898 -0.1112669 0 -0.09537708 -0.116186 0.01124799 -0.102266 -0.120536 0.01128286 -0.08758926 -0.111267 0.01121735 0.07237201 -0.1001098 0 0.0814926 -0.1006924 0 -0.1849542 -0.09352004 0 -0.202226 -0.09699088 0 -0.20406 -0.09286379 0 -0.1969341 -0.09311228 0 -0.1705246 -0.09399414 0 -0.1584938 -0.09437519 0 -0.1489692 -0.09466826 0 -0.1369915 -0.09502613 0 -0.172069 -0.113762 0 -0.171685 -0.113755 0 -0.171494 -0.11377 0 -0.1225 -0.09544217 0 -0.1080549 -0.09583878 0 -0.17226 -0.113786 0 -0.172448 -0.113827 0 -0.09588837 -0.09615868 0 -0.08758968 -0.111267 0 -0.08613473 -0.09640622 0 -0.07657974 -0.09664082 0 -0.06434482 -0.09693044 0 -0.05939066 -0.09705924 0 -0.04730701 -0.09741741 0 -0.07873457 -0.111357 0 -0.02814263 -0.09800958 0 -0.06988096 -0.111422 0 -0.03772026 -0.09770989 0 -0.01848053 -0.09831959 0 -0.05217796 -0.111472 0 -0.06102877 -0.11146 0 -0.008925616 -0.0986337 0 -0.04332846 -0.111459 0 -0.02563369 -0.111355 0 -0.03448039 -0.11142 0 7.39184e-4 -0.09895896 0 -0.01678836 -0.111264 0 0.00802344 -0.0992096 0 0.01285576 -0.09933006 0 8.98115e-4 -0.111004 0 -0.007944405 -0.111147 0 0.01857906 -0.110641 0 0.02004438 -0.09947603 0 0.009739279 -0.110835 0 0.0274176 -0.11042 0 0.02734285 -0.09960836 0 0.03625458 -0.110174 0 0.04509025 -0.109902 0 0.03466588 -0.0997281 0 0.05392456 -0.109604 0 0.04429882 -0.09986239 0 0.06275761 -0.10928 0 0.05374825 -0.09996956 0 0.07158905 -0.10893 0 0.08520179 -0.108376 0 0.0804193 -0.108554 0 0.08137071 -0.100581 0 0.08126628 -0.100499 0 0.06284737 -0.1000499 0 0.08092397 -0.100297 0 0.08080208 -0.1002449 0 0.081043 -0.1003569 0 0.08115679 -0.100425 0 0.08041936 -0.10014 0 0.08054977 -0.100167 0 0.08067739 -0.100202 0 0.08860456 -0.10851 0 -0.102266 -0.120536 0 -0.103868 -0.121 0 -0.172086 -0.120351 0 -0.103308 -0.120947 0 -0.103586 -0.1209869 0 -0.172228 -0.119708 0 -0.103034 -0.120882 0 -0.102767 -0.120791 0 -0.102511 -0.120676 0 -0.171961 -0.121 0 -0.217117 -0.120263 0 -0.2397119 -0.120542 0 -0.239942 -0.120382 0 -0.244213 -0.112293 0 -0.213638 -0.112079 0 -0.214046 -0.112702 0 -0.216552 -0.118101 0 -0.240819 -0.119307 0 -0.216318 -0.117397 0 -0.172388 -0.1190699 0 -0.172567 -0.118439 0 -0.172763 -0.117812 0 -0.172977 -0.117192 0 -0.215776 -0.116 0 -0.216058 -0.116693 0 -0.215474 -0.11532 0 -0.173209 -0.116576 0 -0.1734589 -0.115967 0 -0.16793 -0.115586 0 -0.214806 -0.113993 0 -0.2151499 -0.11465 0 -0.2144359 -0.11334 0 -0.173681 -0.115177 0 -0.173623 -0.114994 0 -0.173553 -0.1148149 0 -0.1734679 -0.114643 0 -0.173117 -0.114189 0 -0.172968 -0.114069 0 -0.173368 -0.114479 0 -0.173251 -0.114327 0 -0.171878 -0.113752 0 -0.17263 -0.113888 0 -0.1728039 -0.113968 0 -0.212764 -0.110877 0 -0.2132109 -0.1114709 0 -0.199023 -0.0998575 0 -0.2026799 -0.09788185 0 -0.199116 -0.0996977 0 -0.2118059 -0.109726 0 -0.212294 -0.110293 0 -0.207319 -0.10583 0 -0.207931 -0.10625 0 -0.1674759 -0.114695 0 -0.173727 -0.115363 0 -0.1989409 -0.100022 0 -0.198868 -0.100192 0 -0.1987349 -0.100727 0 -0.201983 -0.103214 0 -0.198763 -0.100545 0 -0.198808 -0.1003659 0 -0.199034 -0.101765 0 -0.2012709 -0.102986 0 -0.198729 -0.100911 0 -0.1987439 -0.101095 0 -0.200046 -0.1025519 0 -0.200294 -0.1026722 0 -0.199725 -0.102371 0 -0.199571 -0.102269 0 -0.20055 -0.10278 0 -0.199883 -0.102465 0 -0.199283 -0.102038 0 -0.199423 -0.102158 0 -0.199153 -0.101907 0 -0.1988469 -0.1014479 0 -0.1989319 -0.101613 0 -0.1987839 -0.101275 0 -0.2026849 -0.103464 0 -0.2033759 -0.103736 0 -0.204058 -0.10403 0 -0.205392 -0.104684 0 -0.20473 -0.104346 0 -0.206687 -0.105426 0 -0.206044 -0.105044 0 -0.209116 -0.107151 0 -0.20853 -0.106691 0 -0.210247 -0.108132 0 -0.209688 -0.107632 0 -0.2113029 -0.109177 0 -0.210783 -0.108646 0 -0.216951 -0.119535 0 -0.216763 -0.118814 0 -0.21726 -0.121 0 -0.238119 -0.121 0 -0.2386749 -0.120948 0 -0.238399 -0.1209869 0 -0.238947 -0.120883 0 -0.239213 -0.1207939 0 -0.239468 -0.120679 0 -0.2401559 -0.120202 0 -0.240353 -0.120003 0 -0.24053 -0.119786 0 -0.240685 -0.119553 0 0.150575 -0.110957 0 0.111022 -0.109395 3.87913e-4 0.111037 -0.109396 0 0.08520174 -0.1083775 0.02799999 0.150575 -0.110957 0.02799999 0.110055 -0.1093569 0.003273069 0.110251 -0.109365 0.002941548 0.08520179 -0.1083758 0.01058423 0.09809458 -0.108885 0.00790435 0.09847676 -0.1089 0.007942259 0.103813 -0.109111 0.007476866 0.104183 -0.109125 0.007371127 0.11092 -0.109391 0.001147806 0.110983 -0.109394 7.70517e-4 0.11072 -0.109383 0.001886427 0.110832 -0.109388 0.001519799 0.110427 -0.109372 0.002600848 0.110584 -0.109378 0.00224781 0.106998 -0.109236 0.006147801 0.107326 -0.109249 0.005945742 0.109612 -0.10934 0.00390315 0.10984 -0.109349 0.003594875 0.109107 -0.10932 0.004485845 0.109368 -0.1093299 0.00420016 0.108555 -0.109298 0.005020141 0.108837 -0.109309 0.004759073 0.107957 -0.109274 0.005506515 0.108261 -0.109286 0.005269229 0.107647 -0.109262 0.005732059 0.106325 -0.10921 0.006518661 0.106665 -0.109223 0.006338894 0.105628 -0.109182 0.006845116 0.105978 -0.109196 0.006687045 0.1049129 -0.109154 0.007128775 0.105273 -0.109168 0.006992399 0.104549 -0.10914 0.007255017 0.10344 -0.109096 0.007572531 0.102689 -0.109066 0.007734715 0.103066 -0.109081 0.0076586 0.10193 -0.109036 0.007857799 0.10231 -0.109051 0.007800877 0.101548 -0.109021 0.007905006 0.100782 -0.108991 0.00797075 0.1011649 -0.109006 0.007942557 0.100013 -0.108961 0.007998883 0.100398 -0.108976 0.007989525 0.09924459 -0.10893 0.007989346 0.09962868 -0.108945 0.007998764 0.09886056 -0.108915 0.007970511 0.09733235 -0.108855 0.007799923 0.09771305 -0.10887 0.007856905 0.0965774 -0.108825 0.007656991 0.09695398 -0.10884 0.007733285 0.09582996 -0.108795 0.007475316 0.09620225 -0.10881 0.00757116 0.0950939 -0.108766 0.007253527 0.09546065 -0.108781 0.007369399 0.09473025 -0.108752 0.007127523 0.09401595 -0.1087239 0.006843864 0.09437137 -0.108738 0.006990849 0.09331947 -0.108696 0.006517708 0.09366446 -0.10871 0.006686449 0.09264487 -0.1086699 0.006147623 0.09297966 -0.108683 0.006338119 0.0905351 -0.108586 0.004487156 0.09080767 -0.108597 0.004759967 0.09199869 -0.108644 0.005731821 0.09231799 -0.108657 0.005945563 0.09138286 -0.10862 0.005269885 0.0916863 -0.108632 0.005506753 0.09109055 -0.108608 0.005020856 0.09003371 -0.1085669 0.003905355 0.0902782 -0.1085759 0.004202246 0.08958947 -0.1085489 0.003276884 0.08980178 -0.108557 0.003596544 0.08921575 -0.108534 0.002603828 0.08939439 -0.108541 0.002946019 0.08905839 -0.108528 0.002252638 0.08520179 -0.108376 0 0.08881086 -0.108518 0.001524806 0.08892428 -0.108523 0.001893341 0.0886572 -0.108512 7.71391e-4 0.0887202 -0.108515 0.001148998 0.08860456 -0.10851 0 0.08861869 -0.108511 3.88388e-4 0.09820187 -0.09655344 0.05189365 0.09820187 -0.0965535 0.02799999 0.09673655 -0.09788602 0.05194234 0.09628742 -0.09829449 0.05194962 0.09579509 -0.09874218 0.05194216 0.0954945 -0.09901559 0.05192929 0.09504359 -0.09942561 0.0518977 0.09459519 -0.09983336 0.05184936 0.09429579 -0.100106 0.05180919 0.09399688 -0.100378 0.05176216 0.09369879 -0.1006489 0.05170828 0.09340125 -0.100919 0.05164748 0.09310466 -0.101189 0.05157947 0.0928092 -0.101458 0.05150389 0.09251457 -0.101726 0.05142116 0.09222137 -0.101992 0.05133056 0.09192949 -0.102258 0.05123239 0.09163886 -0.102522 0.05112659 0.09135025 -0.102784 0.05101257 0.09106326 -0.103045 0.05089068 0.09077817 -0.103305 0.05076056 0.08939015 -0.104567 0.0499798 0.08912217 -0.104811 0.04979574 0.08993709 -0.104069 0.05031925 0.09021478 -0.103817 0.05047529 0.08834135 -0.105521 0.04918509 0.08885759 -0.105051 0.04960238 0.0852015 -0.1083759 0.04097908 0.08760547 -0.10619 0.04847955 0.08809036 -0.105749 0.04896068 0.0869286 -0.106805 0.04767376 0.08671849 -0.1069959 0.04738175 0.08519589 -0.108381 0.04141718 0.08737188 -0.106402 0.04822289 0.0871464 -0.106607 0.0479542 0.08518821 -0.108388 0.0422309 0.08518707 -0.108389 0.04182428 0.08615028 -0.107513 0.04643529 0.0865193 -0.107178 0.04707795 0.0863294 -0.10735 0.04676246 0.08583146 -0.107803 0.04574579 0.08598488 -0.107664 0.04609638 0.08519446 -0.108382 0.04263907 0.08530259 -0.1082839 0.04385036 0.08524876 -0.108333 0.04344844 0.085693 -0.107929 0.04538488 0.08557045 -0.10804 0.0450142 0.08521276 -0.108366 0.04304575 0.08537375 -0.108219 0.04424548 0.08546257 -0.108139 0.04463285 0.08784478 -0.105972 0.0487256 0.08859688 -0.105288 0.04939919 0.08966225 -0.104319 0.05015408 0.09049546 -0.1035619 0.0506221 0.08520168 -0.108376 0.02799999 0.14326 -0.09778398 0.04983454 0.138263 -0.09764748 0.05016368 0.13963 -0.0976848 0.02799999 0.208173 -0.09955668 3.86132e-4 0.2082099 -0.09955769 7.68214e-4 0.13963 -0.0976848 0 0.133264 -0.09751099 0.05046778 0.2081609 -0.09955638 0 0.208271 -0.09955936 0.001146197 0.2351509 -0.100293 0 0.2351509 -0.100293 0.04039996 0.2165859 -0.0997864 0.005486488 0.208357 -0.09956169 0.001520216 0.2084659 -0.09956467 0.001890122 0.208599 -0.0995683 0.002250313 0.208754 -0.09957259 0.002601802 0.208932 -0.09957736 0.002943873 0.209131 -0.09958291 0.003271698 0.209351 -0.09958887 0.003587841 0.209591 -0.09959536 0.003888487 0.2098489 -0.09960246 0.004172742 0.210126 -0.09960997 0.004441499 0.210418 -0.09961795 0.004689931 0.210726 -0.09962636 0.004920184 0.211049 -0.09963518 0.00513035 0.211383 -0.0996443 0.005318641 0.211731 -0.09965378 0.005486369 0.212086 -0.09966349 0.005630195 0.212451 -0.0996735 0.00575143 0.212823 -0.0996837 0.005849361 0.2132 -0.09969395 0.005922675 0.2139649 -0.09971487 0.005996823 0.227837 -0.100094 0.04039996 0.222881 -0.09995836 0.04115569 0.214349 -0.09972536 0.005996823 0.214734 -0.09973585 0.005972266 0.2151139 -0.09974616 0.005923211 0.215492 -0.09975659 0.005849659 0.213582 -0.09970438 0.005972087 0.215864 -0.09976667 0.005752265 0.216228 -0.09977668 0.005631268 0.216931 -0.09979587 0.005320191 0.217267 -0.09980499 0.005131363 0.217589 -0.09981375 0.004921436 0.2178969 -0.09982216 0.004691958 0.218191 -0.09983026 0.004441857 0.218466 -0.09983777 0.004175007 0.218725 -0.09984475 0.003890395 0.2189649 -0.09985136 0.003589034 0.219184 -0.09985738 0.003274559 0.219384 -0.09986287 0.002944886 0.2195619 -0.0998677 0.002604305 0.219717 -0.09987187 0.002253055 0.219851 -0.09987556 0.001890897 0.21996 -0.0998786 0.001523435 0.220045 -0.09988087 0.001147985 0.220107 -0.0998826 7.68214e-4 0.220144 -0.09988355 3.86132e-4 0.220156 -0.09988385 0 0.217923 -0.09982287 0.04188627 0.212962 -0.09968745 0.04259186 0.207999 -0.09955185 0.04327225 0.1980659 -0.09928065 0.04455786 0.203034 -0.09941625 0.04392755 0.188123 -0.09900909 0.04574304 0.193095 -0.09914487 0.04516297 0.17817 -0.09873729 0.04682797 0.183148 -0.09887325 0.04629808 0.168208 -0.09846526 0.04781246 0.1731899 -0.09860128 0.04733276 0.158236 -0.09819298 0.04869657 0.163223 -0.09832906 0.04826706 0.148254 -0.09792035 0.04948025 0.153246 -0.09805667 0.04910099 0.128262 -0.09737437 0.05074679 0.123258 -0.09723776 0.05100059 0.113243 -0.09696418 0.05143308 0.09820187 -0.0965535 0.02799999 0.118252 -0.09710097 0.05122935 0.103218 -0.09669047 0.0517652 0.108232 -0.09682738 0.05161166 0.09820187 -0.0965535 0.05189359 0.23726 -0.0992124 0.04039996 0.2326599 -0.09964966 0.04039984 0.2351509 -0.100293 0.04039996 0.227837 -0.100094 0.04039996 0.235526 -0.100101 0.03922218 0.235925 -0.0998966 0.03952729 0.2351509 -0.100293 0.04039996 0.2351509 -0.100293 0.03890997 0.236347 -0.09968036 0.03982526 0.236792 -0.09945237 0.04011619 0.23726 -0.0992124 0.04039996 0.236625 -0.103241 0 0.236494 -0.102979 7.37274e-4 0.2351509 -0.100293 0 0.236373 -0.102739 0.001482307 0.236264 -0.102519 0.002235054 0.236165 -0.102321 0.00299561 0.2360759 -0.102144 0.003763914 0.235998 -0.101989 0.004540026 0.235931 -0.101854 0.005323827 0.235875 -0.101741 0.006115436 0.235828 -0.101649 0.006911456 0.235792 -0.101577 0.007705628 0.235767 -0.101526 0.008503317 0.2357349 -0.101461 0.0339663 0.2357209 -0.101433 0.03448069 0.2357468 -0.1014859 0.03277635 0.2357469 -0.101486 0.01010894 0.235752 -0.101496 0.009304404 0.23535 -0.100692 0.03797465 0.235255 -0.100503 0.03844594 0.235745 -0.101482 0.03345137 0.235674 -0.1013399 0.03550505 0.235703 -0.101397 0.03499466 0.23563 -0.101251 0.03600966 0.235575 -0.101142 0.03651076 0.2355099 -0.101011 0.0370084 0.235435 -0.100861 0.03749608 0.2351509 -0.100293 0.03890997 0.339667 -0.09935665 0.01666235 0.312645 -0.09852325 0.0210914 0.31303 -0.09994268 0.0176087 0.247318 -0.100877 0.01507484 0.258437 -0.100415 0.01631665 0.249271 -0.100774 0.01582217 0.2453719 -0.10098 0.01430457 0.251231 -0.100669 0.01654648 0.235752 -0.101496 0.009304404 0.255172 -0.100459 0.01792627 0.257153 -0.100353 0.01858168 0.253198 -0.100565 0.01724785 0.2434329 -0.101083 0.01351135 0.259141 -0.100247 0.01921415 0.237658 -0.101386 0.01099395 0.235747 -0.101486 0.01010894 0.241501 -0.101184 0.01269519 0.239576 -0.101286 0.01185607 0.261136 -0.100139 0.01982367 0.263138 -0.100032 0.02041029 0.265147 -0.09992319 0.02097386 0.267163 -0.09981417 0.02151459 0.285215 -0.09902226 0.02218449 0.269186 -0.09970468 0.0220322 0.271216 -0.09959447 0.02252697 0.275297 -0.09937238 0.02344745 0.273253 -0.09948378 0.02299869 0.3396029 -0.09840446 0.01831281 0.312288 -0.09766459 0.02464479 0.289668 -0.09858459 0.0261209 0.287618 -0.09869748 0.02577686 0.3395568 -0.09772938 0.0196979 0.339528 -0.09729397 0.02072465 0.293775 -0.09835785 0.02675855 0.295832 -0.09824407 0.02705228 0.297891 -0.09812998 0.0273292 0.299952 -0.09801548 0.02758949 0.304082 -0.09778577 0.0280596 0.302016 -0.0979008 0.02783286 0.339501 -0.09690028 0.02176982 0.30615 -0.09767049 0.02826958 0.3394722 -0.09647715 0.02311688 0.315661 -0.09712296 0.02803349 0.310906 -0.0973984 0.02816408 0.320415 -0.09684425 0.02787768 0.339453 -0.09618878 0.02422297 0.339442 -0.09603297 0.02491849 0.325168 -0.09656226 0.02769678 0.3394293 -0.09583985 0.02595359 0.329919 -0.09627705 0.02749079 0.33467 -0.09598851 0.02725976 0.29172 -0.0984714 0.02644807 0.33942 -0.09569668 0.02700358 0.2853547 -0.09882187 0.02537781 0.281472 -0.0990349 0.02465617 0.279407 -0.09914797 0.02427625 0.277348 -0.0992605 0.02387338 0.3397119 -0.100027 0.01565665 0.235792 -0.101577 0.007705628 0.235767 -0.101526 0.008503317 0.3397743 -0.1009439 0.0144248 0.339825 -0.101698 0.01352566 0.235828 -0.101649 0.006911456 0.313431 -0.101912 0.01432716 0.3398786 -0.102481 0.01266729 0.3399548 -0.103613 0.01156127 0.235875 -0.101741 0.006115436 0.235931 -0.101854 0.005323827 0.259219 -0.100776 0.01385265 0.287011 -0.101992 0.01308959 0.313834 -0.10438 0.01137244 0.340016 -0.104519 0.01077336 0.3400774 -0.105425 0.0100485 0.3401848 -0.1070169 0.008935749 0.26001 -0.101415 0.01140844 0.2360759 -0.102144 0.003763914 0.236165 -0.102321 0.00299561 0.340278 -0.1084 0.008117914 0.314225 -0.107259 0.008849561 0.3403415 -0.109335 0.007621765 0.340441 -0.1108139 0.00694704 0.3405831 -0.1129138 0.006169676 0.31459 -0.110435 0.006831228 0.288162 -0.105943 0.007890045 0.340759 -0.115507 0.005501985 0.3406856 -0.1144284 0.005744993 0.289139 -0.111005 0.003995299 0.295674 -0.114595 0.003134787 0.299139 -0.115052 0.003420233 0.31492 -0.11378 0.005351305 0.313046 -0.11687 0.00432527 0.3184686 -0.117573 0.004577577 0.3408306 -0.1165751 0.005302786 0.3251748 -0.1184355 0.004806637 0.3350351 -0.1196941 0.004983365 0.340999 -0.119059 0.005034685 0.330539 -0.119121 0.004924356 0.3410929 -0.1204599 0.005000412 0.3409269 -0.1179999 0.005115211 0.309562 -0.116417 0.004134476 0.250538 -0.105874 0 0.252509 -0.106341 0 0.262996 -0.106581 0.002660691 0.306083 -0.115963 0.003920078 0.292214 -0.114136 0.002825736 0.288759 -0.113677 0.002493023 0.254476 -0.106831 0 0.263636 -0.108407 9.08739e-4 0.285309 -0.1132169 0.002136647 0.281864 -0.112756 0.001756608 0.258398 -0.1078799 0 0.260353 -0.108439 0 0.262304 -0.1090199 0 0.278424 -0.112294 0.001352965 0.26425 -0.109624 0 0.274988 -0.111831 9.25647e-4 0.266193 -0.110251 0 0.271557 -0.111366 4.74655e-4 0.268131 -0.1109009 0 0.302608 -0.115508 0.003681957 0.246583 -0.105007 0 0.262302 -0.104937 0.004616677 0.340515 -0.111906 0.006519079 0.288678 -0.108371 0.005758523 0.287602 -0.103795 0.01035267 0.261565 -0.103511 0.006749987 0.236373 -0.102739 0.001482307 0.260797 -0.10233 0.009026885 0.236264 -0.102519 0.002235054 0.236494 -0.102979 7.37274e-4 0.24062 -0.103879 0 0.238624 -0.103549 0 0.235998 -0.101989 0.004540026 0.286406 -0.100582 0.01602858 0.285802 -0.09959036 0.01908797 0.256439 -0.107344 0 0.2445999 -0.104609 0 0.236625 -0.103241 0 0.248562 -0.105429 0 0.242612 -0.104232 0 0.3410178 -0.1193391 0.005017161 0.3496064 -0.1161592 0.005277872 0.3409274 -0.1180079 0.005114436 0.3620296 -0.1078953 0.007584631 0.3489 -0.108627 0.007685065 0.34916 -0.112357 0.006161689 0.382697 -0.100241 0.01180708 0.39126 -0.099761 0.01162368 0.391052 -0.0971632 0.01442605 0.3624448 -0.1115473 0.00611937 0.43433 -0.100006 0.008671939 0.425765 -0.100593 0.008782744 0.4305704 -0.1034291 0.007075309 0.348656 -0.105123 0.009839296 0.357226 -0.104687 0.009716629 0.357004 -0.101584 0.01236975 0.3795896 -0.1104441 0.006063938 0.39629 -0.1058008 0.007324516 0.3791246 -0.1068844 0.00745356 0.365569 -0.101152 0.01218014 0.365796 -0.104234 0.009595274 0.399823 -0.09926545 0.0114423 0.400068 -0.102254 0.009123027 0.408385 -0.09875416 0.01126295 0.374133 -0.100704 0.01199257 0.374365 -0.1037639 0.009475231 0.391501 -0.102774 0.009239137 0.382933 -0.103277 0.009356498 0.44318 -0.10249 0.006984472 0.442894 -0.09940266 0.008562505 0.408635 -0.101717 0.009008288 0.4133716 -0.104654 0.00719887 0.4172 -0.101163 0.00889486 0.3967261 -0.1092712 0.006009638 0.408167 -0.09617209 0.01391929 0.4143758 -0.1114498 0.005231559 0.4138454 -0.10803 0.005956232 0.44348 -0.105718 0.005865216 0.4310199 -0.1067137 0.00590378 0.435507 -0.112996 0.004999995 0.4433939 -0.1090018 0.005214095 0.4522005 -0.1066167 0.005468308 0.452342 -0.1081061 0.005217075 0.4519239 -0.1037046 0.006224155 0.4525179 -0.109962 0.005033373 0.3398602 -0.1022121 0.01294362 0.348439 -0.102001 0.0125615 0.444082 -0.11221 0.004999995 0.452655 -0.111406 0.004999995 0.3401401 -0.1063579 0.009372413 0.3399556 -0.1036257 0.01155 0.3402529 -0.1080243 0.008326709 0.3403663 -0.1097024 0.00743854 0.3404899 -0.1115346 0.006655871 0.3405842 -0.1129305 0.006164491 0.3407107 -0.1147958 0.005653858 0.349684 -0.119871 0.004999995 0.341093 -0.12046 0.004999995 0.3408312 -0.1165836 0.005301475 0.3400331 -0.1047757 0.01055639 0.348256 -0.09938627 0.01574027 0.3397743 -0.1009446 0.01442372 0.3397117 -0.1000241 0.01566064 0.3396525 -0.09914368 0.01700758 0.433838 -0.09457629 0.0131793 0.425281 -0.09512275 0.01342326 0.425508 -0.0976839 0.01091057 0.348115 -0.09736377 0.01923125 0.39961 -0.09667485 0.01417136 0.3396027 -0.09840267 0.01831626 0.4514455 -0.09866219 0.008524298 0.4513198 -0.09734153 0.009371519 0.3395568 -0.09772956 0.01969754 0.3395187 -0.09715563 0.02107304 0.348018 -0.09596508 0.02287727 0.442394 -0.0940153 0.01293796 0.442629 -0.0965501 0.01056635 0.4510005 -0.09397488 0.01214361 0.416724 -0.09565466 0.01366996 0.416947 -0.0982269 0.01108574 0.3394854 -0.09667593 0.02244943 0.433375 -0.0894472 0.02188259 0.424942 -0.09128648 0.01923877 0.433488 -0.09071236 0.01884806 0.356507 -0.09464019 0.02605569 0.347963 -0.09517288 0.02652865 0.3394579 -0.09625959 0.02392649 0.3394373 -0.09596431 0.02524411 0.3394197 -0.09568953 0.02700263 0.416396 -0.0918498 0.01963216 0.424836 -0.09005957 0.02233874 0.4508756 -0.09266483 0.01354348 0.442194 -0.09186148 0.01559919 0.450603 -0.0897938 0.01758474 0.442033 -0.0901274 0.01846015 0.433643 -0.09242576 0.01591449 0.4506959 -0.09077107 0.01601326 0.4505177 -0.08889377 0.019324 0.441914 -0.08882588 0.02142816 0.450451 -0.08818864 0.02097284 0.36505 -0.09409856 0.02558457 0.356566 -0.09548866 0.02246206 0.365114 -0.09500139 0.02204966 0.373662 -0.09450328 0.02163988 0.382134 -0.0929889 0.02464789 0.373592 -0.09354817 0.02511525 0.356816 -0.09897077 0.01547205 0.356669 -0.0969277 0.01888626 0.365223 -0.09647876 0.01854419 0.365376 -0.09854066 0.01520657 0.358272 -0.119264 0.004999995 0.371555 -0.1146638 0.00526303 0.390675 -0.09242075 0.02418226 0.382209 -0.09399425 0.0212329 0.373777 -0.09601706 0.01820498 0.373935 -0.09809607 0.01494365 0.36686 -0.118639 0.004999995 0.390756 -0.0934745 0.02082866 0.399216 -0.09184378 0.02371859 0.399303 -0.09294378 0.02042704 0.407757 -0.09125787 0.02325677 0.382493 -0.09763687 0.0146836 0.38233 -0.09554249 0.01786887 0.3938614 -0.1130443 0.005246937 0.375446 -0.117996 0.004999995 0.390883 -0.0950551 0.01753568 0.38403 -0.117336 0.004999995 0.40785 -0.09240216 0.02002829 0.416297 -0.09066319 0.02279686 0.399435 -0.0945549 0.01720547 0.392613 -0.116657 0.004999995 0.407988 -0.09404188 0.01687824 0.401195 -0.115961 0.004999995 0.41654 -0.09351599 0.01655405 0.434069 -0.09712487 0.01073747 0.4516118 -0.1004213 0.007559359 0.409775 -0.1152459 0.004999995 0.425091 -0.09297728 0.01623278 0.4517807 -0.1021916 0.006776392 0.418354 -0.114514 0.004999995 0.4507818 -0.09167629 0.01475363 0.4511696 -0.09575754 0.01054942 0.4520616 -0.1051501 0.005803048 0.426932 -0.113764 0.004999995 0.5004473 -0.08673393 0.001846969 0.4981128 -0.08742761 0 0.5005844 -0.08672565 0.001642763 0.5007227 -0.08671736 0.001431345 0.4988862 -0.08722752 0 0.5008769 -0.086708 0.001197218 0.5034837 -0.08636409 0.002922475 0.4998246 -0.08700829 0 0.5010542 -0.08669728 9.24223e-4 0.5038562 -0.08634305 0.002317905 0.5013471 -0.0866822 3.79272e-4 0.5007908 -0.08681339 0 0.504052 -0.08633208 0.001991987 0.501426 -0.08667486 3.28045e-4 0.5041018 -0.08633309 0.001908242 0.5009602 -0.08678108 0 0.5014883 -0.08668875 0 0.5042695 -0.08632028 0.001623094 0.5045971 -0.08630198 0.001053094 0.5044309 -0.08631038 0.001344323 0.5022362 -0.08657169 0 0.5048007 -0.08628946 6.89883e-4 0.5032405 -0.0864396 0 0.504447 -0.08632034 0 0.50499 -0.08627891 3.448e-4 0.5051758 -0.08626872 0 0.5003099 -0.08674228 0.002046227 0.4974959 -0.08760195 0 0.497575 -0.08751994 4.19206e-4 0.4970254 -0.08774185 0 0.5002082 -0.08674943 0.002195 0.4973096 -0.08753657 8.12768e-4 0.4962149 -0.0880019 0 0.4970242 -0.08755856 0.001186311 0.4956253 -0.08820354 0 0.4950479 -0.08841186 0 0.4967774 -0.08757579 0.001517474 0.4944039 -0.08865338 0 0.4966047 -0.08758872 0.001737713 0.4986082 -0.08684569 0.004375338 0.4964177 -0.08760273 0.001974642 0.4937635 -0.08890688 0 0.4962578 -0.08761471 0.002172648 0.4933615 -0.08907282 0 0.4935388 -0.08887463 4.79356e-4 0.4929662 -0.08923983 -1.74548e-7 0.4960606 -0.08762943 0.002420604 0.4931573 -0.08889764 9.84231e-4 0.4917232 -0.08980363 0 0.4928957 -0.0889244 0.001272082 0.4972133 -0.08693104 0.006070137 0.4926329 -0.08895105 0.001556336 0.4909844 -0.09016335 0 0.4952182 -0.08769267 0.003411173 0.4923651 -0.08897811 0.001841366 0.4904255 -0.09044742 0 0.4900167 -0.09065967 0 0.4943669 -0.08775705 0.004354059 0.4921287 -0.08900219 0.002087056 0.4994639 -0.08659201 0.008434057 0.4919407 -0.08902108 0.002279996 0.4917767 -0.08903765 0.002446949 0.4990351 -0.08661639 0.008934974 0.4915269 -0.08905899 0.002714335 0.4958581 -0.08701443 0.00756222 0.4986154 -0.08664041 0.009412825 0.4933811 -0.08783495 0.005360305 0.4983368 -0.08665579 0.009722232 0.4956033 -0.08704406 0.00766766 0.4909933 -0.08912789 0.003177285 0.4981152 -0.08666181 0.009835183 0.492944 -0.08791095 0.005557477 0.4978183 -0.0866695 0.009985148 0.490646 -0.08920812 0.003350019 0.4883865 -0.09097707 0.001313686 0.4953678 -0.08706915 0.007784783 0.4975273 -0.08667677 0.01013082 0.495132 -0.08709365 0.007901549 0.4881531 -0.09103935 0.001445829 0.4903097 -0.08928006 0.003527998 0.4900262 -0.08933967 0.003675222 0.4923077 -0.08801078 0.005875825 0.4948663 -0.08712077 0.008031189 0.4972738 -0.08668291 0.01025629 0.4945706 -0.08715015 0.008174121 0.4919459 -0.08806562 0.006052255 0.489719 -0.08940315 0.00383228 0.4967092 -0.08669561 0.01053124 0.4942407 -0.08718204 0.008331179 0.4963203 -0.08670574 0.01071751 0.4875925 -0.09118479 0.001757204 0.49391 -0.08721303 0.00848633 0.4873913 -0.09123551 0.001866757 0.49158 -0.08811962 0.006228268 0.4893001 -0.08948761 0.004043996 0.487233 -0.09127599 0.001950442 0.4889276 -0.08955985 0.004230439 0.4911536 -0.08818054 0.006431043 0.4935775 -0.08724331 0.008640587 0.4933022 -0.08726757 0.008767724 0.4908111 -0.08822792 0.006592452 0.4929971 -0.08729374 0.008907079 0.4886595 -0.08961075 0.00436294 0.492565 -0.08732944 0.009103119 0.4904943 -0.0882706 0.006739914 0.488362 -0.08966583 0.004509031 0.4879602 -0.08973878 0.004703342 0.4900899 -0.08832353 0.006926655 0.4859613 -0.09157627 0.002623379 0.487557 -0.08980989 0.004895329 0.485507 -0.0916773 0.002855241 0.4892075 -0.08843314 0.007325947 0.4872236 -0.08986669 0.005052924 0.4913718 -0.0874204 0.009631633 0.4888465 -0.08847588 0.007485806 0.486862 -0.08992713 0.005221247 0.4908957 -0.08745431 0.009835898 0.4884861 -0.08851772 0.007642865 0.4864393 -0.08999592 0.005415081 0.4881259 -0.08855867 0.007796704 0.4846287 -0.09186327 0.003291249 0.4860468 -0.09005856 0.005590856 0.4903796 -0.08748936 0.01005369 0.4876993 -0.08860588 0.007977128 0.4900206 -0.08751279 0.01020318 0.4856457 -0.09012079 0.005768597 0.4840184 -0.09198659 0.003584802 0.4836526 -0.09205925 0.003755569 0.4851606 -0.09019446 0.005978703 0.4868936 -0.08869123 0.008310139 0.4832988 -0.0921269 0.003919661 0.4865794 -0.0887233 0.008437275 0.4846342 -0.09027153 0.006202459 0.4861736 -0.08876401 0.008598923 0.4841615 -0.0903387 0.006399512 0.4874942 -0.08766108 0.0111984 0.4893728 -0.08686298 0.01364374 0.4838114 -0.09038776 0.006542384 0.4857603 -0.08880418 0.008761584 0.4889348 -0.08687186 0.01380473 0.481715 -0.09241646 0.004618048 0.4834268 -0.09044039 0.006697237 0.486601 -0.08770674 0.01153141 0.4869819 -0.08768767 0.01139056 0.4885472 -0.08687919 0.01394528 0.4879902 -0.08689117 0.01414412 0.4862232 -0.08772557 0.0116679 0.4823752 -0.09057903 0.007107257 0.479378 -0.09489631 0.003131508 0.4809572 -0.09254658 0.00493431 0.4805644 -0.09261274 0.005092918 0.485841 -0.08774393 0.01180481 0.482012 -0.09062552 0.00724405 0.4816431 -0.09067171 0.00738126 0.4801964 -0.09267359 0.005238771 0.486911 -0.0869134 0.01451838 0.4812743 -0.09071749 0.007515609 0.4847416 -0.08779615 0.0121839 0.4782965 -0.09511369 0.003590583 0.4795078 -0.09278535 0.005504488 0.4808459 -0.09077018 0.007668256 0.4791948 -0.09283554 0.005621492 0.4858292 -0.08693486 0.01487874 0.4841746 -0.0878213 0.01237493 0.4804463 -0.09081852 0.007807493 0.4801033 -0.09085923 0.007925689 0.483111 -0.08786755 0.01272052 0.4836449 -0.08784461 0.01254856 0.4797604 -0.09089976 0.008041262 0.4848171 -0.08695453 0.01520395 0.4781664 -0.09299534 0.005994498 0.4792578 -0.09095829 0.008207559 0.4777008 -0.09306699 0.006155729 0.481647 -0.08792895 0.01317262 0.4833807 -0.08696204 0.01563775 0.4821829 -0.08790665 0.0130105 0.4829669 -0.08696162 0.01575779 0.4825516 -0.0869621 0.01587694 0.481066 -0.08795267 0.01334464 0.4820269 -0.08696269 0.01602524 0.4812828 -0.08696568 0.01623123 0.4772812 -0.09118139 0.008820354 0.4793807 -0.08802086 0.013821 0.4806605 -0.08696919 0.01639991 0.4768548 -0.09122806 0.008944571 0.4754548 -0.09340167 0.006874144 0.4789353 -0.08803886 0.01394128 0.4740707 -0.09360295 0.007269203 0.4784883 -0.0880568 0.01405978 0.4799648 -0.08697414 0.01658475 0.4772176 -0.08810871 0.01438313 0.4747153 -0.09146094 0.00952214 0.4730376 -0.0937525 0.00754112 0.4742807 -0.09150773 0.009630858 0.4735445 -0.09367966 0.007409811 0.4733719 -0.09160596 0.009848296 0.4725344 -0.09382545 0.007666289 0.4738768 -0.0915513 0.009729087 0.4753099 -0.08818793 0.01483625 0.4758402 -0.08702737 0.01759451 0.4766342 -0.08701342 0.01741081 0.4746966 -0.08821433 0.0149731 0.4718354 -0.09177172 0.0101884 0.4708667 -0.09406715 0.008049845 0.4741137 -0.08823955 0.01510006 0.4750287 -0.08704286 0.0177766 0.4736469 -0.0870729 0.01807457 0.4744048 -0.08705562 0.01791286 0.4734224 -0.08827042 0.01524496 0.4713878 -0.09399175 0.007934927 0.47118 -0.091843 0.01032292 0.4724222 -0.09170848 0.01006245 0.4772516 -0.08700412 0.01726478 0.4764963 -0.08813834 0.0145592 0.4778972 -0.08808106 0.01421189 0.4752801 -0.09139984 0.009376704 0.4758136 -0.09134227 0.009234368 0.4746038 -0.09352636 0.007120788 0.4763716 -0.09128153 0.009081006 0.4800043 -0.08799552 0.01364934 0.4759433 -0.0933302 0.006725847 0.476368 -0.0932675 0.006593227 0.4777614 -0.09112781 0.008677661 0.4805907 -0.08797198 0.01348274 0.4768122 -0.09320116 0.006451427 0.4782384 -0.0910741 0.008532106 0.4787165 -0.09101998 0.008382201 0.4772553 -0.09313428 0.006306052 0.4788708 -0.09288626 0.005741596 0.4750605 -0.09345936 0.006990134 0.4792055 -0.08698004 0.01678115 0.477893 -0.0869953 0.01710951 0.4719611 -0.09390825 0.007803738 0.4729279 -0.09165346 0.009950399 0.4703499 -0.09414285 0.008158922 0.4703739 -0.09193068 0.01048028 0.4726175 -0.08830595 0.01541012 0.4729052 -0.08709061 0.01822805 0.4719892 -0.08833491 0.01553332 0.4721431 -0.08711045 0.01838147 0.4697297 -0.09200072 0.01059997 0.4687355 -0.09438049 0.008470892 0.4692733 -0.0920512 0.01068043 0.4711712 -0.08837395 0.01568704 0.4714185 -0.08713042 0.01852297 0.4688161 -0.09210222 0.01075822 0.4682278 -0.09445565 0.008560419 0.4701588 -0.08842271 0.01587033 0.4706875 -0.08715176 0.01866149 0.4677592 -0.09452593 0.008639097 0.4682761 -0.09216219 0.01084721 0.4672896 -0.0945968 0.008714199 0.4698295 -0.08717858 0.01881927 0.4676704 -0.09223043 0.01094174 0.4671267 -0.09229159 0.01102274 0.4667561 -0.0946784 0.008795261 0.4690884 -0.08847695 0.01605188 0.4690244 -0.08720517 0.01896184 0.4660453 -0.09478735 0.008896708 0.4665541 -0.09235709 0.01110363 0.4679807 -0.08853399 0.01623082 0.4681851 -0.08723425 0.01910555 0.4669005 -0.08859258 0.01639312 0.4658682 -0.09243595 0.01119494 0.4653635 -0.09489268 0.00898683 0.4671121 -0.08727401 0.01928132 0.4652504 -0.09250748 0.01127231 0.4641705 -0.09508013 0.009127557 0.4662198 -0.08730888 0.01942092 0.4646713 -0.09257537 0.01134014 0.4658322 -0.08865213 0.01654446 0.4639903 -0.09265637 0.01141422 0.4652881 -0.08734714 0.01956081 0.4649318 -0.08870404 0.01666432 0.4635521 -0.0951783 0.009192049 0.4630749 -0.09525525 0.009237825 0.4641909 -0.08739447 0.01971727 0.463117 -0.09276098 0.01150137 0.4623947 -0.09536623 0.00929737 0.4637726 -0.08877426 0.0168066 0.4622065 -0.09287148 0.01158219 0.4616671 -0.09548538 0.009354174 0.4630886 -0.08744484 0.01986551 0.4624562 -0.0888552 0.01695793 0.4613666 -0.09297484 0.01164782 0.4610863 -0.09558218 0.009393572 0.4622769 -0.08748352 0.01996916 0.4612442 -0.08893406 0.01708287 0.4605942 -0.09307086 0.01170098 0.4605683 -0.09566897 0.009424984 0.4599521 -0.09577363 0.00945729 0.461459 -0.08752369 0.02006924 0.459931 -0.09315425 0.01174098 0.460376 -0.08757925 0.02019441 0.4593077 -0.09323346 0.01177388 0.4592555 -0.09589248 0.009487867 0.4586329 -0.09600013 0.009509384 0.458489 -0.09333974 0.0118094 0.4594001 -0.08763134 0.02030014 0.4596673 -0.08903992 0.01722931 0.4582335 -0.08913952 0.01734662 0.4581135 -0.09609073 0.009523212 0.4585076 -0.08768063 0.02039116 0.4576283 -0.09345096 0.01183974 0.4575269 -0.09619426 0.009534478 0.457552 -0.08773505 0.02048301 0.4568856 -0.08923733 0.01744186 0.4567637 -0.09356534 0.01186108 0.4567622 -0.09633016 0.009542405 0.4561321 -0.09644293 0.00954312 0.4565998 -0.08779126 0.02056783 0.4558893 -0.09368056 0.01187515 0.4559059 -0.08783322 0.02062618 0.4544913 -0.0894159 0.01758414 0.4551932 -0.09377413 0.01187974 0.4555783 -0.09654337 0.009539246 0.4550181 -0.09664541 0.009531438 0.4549952 -0.08788985 0.02069789 0.454158 -0.09391546 0.01187616 0.4544644 -0.09674739 0.009519457 0.4542285 -0.08793866 0.02075403 0.4538655 -0.09685784 0.009502351 0.4534696 -0.08798819 0.02080589 0.4529942 -0.09407413 0.01185935 0.4531171 -0.09699863 0.0094738 0.4524021 -0.0880596 0.02087295 0.4506815 -0.08971947 0.01772195 0.4521338 -0.09419262 0.01183754 0.4523025 -0.09715133 0.009435117 0.4513483 -0.08813226 0.02093136 0.4511088 -0.094325 0.01181149 0.4513881 -0.09730625 0.009395122 0.4505416 -0.08818924 0.02097153 0.4505014 -0.0887351 0.0196805 0.450452 -0.08819568 0.02097564 0.4510256 -0.09424561 0.01188653 0.450535 -0.08907639 0.01895266 0.4505795 -0.08955019 0.01803064 0.4506747 -0.09054708 0.01635807 0.4507739 -0.09159559 0.0148583 0.4508955 -0.09288281 0.01330226 0.4508714 -0.09177619 0.01462215 0.450717 -0.09099 0.01569849 0.4850605 -0.08887028 0.00903052 0.4830672 -0.09048843 0.006839573 0.45095 -0.09344369 0.012694 0.4511597 -0.09568071 0.01062649 0.451229 -0.096381 0.01006978 0.4513198 -0.09734594 0.009366095 0.4514685 -0.09892904 0.00837332 0.4516997 -0.1006308 0.007461726 0.451544 -0.09970569 0.007935881 0.4516438 -0.1007627 0.007396519 0.4517974 -0.1024028 0.006700634 0.4520328 -0.1041761 0.006076335 0.4520938 -0.1054818 0.005722165 0.4519096 -0.1035494 0.006273627 0.4523736 -0.1077928 0.005263984 0.452166 -0.106256 0.005544662 0.4522629 -0.1072696 0.005344331 0.4524436 -0.1091755 0.005098104 0.4525265 -0.110041 0.005031824 0.4527127 -0.1113792 0.004999637 0.452655 -0.111406 0.004999995 0.4648128 -0.09497827 0.00905472 0.4693318 -0.09429216 0.008360743 0.4698229 -0.09421968 0.008265614 0.475845 -0.08816534 0.01471328 0.4784929 -0.08698761 0.01696097 0.4838818 -0.08696246 0.01548999 0.4826154 -0.08788746 0.01288026 0.4843227 -0.08696395 0.01535844 0.4785183 -0.09294098 0.005869507 0.4853544 -0.08694416 0.01503288 0.4798786 -0.09272539 0.005362927 0.4863503 -0.08692413 0.01470685 0.4786928 -0.09503495 0.003425478 0.485399 -0.08776551 0.01195865 0.4789865 -0.09497618 0.003300786 0.4875083 -0.08690118 0.01431292 0.4827343 -0.09053212 0.006969869 0.4813538 -0.09247934 0.004769861 0.4797976 -0.09480959 0.002945005 0.4820688 -0.0923534 0.004467248 0.4825099 -0.09227424 0.004273951 0.4880672 -0.08762997 0.01098018 0.4900469 -0.08684796 0.0133903 0.4829472 -0.09219336 0.004079103 0.4872362 -0.08865547 0.008169353 0.4896512 -0.08837896 0.007126331 0.4970284 -0.08668863 0.01037651 0.4529354 -0.1112757 0.005000174 0.452736 -0.107662 0.005276679 0.4524767 -0.1040433 0.006101846 0.4522992 -0.100498 0.007494747 0.4533042 -0.111106 0.004998981 0.4529085 -0.09157031 0.01462191 0.4532461 -0.1074613 0.005293726 0.4527968 -0.1003726 0.00752598 0.453068 -0.1038528 0.006135821 0.4536284 -0.1109578 0.004995346 0.4540278 -0.1107762 0.004989445 0.453457 -0.1002084 0.007561922 0.4537494 -0.1072645 0.005306482 0.4536335 -0.103672 0.006162822 0.4541057 -0.107126 0.005312979 0.4544144 -0.1106022 0.004980564 0.4541373 -0.1035134 0.00618273 0.4540802 -0.1000537 0.007589995 0.4544936 -0.1069778 0.005317866 0.4546836 -0.1104816 0.004972815 0.4549488 -0.1103641 0.004964351 0.4545393 -0.103387 0.006195783 0.4544989 -0.09140944 0.01459854 0.454672 -0.09990888 0.007611453 0.4549072 -0.1068198 0.00532037 0.4551829 -0.1102601 0.004954695 0.454937 -0.1032626 0.006206512 0.4552318 -0.1066969 0.00532037 0.4556162 -0.1100707 0.004937827 0.4552895 -0.09975844 0.007628321 0.4555872 -0.1065639 0.005318462 0.455339 -0.1031389 0.00621438 0.4557266 -0.09128791 0.01456576 0.4559115 -0.1099421 0.004923284 0.4557455 -0.1030145 0.006219744 0.4558145 -0.09963238 0.007638037 0.4559452 -0.1064311 0.005314171 0.4561738 -0.1098288 0.004909515 0.4563339 -0.1062883 0.005307257 0.456472 -0.1097009 0.00489217 0.4562445 -0.1028633 0.006222546 0.4562444 -0.09953016 0.007642745 0.4571343 -0.09115093 0.01451134 0.4567872 -0.1095666 0.004872202 0.4568356 -0.1061052 0.00529462 0.4566785 -0.09942811 0.007644653 0.4567085 -0.1027237 0.006221652 0.4570446 -0.1094577 0.004854738 0.4572623 -0.1025588 0.006216168 0.4572513 -0.1093701 0.004839539 0.4571971 -0.0993061 0.007643699 0.4573047 -0.1059356 0.005278885 0.4575224 -0.1092568 0.004819214 0.4576262 -0.1058195 0.00526601 0.4578204 -0.09916168 0.007636785 0.4578379 -0.1091254 0.004793643 0.4582018 -0.0910474 0.01445949 0.4578564 -0.1023852 0.006203949 0.4579538 -0.1057044 0.005250871 0.4583722 -0.1089063 0.004748702 0.4583504 -0.1022419 0.006189584 0.4584124 -0.1055417 0.005227029 0.4584333 -0.09902036 0.007624387 0.4592123 -0.09095305 0.01439863 0.4585958 -0.1088151 0.00472474 0.4587481 -0.1021271 0.0061751 0.458844 -0.1087145 0.004701018 0.4588521 -0.09892469 0.007612586 0.4589175 -0.1053665 0.005195915 0.4590288 -0.1086413 0.004682421 0.4592154 -0.1019949 0.006154417 0.4593822 -0.09880596 0.007593393 0.4601598 -0.09086459 0.01433426 0.4592525 -0.1085516 0.00465852 0.4593262 -0.1052264 0.005167424 0.4597631 -0.1018403 0.006125688 0.4597653 -0.1050775 0.005133628 0.4596744 -0.1083858 0.004613697 0.4600344 -0.09866088 0.007563769 0.4609737 -0.09079027 0.01427167 0.4599314 -0.108285 0.004584014 0.4601926 -0.1017206 0.006099343 0.4602615 -0.104911 0.005090951 0.4601198 -0.1082115 0.004561007 0.4604833 -0.09856134 0.007539629 0.4604957 -0.1080662 0.004514515 0.4618582 -0.09071052 0.01419663 0.4606215 -0.1016029 0.006069898 0.4609072 -0.09846907 0.007513761 0.4606623 -0.1047772 0.005053341 0.4609006 -0.1079118 0.004459917 0.4611378 -0.1014616 0.006030201 0.4611253 -0.1046256 0.005006194 0.4613885 -0.09836453 0.007481038 0.4629516 -0.09061431 0.01409256 0.4613049 -0.1077581 0.004402995 0.4618079 -0.09827435 0.007449388 0.4617179 -0.101306 0.005979597 0.4615582 -0.1044846 0.004958033 0.461537 -0.107671 0.004368305 0.4622954 -0.09817099 0.007408738 0.4619041 -0.1043738 0.004917085 0.461757 -0.1075887 0.004334628 0.4622372 -0.1011684 0.005928933 0.463851 -0.0905354 0.01399928 0.4619481 -0.1075174 0.004303753 0.4622198 -0.104273 0.004877626 0.4627502 -0.09807538 0.007367193 0.4622768 -0.1073973 0.004250884 0.4626385 -0.1010631 0.005886316 0.4625383 -0.1041728 0.004835903 0.4646299 -0.0904693 0.01391047 0.4631717 -0.09798759 0.007325649 0.4626131 -0.1072737 0.004194498 0.4630323 -0.1009608 0.005841791 0.4629366 -0.1040484 0.004780828 0.4628076 -0.1072033 0.00415951 0.4637141 -0.09787511 0.00726813 0.4635472 -0.1008287 0.005779147 0.4630619 -0.1071113 0.004113316 0.4655522 -0.09039187 0.01379793 0.4633355 -0.1039247 0.004722535 0.4632973 -0.1070269 0.004069209 0.4641923 -0.09777688 0.007213175 0.4637086 -0.103811 0.004664778 0.4636659 -0.1068968 0.003998517 0.4640576 -0.1006982 0.005712151 0.464741 -0.09766632 0.007144868 0.4664791 -0.09031563 0.01367545 0.4641335 -0.1036828 0.004595756 0.4644785 -0.1005924 0.005653083 0.4640291 -0.1067687 0.003925025 0.4642753 -0.1066831 0.003873884 0.4653431 -0.09754484 0.007064282 0.4648362 -0.1005035 0.005600094 0.4645855 -0.1035477 0.004517972 0.467194 -0.0902571 0.01357549 0.4644895 -0.1066088 0.003827869 0.4652014 -0.1004133 0.005542993 0.4650428 -0.1034131 0.004434764 0.4657654 -0.09746164 0.007003307 0.467806 -0.09020805 0.01348507 0.4646886 -0.1065428 0.003784716 0.464919 -0.1064673 0.003734052 0.4656531 -0.1003032 0.005469083 0.4661777 -0.09738022 0.006941378 0.4652203 -0.1063691 0.003665566 0.4655584 -0.1032643 0.004335165 0.468618 -0.09014415 0.01335811 0.4661251 -0.1001881 0.005387783 0.4666166 -0.09729397 0.006872057 0.4655004 -0.1062785 0.003599941 0.46601 -0.1031352 0.004243195 0.4658101 -0.1061789 0.003525495 0.4670913 -0.09720182 0.006792962 0.4664856 -0.1001018 0.005322098 0.4694133 -0.09008187 0.01322734 0.4668418 -0.1000168 0.005255043 0.466461 -0.1030072 0.004146933 0.4661231 -0.1060786 0.003447234 0.4677248 -0.0970804 0.006680727 0.4701293 -0.09002655 0.01310372 0.4673709 -0.09989213 0.005150139 0.4664342 -0.1059794 0.003367662 0.466955 -0.102868 0.004036188 0.4666596 -0.1059082 0.003308236 0.4682255 -0.09698486 0.006586551 0.4707278 -0.08998072 0.0129956 0.4669322 -0.1058223 0.003235399 0.467959 -0.09975546 0.005026221 0.4673672 -0.1027537 0.003939032 0.4686002 -0.09691411 0.006513118 0.4671644 -0.1057488 0.003170907 0.4712938 -0.08993804 0.01288932 0.4677551 -0.1026484 0.003843903 0.4690622 -0.09682708 0.006418883 0.4685381 -0.09962183 0.004897058 0.467554 -0.1056275 0.003060638 0.4718435 -0.08989632 0.01278322 0.468193 -0.1025302 0.003732144 0.4678487 -0.1055363 0.002974033 0.4694946 -0.09674638 0.006326615 0.4723235 -0.08986037 0.01268726 0.4690814 -0.09949737 0.004769325 0.46814 -0.1054464 0.00288695 0.4685444 -0.1024359 0.003638923 0.469953 -0.09666132 0.006224989 0.4729157 -0.08981662 0.01256471 0.4683187 -0.1053918 0.002831697 0.4688712 -0.1023493 0.003549575 0.4695143 -0.0994001 0.004662394 0.4685365 -0.1053251 0.002763986 0.4704991 -0.09656029 0.006098687 0.4692231 -0.1022573 0.003450214 0.4735013 -0.08977323 0.01243937 0.4699738 -0.09929752 0.004544019 0.468847 -0.1052314 0.002665281 0.469565 -0.1021669 0.003350973 0.4691244 -0.1051474 0.002574086 0.4710409 -0.09646046 0.005967319 0.4740129 -0.08973574 0.01232653 0.4705706 -0.09916532 0.004383087 0.4696095 -0.1050026 0.002411723 0.4699838 -0.1020576 0.003225088 0.4744873 -0.08970111 0.01221865 0.4714636 -0.09638345 0.005859971 0.474955 -0.08966684 0.01210993 0.4718493 -0.09631276 0.005759596 0.4710933 -0.09904867 0.004235744 0.4698547 -0.1049295 0.002324163 0.4703566 -0.1019623 0.003108561 0.470099 -0.1048576 0.002236843 0.4707291 -0.101868 0.002988517 0.4755332 -0.08962482 0.01197105 0.4723178 -0.09622704 0.005633294 0.4715344 -0.09895145 0.004106163 0.4704242 -0.104762 0.002118408 0.4710872 -0.1017758 0.002869844 0.4762426 -0.08957278 0.01179563 0.4726964 -0.09615772 0.005527913 0.4719176 -0.09886723 0.003989577 0.4706817 -0.1046869 0.002021729 0.4714298 -0.1016905 0.002752721 0.473076 -0.09608864 0.005418956 0.4722995 -0.09878391 0.003869771 0.4710479 -0.1045822 0.001882016 0.4769793 -0.08951854 0.01160669 0.4718101 -0.1015943 0.002618908 0.4735386 -0.09600436 0.005282044 0.472734 -0.09868913 0.003728985 0.4713955 -0.1044825 0.001744389 0.4721155 -0.1015177 0.002508282 0.4775706 -0.08947485 0.01144951 0.4739158 -0.0959357 0.005166649 0.4716271 -0.1044169 0.001651227 0.4731093 -0.0986073 0.003603398 0.4724669 -0.1014297 0.002378165 0.4718494 -0.1043536 0.001559853 0.4742899 -0.09586757 0.005049288 0.4779884 -0.08944386 0.01133579 0.4734674 -0.09853023 0.003479838 0.4720952 -0.104285 0.001456856 0.478478 -0.08940774 0.01119863 0.4729146 -0.1013176 0.002207279 0.4746912 -0.09579437 0.004919528 0.4738166 -0.09845453 0.003356158 0.4723173 -0.1042232 0.001362025 0.4725866 -0.1041492 0.001245081 0.4751676 -0.09570664 0.004761815 0.4789552 -0.0893718 0.01106286 0.4742027 -0.09836935 0.003216922 0.4732919 -0.1012241 0.002057731 0.4793683 -0.08934074 0.01094204 0.472899 -0.1040635 0.001106381 0.4736125 -0.1011446 0.001927495 0.4746776 -0.09826588 0.003039121 0.4757248 -0.09560334 0.004570126 0.4731343 -0.1039997 9.9967e-4 0.4797769 -0.08930969 0.01082062 0.4740405 -0.1010402 0.001748502 0.4733671 -0.1039372 8.91631e-4 0.480152 -0.08928108 0.01070678 0.4752017 -0.09815108 0.002835988 0.476147 -0.09552538 0.004419565 0.4735639 -0.1038839 7.98833e-4 0.48063 -0.08924436 0.01055854 0.474465 -0.1009356 0.001564919 0.4765344 -0.09545296 0.004278063 0.473734 -0.1038385 7.17357e-4 0.4757164 -0.09803754 0.002628743 0.4739462 -0.1037817 6.13936e-4 0.4748141 -0.1008462 0.001411318 0.4810616 -0.08921021 0.01042288 0.4770293 -0.09535938 0.004092395 0.4814622 -0.08917838 0.01029431 0.4760994 -0.09795218 0.002469718 0.4744305 -0.1036561 3.74553e-4 0.475156 -0.100762 0.001255452 0.4775121 -0.09526616 0.003906309 0.4818634 -0.08914619 0.01016294 0.476458 -0.09787219 0.002317249 0.4755184 -0.1006716 0.001086413 0.4746994 -0.1035868 2.36941e-4 0.4822968 -0.08911097 0.01001828 0.4749016 -0.1035352 1.31656e-4 0.4778918 -0.09519279 0.003755331 0.4768884 -0.0977751 0.002129495 0.4759161 -0.1005815 8.9072e-4 0.4751507 -0.1034719 6.57445e-7 0.4828205 -0.08906733 0.009840369 0.4760835 -0.1005284 8.14572e-4 0.4752991 -0.1032453 0 0.477385 -0.09766083 0.001906812 0.4755976 -0.1028029 2.41398e-7 0.4763249 -0.1004649 6.96281e-4 0.4832497 -0.0890311 0.00969088 0.4759362 -0.1023206 -1.47409e-7 0.4836103 -0.08900022 0.009563386 0.476606 -0.1003937 5.54327e-4 0.476226 -0.1019238 0 0.4778583 -0.0975514 0.001686632 0.4840002 -0.08896625 0.009423375 0.4764609 -0.1016112 0 0.4768791 -0.1003242 4.13519e-4 0.4766775 -0.1013287 -1.21382e-7 0.4771158 -0.1002756 2.82091e-4 0.4781817 -0.09747582 0.001532614 0.484322 -0.08893752 0.009306073 0.4769368 -0.100998 -1.50712e-6 0.4783746 -0.09743046 0.001439034 0.4846422 -0.08890855 0.009187996 0.4772901 -0.1005685 1.68293e-7 0.4785735 -0.0973832 0.001340806 0.4775902 -0.1002124 0 0.480112 -0.09474402 0.002802014 0.4787541 -0.09734016 0.001251578 0.4789347 -0.09729528 0.001161575 0.4779471 -0.09980285 3.33956e-7 0.4854398 -0.08883458 0.008886158 0.4804437 -0.09467309 0.002649486 0.4791207 -0.09724467 0.00107187 0.4782624 -0.09945368 6.24298e-7 0.478533 -0.09917372 7.03763e-7 0.4808579 -0.09458392 0.00245434 0.4793719 -0.09718734 9.39379e-4 0.4796045 -0.09712892 8.18239e-4 0.4788925 -0.09880781 0 0.4812753 -0.09449261 0.002252042 0.4799521 -0.09704113 6.34272e-4 0.4886012 -0.08759963 0.01077306 0.4906339 -0.08683592 0.01316487 0.4793921 -0.09831643 1.22779e-7 0.4817202 -0.09439772 0.002026915 0.4796659 -0.09805309 0 0.4891346 -0.08756822 0.010562 0.4802979 -0.09696364 4.36684e-4 0.491225 -0.08682262 0.01293289 0.4799551 -0.09777843 -7.81351e-7 0.4819461 -0.09433883 0.001921355 0.4802317 -0.09752315 0 0.4896634 -0.08753573 0.01034879 0.4917762 -0.08681112 0.01271241 0.4821571 -0.0942896 0.00181365 0.4806196 -0.097171 0 0.482396 -0.09423345 0.001691162 0.4810256 -0.09681165 2.05059e-7 0.4843382 -0.0919227 0.003431975 0.4826416 -0.09417456 0.001563847 0.4924517 -0.08679533 0.01243591 0.4814746 -0.09642356 0 0.4828853 -0.09411501 0.001436054 0.4929602 -0.08678454 0.01222336 0.4831411 -0.09405016 0.001302242 0.4818319 -0.09612298 0 0.4848902 -0.09180903 0.003163397 0.4822714 -0.09576511 0 0.4851517 -0.09175401 0.003033339 0.493456 -0.08677291 0.0120123 0.4834615 -0.09397029 0.001128196 0.4937878 -0.08676546 0.01186913 0.4917852 -0.08739006 0.009450614 0.4827736 -0.09536933 0 0.4837284 -0.09390228 9.81118e-4 0.4940953 -0.08675891 0.01173496 0.4840136 -0.09382802 8.2261e-4 0.492161 -0.08736139 0.0092839 0.4831908 -0.09504842 0 0.4945632 -0.08674693 0.01152753 0.4836624 -0.0946936 1.29172e-7 0.4843045 -0.09375131 6.5779e-4 0.494898 -0.08673965 0.01137739 0.4863609 -0.09148967 0.002407133 0.4845237 -0.09369969 5.20625e-4 0.4840424 -0.09441143 -8.30923e-7 0.4952833 -0.08673155 0.01120215 0.4865401 -0.09144347 0.002320766 0.4844256 -0.09413695 0 0.4867127 -0.09140205 0.002230525 0.4868627 -0.09136641 0.002149939 0.4957392 -0.08671945 0.01099121 0.4847843 -0.09388369 0 0.4870352 -0.09132462 0.002057731 0.496021 -0.08671301 0.01085913 0.4851372 -0.09363764 0 0.4855778 -0.09333723 0 0.4859629 -0.09308058 0 0.4878147 -0.09112799 0.001633763 0.4863309 -0.09283757 0 0.4879812 -0.0910843 0.001542806 0.4926124 -0.08796352 0.00572443 0.486807 -0.09252762 0 0.4873099 -0.09221011 0 0.4886565 -0.09090352 0.001160025 0.4877054 -0.09196698 0 0.4889206 -0.09083092 0.00100708 0.4881519 -0.09169942 0 0.4892588 -0.09079372 6.64134e-4 0.4886946 -0.09138447 0 0.489103 -0.0911538 0 0.4896023 -0.09088039 0 0.4998619 -0.08656924 0.007955491 0.5001333 -0.08655381 0.007622539 0.5004481 -0.08653593 0.00722897 0.500753 -0.08651858 0.006838619 0.5011568 -0.08649563 0.00630939 0.4924823 -0.08945357 0 0.5014935 -0.08647656 0.005855262 0.5017263 -0.08646333 0.00553596 0.502013 -0.08644711 0.005133569 0.5023429 -0.08642846 0.004659831 0.502724 -0.08640688 0.004098057 0.5030486 -0.08638858 0.003604352 0.5032231 -0.08637881 0.003333926 0.417734 -0.08296096 0 0.22032 -0.09388619 0 0.222374 -0.09194147 0 0.2499769 -0.09269529 0 0.5041335 -0.08634823 0 0.4915109 -0.07897573 0 0.5046554 -0.08630454 0 0.5051367 -0.0862714 0 0.51 -0.07799953 4.01155e-7 0.455 -0.074225 0 0.48 -0.074225 0 0.48 -0.07958817 0 0.455 -0.08093041 0 0.51 -0.08599996 0 0.4989326 -0.08721625 0 0.503578 -0.08640277 0 0.503022 -0.08646678 0 0.5025956 -0.08652162 0 0.5019795 -0.08660984 0 0.5013558 -0.0867114 0 0.5008313 -0.08680558 0 0.5002863 -0.08691197 0 0.4998458 -0.08700495 0 0.4994032 -0.0871039 0 0.498423 -0.08734536 0 0.4977226 -0.08753603 0 0.4970758 -0.08772665 0 0.4964796 -0.08791452 0 0.4958832 -0.08811348 0 0.4954266 -0.08827477 0 0.4948295 -0.08849185 0 0.4941813 -0.08873957 0 0.4935606 -0.08898979 0 0.4930366 -0.08921068 0 0.4926489 -0.0893799 0 0.4922189 -0.0895729 0 0.4916089 -0.08985823 0 0.4909864 -0.09016227 0 0.4903212 -0.09050101 0 0.4896618 -0.09084773 0 0.4891031 -0.09115397 0 0.4887045 -0.09137839 0 0.4880699 -0.09174782 0 0.4875274 -0.09207522 0 0.4870182 -0.09239321 0 0.486575 -0.09267693 0 0.4860175 -0.09304457 0 0.4854898 -0.0933966 0 0.436368 -0.08193969 0 0.4850623 -0.09368902 0 0.4844362 -0.0941292 0 0.4839152 -0.09450644 0 0.4835096 -0.09480774 0 0.4830284 -0.09517216 0 0.4825713 -0.09552741 0 0.4820623 -0.09593313 0 0.4817984 -0.09615105 0 0.481478 -0.0964204 0 0.4810789 -0.09676444 0 0.4805529 -0.09723079 0 0.4800434 -0.09769731 0 0.4796624 -0.09805631 0 0.4793287 -0.0983774 0 0.4788178 -0.0988835 0 0.4785453 -0.09915971 0 0.478274 -0.09943991 0 0.4779645 -0.09978252 0 0.4775863 -0.1002165 0 0.4773473 -0.1004993 0 0.4771295 -0.1007628 0 0.4768409 -0.1011216 0 0.4765706 -0.1014676 0 0.3991 -0.08399426 0 0.4763763 -0.1017225 0 0.4762055 -0.1019512 0 0.4759125 -0.1023544 0 0.4756163 -0.1027761 0 0.4753487 -0.1031705 0 0.4751499 -0.1034721 0 0.39 -0.127696 0 0.415 -0.129584 0 0.380464 -0.08503967 0 0.449355 -0.145388 0 0.415 -0.147584 0 0.449124 -0.1457369 0 0.4337115 -0.1497437 0 0.444303 -0.149034 0 0.4344919 -0.14982 0 0.446983 -0.147763 0 0.446624 -0.147988 0 0.442662 -0.149479 0 0.43635 -0.149937 0 0.443081 -0.149383 0 0.441005 -0.149762 0 0.441831 -0.14964 0 0.44142 -0.1497049 0 0.440585 -0.149811 0 0.440162 -0.149853 0 0.439739 -0.149888 0 0.439318 -0.1499159 0 0.442244 -0.149565 0 0.4386329 -0.1499468 0 0.43781 -0.149962 0 0.4369577 -0.1499558 0 0.443496 -0.149277 0 0.4356899 -0.1499062 0 0.435082 -0.1498669 0 0.443902 -0.149161 0 0.444702 -0.148894 0 0.445098 -0.1487399 0 0.445876 -0.148393 0 0.445491 -0.1485739 0 0.446254 -0.1481969 0 0.447669 -0.147266 0 0.447331 -0.147522 0 0.448303 -0.146701 0 0.447992 -0.146992 0 0.448601 -0.146392 0 0.448873 -0.146071 0 0.343188 -0.08716666 0 0.268131 -0.1109009 0 0.361827 -0.08609718 0 0.342357 -0.13665 0 0.340568 -0.1361629 0 0.324548 -0.08824825 0 0.351346 -0.1388739 0 0.349542 -0.138457 0 0.382416 -0.14382 0 0.39 -0.1446959 0 0.360402 -0.140748 0 0.358585 -0.140401 0 0.380567 -0.1436409 0 0.37872 -0.1434479 0 0.376876 -0.143241 0 0.375035 -0.14302 0 0.373196 -0.142785 0 0.37136 -0.142536 0 0.369527 -0.142273 0 0.367696 -0.141996 0 0.365869 -0.141705 0 0.364044 -0.1414 0 0.362222 -0.141081 0 0.356771 -0.1400409 0 0.353151 -0.139277 0 0.35496 -0.139666 0 0.347742 -0.1380259 0 0.345944 -0.137581 0 0.34415 -0.137122 0 0.305907 -0.08934199 0 0.266193 -0.110251 0 0.287265 -0.09044766 0 0.26425 -0.109624 0 0.260353 -0.108439 0 0.262304 -0.1090199 0 0.256439 -0.107344 0 0.258398 -0.1078799 0 0.254476 -0.106831 0 0.268622 -0.09156548 0 0.252509 -0.106341 0 0.250538 -0.105874 0 0.248562 -0.105429 0 0.246583 -0.105007 0 0.2445999 -0.104609 0 0.242612 -0.104232 0 0.24062 -0.103879 0 0.2351509 -0.100293 0 0.238624 -0.103549 0 0.236625 -0.103241 0 0.220156 -0.09988385 0 0.220383 -0.09344208 0 0.220339 -0.09366208 0 0.220542 -0.09302359 0 0.22045 -0.09322875 0 0.220791 -0.09265136 0 0.220656 -0.09283047 0 0.221116 -0.09234338 0 0.220945 -0.09248811 0 0.221502 -0.09211558 0 0.221302 -0.09221869 0 0.221928 -0.09197938 0 0.221711 -0.09203559 0 0.222149 -0.09194809 0 0.51 -0.0643565 0.01924109 0.51 -0.07610207 0.0251767 0.51 -0.06500577 0.01903527 0.51 -0.04773849 0.01854258 0.51 -0.03530156 0.02345985 0.51 -0.03582847 0.02386599 0.51 -0.04836899 0.01879239 0.51 -0.03637045 0.02424675 0.51 -0.07235217 0.02673029 0.51 -0.06370431 0.01942026 0.51 -0.07169508 0.02691006 0.51 -0.04650497 0.0179789 0.51 -0.03380578 0.02215194 0.51 -0.03429114 0.02260255 0.51 -0.0347892 0.0230388 0.51 -0.04711484 0.01826947 0.51 -0.04531395 0.01733469 0.51 -0.03244537 0.02070426 0.51 -0.03288435 0.02120357 0.51 -0.03333675 0.02168565 0.51 -0.04590469 0.01766729 0.51 -0.04417008 0.01660698 0.51 -0.03124499 0.01911938 0.51 -0.03162598 0.01966339 0.51 -0.03202587 0.02019089 0.51 -0.04473298 0.01698106 0.51 -0.04255956 0.01536005 0.51 -0.03054326 0.01799625 0.51 -0.04308336 0.01579648 0.51 -0.03088408 0.01856356 0.51 -0.04362016 0.01621216 0.51 -0.04156839 0.01443856 0.51 -0.02992105 0.0168246 0.51 -0.04205596 0.01490855 0.51 -0.0302217 0.0174151 0.51 -0.02914458 0.01499456 0.51 -0.02938205 0.01561319 0.51 -0.04064089 0.01344329 0.51 -0.02964144 0.01622468 0.51 -0.04109668 0.01395016 0.51 -0.02892899 0.01436889 0.51 -0.04020708 0.01292425 0.51 -0.02873456 0.01373368 0.51 -0.0397917 0.01238936 0.51 -0.02856296 0.01309365 0.51 -0.02841407 0.01244878 0.51 -0.03939455 0.01183855 0.51 -0.03901588 0.01127189 0.51 -0.02818435 0.01114207 0.51 -0.03866046 0.01069658 0.51 -0.03832548 0.01010829 0.51 -0.02828776 0.01179659 0.51 -0.02804636 0.009825766 0.51 -0.02810388 0.01048505 0.51 -0.03801089 0.009507 0.51 -0.08595299 0.009858787 0.51 -0.08598846 0.009181082 0.51 -0.07628089 0.008889436 0.51 -0.03744578 0.008273124 0.51 -0.02801167 0.009164035 0.51 -0.03771656 0.008892774 0.51 -0.0753411 0.01069098 0.51 -0.08570116 0.01187658 0.51 -0.08580988 0.011204 0.51 -0.08541399 0.01320135 0.51 -0.08556926 0.01254236 0.51 -0.0746085 0.01183408 0.51 -0.03719645 0.007643461 0.51 -0.02799999 0.008500039 0.51 -0.07379609 0.01291894 0.51 -0.0850321 0.01450419 0.51 -0.08523547 0.01385366 0.51 -0.0848065 0.01514446 0.51 -0.07335919 0.0134415 0.51 -0.03696876 0.007003903 0.51 -0.07290738 0.01394444 0.51 -0.08455866 0.01577466 0.51 -0.08399337 0.0170089 0.51 -0.08428865 0.01639467 0.51 -0.071949 0.01490306 0.51 -0.03676265 0.006354331 0.51 -0.08367788 0.01760995 0.51 -0.07144236 0.01535856 0.51 -0.08334207 0.01819807 0.51 -0.07092356 0.01579225 0.51 -0.03642755 0.005043208 0.51 -0.03658336 0.005702257 0.51 -0.07038885 0.01620775 0.51 -0.08298629 0.01877319 0.51 -0.07243728 0.01443165 0.51 -0.03629547 0.004377186 0.51 -0.0698384 0.0166049 0.51 -0.08260738 0.01933979 0.51 -0.0822103 0.01989024 0.51 -0.06927198 0.01698386 0.51 -0.03618699 0.00370413 0.51 -0.08179467 0.0204249 0.51 -0.07421261 0.01238316 0.51 -0.03610378 0.003033161 0.51 -0.08136075 0.02094346 0.51 -0.06869697 0.01733988 0.51 -0.07498395 0.01127177 0.51 -0.03601026 0.001681089 0.51 -0.03604489 0.002358794 0.51 -0.08090436 0.02144938 0.51 -0.06810885 0.01767569 0.51 -0.08589351 0.01053309 0.51 -0.07567638 0.01010036 0.51 -0.03599995 0.000999987 0.51 -0.02799999 0 0.51 -0.08043229 0.02193707 0.51 -0.0759896 0.009499847 0.51 -0.07994461 0.02240669 0.51 -0.0675078 0.01799148 0.51 -0.07655209 0.008264422 0.51 -0.08599996 0.008499979 0.51 -0.06689375 0.01828706 0.51 -0.0768001 0.007632732 0.51 -0.07702499 0.006994247 0.51 -0.07722675 0.006349086 0.51 -0.03599995 0 0.51 -0.03692716 0.02460736 0.51 -0.04900658 0.01901876 0.51 -0.03749865 0.02494788 0.51 -0.04965108 0.01922178 0.51 -0.03807747 0.02526938 0.51 -0.03926819 0.02585387 0.51 -0.03866726 0.0255714 0.51 -0.03987759 0.02611315 0.51 -0.05030798 0.01940166 0.51 -0.04049676 0.02635097 0.51 -0.04112577 0.02656739 0.51 -0.04175937 0.02676057 0.51 -0.05096828 0.01955795 0.51 -0.04240006 0.02693146 0.51 -0.04369789 0.02720695 0.51 -0.0430479 0.02707999 0.51 -0.04501187 0.02739524 0.51 -0.04435259 0.02731209 0.51 -0.04633456 0.02748847 0.51 -0.04567188 0.0274536 0.51 -0.04699999 0.02749997 0.51 -0.05163186 0.01969069 0.51 -0.0522989 0.01979976 0.51 -0.05296909 0.0198853 0.51 -0.05364274 0.01994717 0.51 -0.05499994 0.01999998 0.51 -0.05431967 0.01998537 0.51 -0.05899995 0.01999998 0.51 -0.06304478 0.01957577 0.51 -0.06768089 0.02748727 0.51 -0.06170427 0.01981556 0.51 -0.06103307 0.01989817 0.51 -0.06699997 0.02749997 0.51 -0.06970328 0.02730607 0.51 -0.07037055 0.02719795 0.51 -0.07103449 0.02706587 0.51 -0.07426768 0.02605456 0.51 -0.07363599 0.02630305 0.51 -0.07299751 0.02652829 0.51 -0.07550239 0.02549088 0.51 -0.07489258 0.025783 0.51 -0.07727116 0.02448207 0.51 -0.06564497 0.01880764 0.51 -0.07669168 0.02484035 0.51 -0.07783329 0.02410626 0.51 -0.07838225 0.02371037 0.51 -0.0662744 0.01855826 0.51 -0.07891827 0.02329427 0.51 -0.08599996 0 0.51 -0.07740616 0.005691945 0.51 -0.0794413 0.02285796 0.51 -0.07756197 0.005031526 0.51 -0.07769405 0.004367828 0.51 -0.07780259 0.003700852 0.51 -0.07788747 0.003030598 0.51 -0.07794857 0.002357006 0.51 -0.07798606 0.001680135 0.51 -0.078 0.000999987 0.51 -0.078 0 0.51 -0.06903249 0.02739036 0.51 -0.06835836 0.02745079 0.51 -0.06237816 0.0197075 0.51 -0.0603587 0.01995646 0.51 -0.05968099 0.0199905 0.476744 -0.04393714 0.01999998 0.476959 -0.03802925 0.028023 0.477035 -0.03594249 0.01999998 0.476744 -0.04393714 0.02980619 0.476772 -0.0431714 0.02966076 0.4768 -0.04241335 0.02949327 0.476827 -0.04166328 0.02930366 0.476854 -0.04092085 0.02909189 0.476881 -0.04018628 0.02885788 0.476907 -0.03945946 0.02860176 0.476933 -0.03874045 0.02832347 0.476985 -0.03732585 0.02770036 0.47701 -0.03663027 0.02735567 0.477035 -0.03594249 0.0269888 0.3508513 -0.02770859 0.01999998 0.35033 -0.02717655 0.03643399 0.350635 -0.02749097 0.03645479 0.349974 -0.02679169 0.01999998 0.4647844 -0.04395282 0.03069478 0.468035 -0.04393726 0.01099997 0.465043 -0.04400235 0.01099997 0.350034 -0.02685737 0.03639996 0.4546795 -0.04404526 0.0314458 0.4543833 -0.04414933 0.01099997 0.4607541 -0.044079 0.01099997 0.4403887 -0.04413723 0.01099997 0.4444706 -0.04411935 0.03219121 0.444107 -0.04416257 0.01099997 0.4490429 -0.04417246 0.01099997 0.448697 -0.04409563 0.03188478 0.4334703 -0.0441032 0.03296864 0.4345907 -0.0440647 0.01099997 0.4292117 -0.04404789 0.03326016 0.438689 -0.04413151 0.03260415 0.4204224 -0.04382055 0.03384178 0.4184201 -0.0436564 0.01099997 0.4248229 -0.04395616 0.03355419 0.4281652 -0.04393774 0.01099997 0.3987407 -0.04232579 0.01099997 0.400606 -0.04249292 0.0350272 0.414223 -0.04349255 0.01099997 0.412814 -0.04346317 0.03431957 0.4157851 -0.04362177 0.03413623 0.3812838 -0.03953802 0.01099997 0.3812169 -0.03955018 0.03595048 0.3876146 -0.04074513 0.03567725 0.3879786 -0.04080253 0.01099997 0.367303 -0.03607428 0.01999998 0.366306 -0.03577399 0.036462 0.3749024 -0.03813093 0.03618842 0.3712359 -0.03718882 0.01099997 0.3551363 -0.031008 0.01999998 0.3550308 -0.03094136 0.03662866 0.360324 -0.03363043 0.03658664 0.3602753 -0.03361308 0.01999998 0.3564286 -0.0317614 0.03662019 0.3582791 -0.03271818 0.0366041 0.3569986 -0.03206968 0.01999998 0.4093853 -0.0432474 0.03452652 0.4112367 -0.04337263 0 0.3585516 -0.0328384 0.01999998 0.406237 -0.04300785 0 0.406237 -0.04300785 0.01099997 0.4051588 -0.04292142 0.03477293 0.3616465 -0.03416496 0.0365681 0.3625812 -0.03451722 0.01999998 0.3638207 -0.03496199 0.03652513 0.3649039 -0.03532576 0.01999998 0.3687995 -0.03651279 0.03638905 0.3696142 -0.03674459 0.01999998 0.371237 -0.03718459 0.01999998 0.3714943 -0.0372557 0.03630381 0.349468 -0.02620345 0.03629338 0.349747 -0.02653336 0.03635287 0.3489473 -0.02555394 0.01999998 0.349196 -0.02586644 0.03622245 0.348935 -0.02552729 0.03613626 0.348684 -0.025186 0.03603488 0.348444 -0.02483999 0.03591895 0.3480994 -0.02431356 0.01999998 0.347995 -0.02414298 0.03564095 0.348214 -0.02449059 0.03578805 0.347787 -0.02379715 0.03547769 0.347592 -0.0234493 0.03529727 0.3474334 -0.0231623 0.01999998 0.347408 -0.02310377 0.03510087 0.347073 -0.02243065 0.03466176 0.347235 -0.02276426 0.03488898 0.3468751 -0.02198988 0.01999998 0.346925 -0.02209877 0.03441679 0.346786 -0.02177488 0.03415745 0.3463841 -0.02073395 0.01999998 0.346657 -0.02146035 0.03388488 0.346538 -0.02115529 0.03359878 0.346432 -0.0208562 0.03329575 0.346333 -0.02056878 0.03298187 0.346242 -0.02029305 0.03265714 0.34616 -0.02002865 0.03232055 0.346087 -0.01977467 0.03197097 0.3459828 -0.0194031 0.01999998 0.34602 -0.01953399 0.03161299 0.345959 -0.01930648 0.03124666 0.345906 -0.01909166 0.03087037 0.345858 -0.01888966 0.03048497 0.345815 -0.01870185 0.03009355 0.345777 -0.0185284 0.02969604 0.345606 -0.01766365 0.01999998 0.345743 -0.01836818 0.02929049 0.345715 -0.01822239 0.02887916 0.345667 -0.01797574 0.02804487 0.345689 -0.01809155 0.02846395 0.345648 -0.01787495 0.02762186 0.345621 -0.01771849 0.02676415 0.345633 -0.01778918 0.02719497 0.345612 -0.0176627 0.02632945 0.3511735 -0.02801829 0.03649657 0.352077 -0.02881467 0.03653669 0.3518267 -0.02859973 0.01999998 0.3527489 -0.02935767 0.01999998 0.3530791 -0.02961194 0.0365917 0.3538191 -0.03014206 0.01999998 0.353856 -0.03017187 0.03661692 0.3767315 -0.03854084 0.01099997 0.3783468 -0.03893363 0.03606218 0.3843945 -0.04017394 0.03581887 0.384423 -0.04015845 0.01099997 0.3904104 -0.04119354 0.03554755 0.390989 -0.04128974 0.01099997 0.393046 -0.04157668 0.03541988 0.3944647 -0.04179644 0.01099997 0.3961899 -0.04199224 0.03526151 0.4029672 -0.04275012 0.01099997 0.411237 -0.04336738 0.01099997 0.4712763 -0.04392647 0.03021109 0.468035 -0.04393726 0.01999998 0.476744 -0.04392814 0.01999998 0.476744 -0.04393535 0.02980595 0.345612 -0.01761877 0.02218484 0.345612 -0.0176627 0.02632945 0.345612 -0.0176627 0.01999998 0.345612 -0.01763504 0.01999998 0.345612 -0.01759827 0.02328449 0.345612 -0.0176205 0.02534538 0.345612 -0.01759898 0.02433037 0.474027 -0.04392749 0.01999998 0.477035 -0.03594249 0.01999998 0.471124 -0.04392749 0.01999998 0.350222 -0.02705919 0.01999998 0.350662 -0.02751755 0.01999998 0.371237 -0.02918457 0.01999998 0.4205348 -0.02269983 0.01999998 0.347292 -0.02288007 0.01999998 0.347595 -0.02345567 0.01999998 0.3695704 -0.03673082 0.01999998 0.371237 -0.0371859 0.01999998 0.3682441 -0.0363515 0.01999998 0.3669325 -0.03596127 0.01999998 0.3655329 -0.03552734 0.01999998 0.3642559 -0.0351054 0.01999998 0.362601 -0.03452235 0.01999998 0.363256 -0.03475785 0.01999998 0.361311 -0.03402787 0.01999998 0.361954 -0.03427845 0.01999998 0.360037 -0.03350687 0.01999998 0.360672 -0.03377068 0.01999998 0.358794 -0.03295075 0.01999998 0.359412 -0.03323274 0.01999998 0.357575 -0.03236269 0.01999998 0.358182 -0.03266066 0.01999998 0.356394 -0.03173559 0.01999998 0.35698 -0.03205418 0.01999998 0.355247 -0.03107035 0.01999998 0.355816 -0.03140765 0.01999998 0.354143 -0.03036206 0.01999998 0.354689 -0.0307222 0.01999998 0.353084 -0.02960979 0.01999998 0.353608 -0.02999126 0.01999998 0.352075 -0.02881008 0.01999998 0.352572 -0.02921676 0.01999998 0.35112 -0.02796047 0.01999998 0.351591 -0.0283913 0.01999998 0.349797 -0.02658748 0.01999998 0.349388 -0.0261023 0.01999998 0.348993 -0.02560377 0.01999998 0.348259 -0.02455949 0.01999998 0.348617 -0.02508926 0.01999998 0.347919 -0.02401494 0.01999998 0.346746 -0.02167814 0.01999998 0.347009 -0.02228718 0.01999998 0.346502 -0.02105319 0.01999998 0.34608 -0.01975029 0.01999998 0.346279 -0.02041125 0.01999998 0.345747 -0.01837599 0.01999998 0.345903 -0.01907175 0.01999998 0.345612 -0.0176627 0.01999998 0.345612 -0.01763504 0.01999998 0.468035 -0.03543728 0.01999998 0.495241 -0.03034007 0.01999998 0.495241 -0.03060024 0.01999998 0.495023 -0.03659635 0.01999998 0.476744 -0.04393714 0.01999998 0.468035 -0.04393726 0.01999998 0.495241 -0.03060024 0.01999998 0.495241 -0.03060024 0.02034616 0.495241 -0.03034007 0.01999998 0.495023 -0.03659635 0.01999998 0.495178 -0.0323289 0.02240586 0.495195 -0.03186875 0.02191489 0.495044 -0.03601616 0.02538305 0.495065 -0.03544938 0.02500945 0.495023 -0.03659635 0.02573937 0.495085 -0.03489595 0.02461868 0.495104 -0.03435587 0.02421057 0.495124 -0.03382909 0.02378529 0.49516 -0.03281557 0.02288299 0.495142 -0.03331565 0.02334278 0.495211 -0.03142726 0.0214079 0.495226 -0.03100448 0.02088499 0.495241 -0.03060024 0.02034616 0.495241 -0.03060024 0.01999998 0.477035 -0.03594249 0.01999998 0.477035 -0.03594249 0.0269888 0.486007 -0.03626859 0.02635806 0.495023 -0.03659635 0.02573937 0.495023 -0.03659635 0.01999998 0.3340001 -0.01689869 0.009301006 0.334 -0.04255306 0 0.3340001 -0.01691001 0 0.334 -0.04255306 0.01499998 0.334 -0.01688188 0.01499998 0.334 -0.04255306 0.01499998 0.328607 -0.04237645 0.03119146 0.311804 -0.04182636 0.03218245 0.36 -0.04340416 0.003881454 0.36 -0.04340416 0.02599996 0.337 -0.04265129 0.01499998 0.337 -0.04265129 0 0.360082 -0.0434069 0.003323078 0.360037 -0.04340535 0.003504455 0.360009 -0.04340445 0.003691554 0.360222 -0.04341149 0.002999961 0.360145 -0.04340887 0.003153383 0.455 -0.04651415 0 0.455 -0.04651415 0.002999961 0.334 -0.04255306 0 0.317949 -0.04202759 7.11862e-4 0.317987 -0.04202878 3.5792e-4 0.311936 -0.04183077 0.004885375 0.295 -0.04127627 0.03315764 0.317885 -0.04202544 0.001063942 0.318 -0.04202926 0 0.311591 -0.04181945 0.004797279 0.311252 -0.04180836 0.004684269 0.317797 -0.04202258 0.001409173 0.317684 -0.04201889 0.001748263 0.317548 -0.04201447 0.002077758 0.317388 -0.04200917 0.002396941 0.317206 -0.04200327 0.002704024 0.317002 -0.04199659 0.002996742 0.316778 -0.04198926 0.003275096 0.316536 -0.04198127 0.003535509 0.316273 -0.04197269 0.00377947 0.315996 -0.04196369 0.004002869 0.315702 -0.04195398 0.004206836 0.315396 -0.04194396 0.00438863 0.315076 -0.04193359 0.00454849 0.314408 -0.04191166 0.004797577 0.314747 -0.04192274 0.004684984 0.313712 -0.04188889 0.004949033 0.314062 -0.04190039 0.004885852 0.313 -0.04186558 0.004999995 0.313358 -0.04187726 0.004987061 0.312642 -0.0418539 0.004987061 0.312288 -0.04184228 0.004949033 0.295 -0.04127627 0 0.310922 -0.04179757 0.004547774 0.310603 -0.04178708 0.004387855 0.310296 -0.04177707 0.004205644 0.310003 -0.04176747 0.004002332 0.309725 -0.04175835 0.003777921 0.309464 -0.04174989 0.003535509 0.30922 -0.04174184 0.003273308 0.308997 -0.04173457 0.002996146 0.308793 -0.0417279 0.002702116 0.308611 -0.04172188 0.002395689 0.308451 -0.04171669 0.002076029 0.308315 -0.04171216 0.001746535 0.308202 -0.04170846 0.001407802 0.308114 -0.04170554 0.001061797 0.308051 -0.04170358 7.11862e-4 0.308013 -0.04170227 3.5792e-4 0.308 -0.04170185 0 0.36221 -0.04347658 0.02916216 0.345409 -0.04292654 0.03018468 0.395809 -0.04457646 0.02706974 0.37901 -0.04402649 0.02812385 0.412608 -0.04512637 0.02599996 0.3096798 -0.01526182 0.003744125 0.3097061 -0.04175776 0.003772258 0.3102808 -0.01530206 0.004200041 0.3104444 -0.0417819 0.004301548 0.3110531 -0.01535379 0.004612147 0.3110831 -0.04180282 0.00462085 0.3117641 -0.04182517 0.004849731 0.3117482 -0.01540058 0.00484842 0.3123578 -0.01544159 0.004956126 0.3124763 -0.04184842 0.004974961 0.313 -0.01548475 0.004999995 0.313 -0.04186558 0.004999995 0.3091102 -0.04173827 0.003146111 0.3091129 -0.01522397 0.003153622 0.3087047 -0.04172492 0.002565324 0.3086637 -0.01519429 0.002496182 0.308451 -0.04171669 0.002076029 0.3083849 -0.0151757 0.001929163 0.3082475 -0.04170995 0.001562714 0.3081839 -0.01516234 0.001355111 0.3080528 -0.0151534 7.42731e-4 0.3080773 -0.04170441 8.91592e-4 0.3079912 -0.04170155 2.84146e-7 0.3079951 -0.01514935 1.58791e-7 0.2319378 -0.01018232 0.03145456 0.255783 -0.01168417 0.03197067 0.2521901 -0.01145362 0.02999997 -0.206521 -0.09830886 0.03188908 -0.229373 -0.09191399 0.03331327 -0.229387 -0.09458029 0.02898007 0.2319453 -0.01018404 0.03351265 0.3020085 -0.01474159 0.007906496 0.232012 -0.01019847 0.03440785 0.23197 -0.01018947 0.03420579 0.232495 -0.01030409 0.0353114 0.23263 -0.01033365 0.03546649 0.255784 -0.01189517 0.03448325 0.2322559 -0.01025187 0.03497618 0.232157 -0.01023006 0.03479498 0.2338241 -0.01059609 0.03643226 0.233076 -0.01043146 0.03588926 0.233235 -0.01046639 0.03601807 0.334 -0.01688164 0.01499998 0.3340001 -0.01690346 0.006624877 0.255786 -0.01243746 0.03643286 0.2350907 -0.01087516 0.03711241 0.3458819 -0.01899218 0.03068876 0.325173 -0.01748806 0.03221338 0.2371708 -0.01132875 0.03791266 0.255788 -0.0140872 0.0394628 0.255787 -0.01318395 0.03806287 0.278922 -0.01549714 0.03767138 0.2830001 -0.01346635 0.01807618 0.345612 -0.01763528 0.01999998 0.302053 -0.01689416 0.0357123 0.32519 -0.01918685 0.03481197 0.325182 -0.01827549 0.03359657 0.3456118 -0.01765644 0.02629733 0.3207532 -0.01593655 0.02687162 0.325157 -0.01638948 0.02876788 0.3456121 -0.01761573 0.02234101 0.4635879 -0.025321 0.008996605 0.4423472 -0.02405136 0.005556523 0.3554449 -0.01829946 0.02000004 0.4176214 -0.02246403 0.008704364 0.4885036 -0.02676093 0.01069855 0.383072 -0.02016735 0.01999998 0.371371 -0.01934218 0.01996439 0.4179092 -0.02252703 0 0.363 -0.0188747 0 0.3630001 -0.01886826 0.005132377 0.4638594 -0.02537977 0.002071082 0.3879886 -0.02056998 0 0.4527561 -0.02469849 0 0.4859814 -0.0266751 0.001860797 0.51 -0.02799975 0 0.4868771 -0.02670902 0 0.232075 -0.01021218 0.03460568 0.312605 -0.01545828 0.004977941 0.312245 -0.01543396 0.004939436 0.318 -0.01582509 0 0.317987 -0.01582407 3.60726e-4 0.334 -0.01690888 0 0.23237 -0.01027679 0.03514796 0.232773 -0.01036489 0.03561389 0.232922 -0.01039755 0.03575456 0.314747 -0.01560294 0.004684865 0.314408 -0.01557999 0.004797577 0.317885 -0.0158171 0.001066863 0.317948 -0.01582145 7.16354e-4 0.313 -0.01548475 0.004999995 0.311366 -0.01537489 0.004725456 0.311096 -0.01535665 0.004623711 0.317684 -0.01580327 0.001750349 0.317796 -0.01581108 0.001412272 0.317547 -0.01579385 0.002079546 0.317387 -0.01578289 0.002399086 0.317204 -0.01577037 0.002705752 0.317 -0.01575636 0.00300014 0.316776 -0.01574105 0.003277122 0.316532 -0.01572448 0.003538906 0.316272 -0.01570665 0.003780543 0.315995 -0.01568776 0.004003942 0.315702 -0.01566785 0.004206657 0.315076 -0.01562529 0.004548668 0.315395 -0.01564699 0.004388868 0.314064 -0.01555669 0.004885435 0.313713 -0.01553285 0.004948914 0.313359 -0.01550894 0.004986941 0.311918 -0.01541209 0.004884541 0.311625 -0.0153923 0.004813253 0.310834 -0.01533907 0.004506945 0.310302 -0.01530349 0.004206538 0.310572 -0.01532155 0.004369676 0.310028 -0.01528519 0.004021048 0.30979 -0.01526916 0.00383538 0.30957 -0.01525449 0.003640055 0.309359 -0.01524037 0.003425359 0.309146 -0.01522618 0.003181576 0.308938 -0.01521235 0.002915203 0.308758 -0.01520049 0.002647995 0.308597 -0.01518988 0.002370715 0.308456 -0.01518046 0.002085864 0.283 -0.01347607 0 0.308333 -0.0151723 0.001796126 0.30823 -0.01516538 0.001499772 0.308146 -0.01515978 0.001202523 0.308082 -0.01515537 9.02045e-4 0.308036 -0.01515227 6.00533e-4 0.308009 -0.01515036 3.0037e-4 0.308 -0.01514977 0 0.01102864 -0.005043029 0.05330181 0.00137645 -0.005617082 0.05394536 0.2334823 -0.01052087 0.03620326 0.234184 -0.01067543 0.03664821 0.2345335 -0.01075255 0.03683894 0.234798 -0.01081085 0.0369727 0.235421 -0.0109477 0.03725999 0.2359064 -0.01105427 0.03746175 0.2884408 -0.01398438 0.03193104 0.2367714 -0.0112425 0.0377798 0.2363744 -0.01115614 0.03763884 0.2830001 -0.01344233 0.02999997 0.2377107 -0.0114445 0.03808045 0.2384343 -0.01159864 0.03828603 0.239169 -0.01175385 0.0384767 0.2411573 -0.01217502 0.03893393 0.2399242 -0.01191335 0.03865945 0.278918 -0.01461857 0.03626739 0.241886 -0.0123316 0.03908467 0.242435 -0.01244366 0.0391829 0.243547 -0.0126394 0.03931826 0.244107 -0.01272535 0.03936237 0.242989 -0.0125463 0.03926014 0.278914 -0.01389479 0.03463888 0.302041 -0.01536625 0.03270035 0.34616 -0.02002865 0.03232055 0.345959 -0.01930648 0.03124666 0.2315378 -0.01278162 0.04142445 0.255789 -0.01512479 0.04067409 0.2330446 -0.0127747 0.04119551 0.232653 -0.01371407 0.0423153 0.2279062 -0.01277261 0.04192936 0.2292563 -0.01277959 0.04174828 0.2419126 -0.01273065 0.03974193 0.240859 -0.0127384 0.03992825 0.2440741 -0.01280081 0.03948891 0.2396586 -0.01274174 0.04012906 0.2424293 -0.01273363 0.03966021 0.2434808 -0.01276791 0.03953731 0.2431279 -0.01275187 0.03957194 0.242771 -0.01274049 0.0396139 0.2370526 -0.01274621 0.04054862 0.2345076 -0.01276367 0.04096257 0.2302836 -0.01278221 0.04160559 0.278925 -0.01650846 0.0388906 0.30206 -0.01786279 0.03693288 0.2095209 -0.01344519 0.04480326 0.2260681 -0.01275718 0.04216438 0.346657 -0.02146035 0.03388488 0.325199 -0.02021265 0.03587627 0.346786 -0.02177488 0.03415745 0.2239194 -0.01273238 0.04242646 0.51 -0.02962476 0.01620262 0.486941 -0.02832859 0.01817876 0.47034 -0.02779334 0.01999998 0.2218654 -0.01270276 0.04266589 0.325207 -0.02134978 0.03679496 0.346925 -0.02209877 0.03441679 0.219896 -0.01267063 0.04288768 0.2176727 -0.0126304 0.04312944 0.215412 -0.01258713 0.04336845 0.25579 -0.01628679 0.04171675 0.278929 -0.01764225 0.03994417 0.2128007 -0.01253455 0.0436365 0.232652 -0.01488405 0.04334586 0.2099708 -0.01247578 0.04391962 0.2065497 -0.01240354 0.04425257 0.278933 -0.01889598 0.04083859 0.302071 -0.02015405 0.03890097 0.2040178 -0.01234978 0.04449295 0.2004791 -0.01227414 0.04482167 0.1963315 -0.01218456 0.04519468 0.1929292 -0.01211065 0.04549223 0.5100001 -0.03082972 0.01849335 0.495226 -0.03100448 0.02088499 0.51 -0.03123944 0.01912528 0.1893647 -0.0120331 0.04579651 0.185815 -0.01195645 0.04609137 0.1818964 -0.01187217 0.04640895 0.186394 -0.01324278 0.0469014 0.209519 -0.01472645 0.04565906 0.302077 -0.02147656 0.03965216 0.278936 -0.02027314 0.04157167 0.495211 -0.03142726 0.0214079 0.325221 -0.02397155 0.03817725 0.348935 -0.02552729 0.03613626 0.348684 -0.025186 0.03603488 0.1780475 -0.01179009 0.04671192 0.255791 -0.01757127 0.04259794 0.255792 -0.01898306 0.04331535 0.51 -0.03161728 0.01966929 0.2326509 -0.01617777 0.04421454 0.1739622 -0.01170343 0.04702538 0.1696782 -0.01161307 0.04734414 0.495195 -0.03186875 0.02191489 0.163275 -0.01175427 0.04797124 0.186392 -0.01462548 0.04758656 0.18639 -0.0161677 0.04810327 0.209514 -0.01770758 0.04687237 0.1658529 -0.01153284 0.04762113 0.160623 -0.01142388 0.04798805 0.5100001 -0.03230321 0.02056944 0.1547082 -0.01130127 0.04838639 0.23265 -0.01760166 0.04491925 0.4951717 -0.03249347 0.02257287 0.163273 -0.01308798 0.04864597 0.5099999 -0.03312247 0.02149635 0.325232 -0.02708709 0.0388301 0.348367 -0.02780896 0.03673017 0.35033 -0.02717655 0.03643399 0.1501467 -0.01120752 0.04868215 0.1451792 -0.01110607 0.04899394 0.209516 -0.01613998 0.04635345 0.140157 -0.01155757 0.04955935 0.1387454 -0.01097518 0.04938095 0.4951362 -0.03348392 0.02349233 0.5099999 -0.03408277 0.02244424 0.1330108 -0.01085847 0.04971015 0.232649 -0.01917397 0.04544568 0.1292174 -0.01078099 0.04991996 0.140156 -0.01299506 0.05007636 0.1256715 -0.01070821 0.05011117 0.495104 -0.03435587 0.02421057 0.1192337 -0.01057451 0.05044466 0.5099999 -0.03508877 0.02330952 0.11704 -0.01142668 0.05086767 0.232648 -0.02092945 0.04576557 0.495078 -0.03509068 0.02476102 0.1132255 -0.01044744 0.05074006 0.1074502 -0.01032274 0.0510106 0.278944 -0.02529895 0.04260796 0.278945 -0.02729916 0.04265737 0.302093 -0.02800416 0.04088854 0.5099999 -0.03615164 0.0241037 0.209513 -0.01947569 0.04718565 0.495044 -0.03601616 0.02538305 0.1027903 -0.01021963 0.05121916 0.0857076 -0.009811103 0.05191719 0.09392118 -0.01147758 0.05192327 0.495023 -0.03659635 0.02573937 0.0994355 -0.01014357 0.05136448 0.255796 -0.02924799 0.04430085 0.278947 -0.03236055 0.04275888 0.278946 -0.02963167 0.04270559 0.117039 -0.01306205 0.05122095 0.232647 -0.02296668 0.0458253 0.5100001 -0.03722864 0.02480185 0.163271 -0.01458609 0.0491631 0.348376 -0.0324921 0.0374158 0.35697 -0.03205096 0.03661537 0.356396 -0.03173989 0.03662025 0.09556609 -0.01005381 0.05152708 0.09060335 -0.009934544 0.05172789 0.486007 -0.03626859 0.02635806 0.486959 -0.03743159 0.02689927 0.302095 -0.02997738 0.04098439 0.4770348 -0.03594034 0.02699279 0.186387 -0.0179283 0.04842036 0.209511 -0.02158939 0.04723095 0.4769702 -0.03772848 0.02789151 0.0708 -0.01000589 0.05256408 0.09475499 -0.0138325 0.05200529 0.51 -0.03807705 0.02527749 0.302095 -0.03240638 0.04109048 0.325239 -0.03245019 0.0393092 0.2328771 -0.02714258 0.04578077 0.476933 -0.03874045 0.02832347 0.486958 -0.03937226 0.02776575 0.08145833 -0.009698927 0.05207526 0.186386 -0.02010619 0.04846608 0.163269 -0.01632106 0.04949069 0.140154 -0.01468777 0.0504173 0.4768959 -0.03976947 0.02871692 0.361731 -0.03419494 0.03656625 0.361123 -0.03395634 0.03657609 0.348376 -0.03481537 0.03774034 0.362342 -0.03442674 0.03655534 0.07692646 -0.009572625 0.05223721 0.186221 -0.0308755 0.04833662 0.209509 -0.03220909 0.04709035 0.486957 -0.04146689 0.02847367 0.4768285 -0.04162532 0.02930223 0.07107967 -0.01235359 0.05267333 0.51 -0.03988099 0.02611684 0.51 -0.0389741 0.0257278 0.07224351 -0.009433805 0.05239778 0.3650834 -0.03538292 0.03649419 0.3662691 -0.0357604 0.03646248 0.348375 -0.03729397 0.03805279 0.2096091 -0.02624934 0.0471639 0.1637701 -0.01850563 0.04952287 0.1408532 -0.01694601 0.0504617 0.06798559 -0.009298503 0.05253809 0.325239 -0.03493696 0.0395351 0.5100001 -0.04210561 0.02686208 0.51 -0.04081076 0.02646613 0.3688975 -0.03653961 0.03638589 0.3675804 -0.03615772 0.03642541 0.3704726 -0.03697866 0.03633666 0.09395992 -0.03309595 0.05203056 0.0650925 -0.00920099 0.05263054 0.06263279 -0.009114384 0.05270755 0.3735679 -0.03779381 0.03623431 0.4446344 -0.04411929 0.03217941 0.4402531 -0.0441302 0.03249305 0.440814 -0.04525399 0.03260529 0.4489758 -0.04409283 0.0318644 0.453277 -0.04405695 0.03154915 0.41772 -0.04602825 0.03428989 0.432654 -0.04409325 0.03302478 0.426039 -0.04398447 0.03347319 0.428244 -0.04403018 0.03332537 0.394616 -0.04412984 0.03565239 0.394613 -0.04678624 0.03590124 0.2553912 -0.04578244 0.0444042 0.2331991 -0.04308611 0.04563254 0.285033 -0.04466348 0.04265969 0.255796 -0.04135864 0.04436385 0.232646 -0.03855597 0.04569888 0.1865575 -0.04522746 0.04804295 0.1630619 -0.04096114 0.0492652 0.2118693 -0.04372781 0.04676115 0.1636159 -0.03269714 0.04938167 0.2106723 -0.03749567 0.0469262 0.371503 -0.03949689 0.03664875 0.3824667 -0.03980118 0.0358994 0.3809089 -0.0394845 0.03596252 0.06000506 -0.009017407 0.05278813 0.05710256 -0.008904635 0.05287557 0.0476737 -0.008852958 0.05321049 0.05407691 -0.008779585 0.05296391 0.0514698 -0.008665204 0.05303823 0.04884213 -0.008543193 0.05311137 -0.06817412 -0.03269094 0.05777829 -0.1145015 -0.05505836 0.05741959 0.02474051 -0.09785723 0.05405718 0.04770207 -0.0900408 0.05339646 -0.09133714 -0.06573289 0.05803149 -0.1144637 -0.06762695 0.05750137 -0.09134405 -0.07363241 0.05812567 -0.2291949 -0.05200856 0.04216545 -0.206422 -0.06113505 0.04563146 -0.206413 -0.0585196 0.04549628 -0.02180176 -0.101933 0.05583494 0.00137639 -0.103458 0.05464559 -0.02180218 -0.09972816 0.05609846 -0.183566 -0.08347505 0.04843068 -0.183569 -0.08001166 0.04882168 -0.206459 -0.07324057 0.04647576 -0.1144589 -0.07461351 0.05759781 -0.137522 -0.07062786 0.0558477 -0.137521 -0.0738812 0.05586677 -0.160566 -0.07598775 0.05268949 -0.183574 -0.07357817 0.04893845 -0.160564 -0.0792582 0.05262857 0.09146666 -0.1026784 0.05106127 0.07079946 -0.103285 0.05195116 -0.206468 -0.07703298 0.04642587 -0.1835629 -0.08699721 0.04750555 -0.137522 -0.0674268 0.05583155 -0.1605692 -0.06255054 0.05286306 -0.160571 -0.06675946 0.0528205 -0.273365 -0.07287609 0.02928227 -0.29 -0.06037229 0.01686066 -0.273364 -0.0745871 0.02791368 -0.09135025 -0.08104681 0.05826067 -0.04501152 -0.08486038 0.05711805 -0.0681672 -0.08106565 0.05793291 -0.04495203 -0.09232032 0.05721366 0.07079958 -0.101925 0.05242395 0.0931524 -0.1011456 0.05159133 -0.183579 -0.06768518 0.04901599 -0.183582 -0.06485718 0.0490458 -0.09128528 -0.08997809 0.058501 -0.06811916 -0.08814841 0.0580675 0.09469455 -0.09974277 0.05186253 -0.1374936 -0.06322795 0.05581688 -0.1144757 -0.06051582 0.05743753 -0.183586 -0.05931568 0.04908949 -0.183584 -0.0620746 0.04907029 0.0962305 -0.09834635 0.05195724 0.07128089 -0.09721952 0.05271911 0.0707997 -0.100054 0.0527116 -0.09138244 -0.05777043 0.05798155 -0.1605785 -0.04365658 0.05289405 0.04567819 -0.008386194 0.05319678 0.04308396 -0.008247256 0.0532642 0.02453505 -0.008253991 0.05393958 0.04101556 -0.008130311 0.05331623 -0.06817179 -0.01115429 0.05718797 -0.06817537 -0.01367175 0.05767154 -0.04499286 -0.01143479 0.05691707 0.03894865 -0.008006572 0.05336576 -0.1375248 -0.02280354 0.05579954 -0.1144118 -0.02138584 0.05743932 -0.160584 -0.02945655 0.05289185 -0.1375688 -0.05654639 0.0557928 -0.160584 -0.0264675 0.05289238 0.03673893 -0.00786674 0.05341643 -0.188 -0.03299993 0.04834473 -0.1835989 -0.03234159 0.04910326 -0.0449903 -0.009296715 0.0564779 -0.02180367 -0.00957942 0.05588525 0.03456449 -0.007719099 0.05346256 -0.09133177 -0.01305437 0.05736094 -0.114455 -0.01470535 0.05674356 -0.09133565 -0.01595205 0.05788975 0.001376628 -0.00844419 0.0548287 -0.02180248 -0.007773339 0.05548429 0.03290903 -0.007600069 0.0534951 -0.09132736 -0.01033645 0.05645465 -0.114452 -0.01161557 0.05573225 -0.06816768 -0.008856177 0.05639779 -0.160583 -0.02324616 0.05289328 -0.160582 -0.01968008 0.05277138 0.02896791 -0.007289171 0.05356061 -0.114459 -0.0179373 0.0573129 -0.1724449 -0.02135807 0.05099523 -0.137522 -0.01928907 0.05567717 -0.1605809 -0.01609599 0.05215638 0.02602845 -0.007028162 0.05359482 0.001376569 -0.006875991 0.0544545 -0.1709123 -0.02021121 0.05119556 0.02481138 -0.006911814 0.05360436 -0.1691214 -0.01887106 0.05135458 0.02358525 -0.006789088 0.05361062 0.02233105 -0.006657838 0.05361318 -0.1675532 -0.01769715 0.05142807 -0.137521 -0.01581567 0.05507785 -0.1631622 -0.01441091 0.05129367 0.02068668 -0.006475687 0.0536099 -0.04498738 -0.007415533 0.05580157 -0.06816327 -0.006739616 0.05532407 0.01933073 -0.006314218 0.05359929 0.01837188 -0.006194174 0.05358755 -0.1643283 -0.01528364 0.05137938 0.01740247 -0.00606656 0.0535711 -0.162328 -0.01378649 0.05120998 0.01645237 -0.00593543 0.05355018 0.01548945 -0.005795419 0.05352306 -0.13752 -0.01245278 0.05398666 -0.1591208 -0.01138621 0.0507031 -0.1604062 -0.01234841 0.0509423 -0.0681585 -0.004802823 0.05398547 -0.0449841 -0.005715906 0.05491518 -0.114439 -0.003596186 0.05022525 -0.114443 -0.006015419 0.05245167 -0.09131729 -0.005463719 0.05358767 0.01332479 -0.005453586 0.05343836 0.01211041 -0.005242764 0.05337274 -0.1580128 -0.01055699 0.05045312 -0.1570964 -0.009870946 0.05021649 -0.137519 -0.009264826 0.05241376 -0.09131175 -0.003359317 0.05166035 -0.156309 -0.009281933 0.04999005 -0.09132248 -0.007799327 0.05518949 -0.137517 -0.003671407 0.04792827 -0.137518 -0.006316125 0.05038535 0.00137633 -0.004538238 0.05333429 0.009932458 -0.004828095 0.05321538 -0.114434 -0.001494824 0.04763507 -0.0449807 -0.004174947 0.05383348 -0.0681535 -0.003057837 0.05238765 0.009151101 -0.004665315 0.05314284 0.008187711 -0.004449605 0.05303728 0.008651971 -0.004556 0.05309081 0.00759685 -0.004306733 0.05296105 -0.153952 -0.007517755 0.04917466 -0.1546782 -0.00806123 0.04945045 0.007054507 -0.00416702 0.05288147 -0.1532164 -0.006966352 0.04887437 -0.0913062 -0.001519739 0.04941695 -0.1521989 -0.006205797 0.04842007 0.006498336 -0.004013597 0.05278831 -0.02179789 -0.003722369 0.05332046 -0.1509321 -0.005257546 0.04778116 -0.151576 -0.005739629 0.04811537 0.001376211 -0.003587663 0.05262994 0.005950808 -0.003851413 0.05268323 -0.1144289 2.3826e-4 0.04471069 0.005009531 -0.003543376 0.0524646 0.004609465 -0.003401756 0.052356 -0.1495981 -0.004258573 0.04701012 -0.150242 -0.004741251 0.04739415 -0.0913006 1.54963e-5 0.04687088 -0.06814837 -0.001523673 0.05053186 -0.137515 -0.001392364 0.04507809 -0.146905 -0.00224328 0.04506909 -0.148973 -0.003791451 0.04660767 -0.148564 -0.003485321 0.04633045 -0.02179616 -0.002650439 0.05232387 -0.148147 -0.003173351 0.0460335 0.004084289 -0.003206431 0.05219721 0.003561973 -0.003002405 0.05202001 -0.137223 0.002924203 0 -0.1150569 0.002636015 0 -0.147732 -0.002862334 0.04572427 -0.04497337 -0.001563906 0.05108517 -0.06814318 -2.27636e-4 0.04841744 0.003047108 -0.002791047 0.05182784 -0.114424 0.001542747 0.04147905 0.002539217 -0.00257945 0.05161356 -0.146118 -0.001654326 0.04437935 -0.146507 -0.001945555 0.04472875 -0.0912801 0.002220392 0.005563259 -0.145736 -0.001368761 0.04402029 0.002178788 -0.002421975 0.05144649 -0.1375139 4.62996e-4 0.04188305 -0.1442599 -2.64273e-4 0.04243785 -0.091295 0.001193165 0.04402744 -0.145362 -0.001088738 0.04365158 0.001938045 -0.002311289 0.05132359 0.001704812 -0.002196371 0.05119025 -0.02179437 -0.001697421 0.05118215 0.001481831 -0.002076566 0.05104476 -0.144991 -8.10875e-4 0.04326367 0.001273214 -0.001950323 0.05088388 0.001080095 -0.001819074 0.05070817 -0.144623 -5.35732e-4 0.04285818 9.06818e-4 -0.001683592 0.05051589 -0.06813806 7.88904e-4 0.04603087 -0.04496967 -5.14195e-4 0.04940205 -0.09128957 0.001955509 0.04088598 -0.1435599 2.60171e-4 0.04155856 -0.143234 5.03852e-4 0.04110729 6.19159e-4 -0.001407504 0.05008846 -0.02179259 -8.67243e-4 0.04987585 7.52466e-4 -0.001545369 0.05030888 -0.14292 7.38567e-4 0.04064536 -0.142055 0.001386165 0.03918737 -0.142619 9.64315e-4 0.04017299 -0.04496598 3.32204e-4 0.04747915 -0.06813305 0.001474678 0.04333335 -0.02179086 -1.74663e-4 0.04836237 -0.1423299 0.00118041 0.03968769 4.08044e-4 -0.001138091 0.04961389 3.27452e-4 -0.001009702 0.04936307 -0.1142503 0.002619564 0.03420168 -0.1144199 0.002359807 0.03797477 -0.09141409 0.002219736 0.0373013 -0.137513 0.00183463 0.03839337 -0.14131 0.001944005 0.03761094 -0.141544 0.001768767 0.0381484 2.59101e-4 -8.88098e-4 0.04910629 2.03408e-4 -7.72586e-4 0.04884308 -0.1410959 0.002103984 0.03706508 -0.140898 0.002251863 0.03650826 -0.137223 0.002855181 0.03299999 -0.1401 0.002849698 0.03299999 -0.1401849 0.002786099 0.03360176 1.56632e-4 -6.64648e-4 0.04857569 1.19499e-4 -5.63902e-4 0.04830336 -0.06795626 0.001726627 0.04007548 -0.04496234 9.33647e-4 0.04524189 -0.137512 0.002670526 0.03467297 -0.1405529 0.002510488 0.03536325 -0.140717 0.002387583 0.03594058 -0.1402879 0.002708375 0.03419625 8.9132e-5 -4.71148e-4 0.04802799 -0.140411 0.002616465 0.03478348 5.53892e-5 -3.44076e-4 0.0476011 -0.02178919 3.48501e-4 0.04653668 -0.137223 0.002920448 0.02765417 -0.04501157 0.001181542 0.04228681 1.64069e-5 -1.02243e-4 0.04644358 2.90272e-5 -2.04001e-4 0.04701071 -0.02176117 5.8416e-4 0.04388964 -0.06999999 0.001773774 0.02999997 1.18392e-5 -3.40926e-5 0.04582822 -0.04445892 0.001169443 0.02999997 1.05139e-5 1.10025e-6 0.04520952 -0.02045959 5.5331e-4 0.02999997 1.06239e-5 4.61046e-7 0.02999997 -0.09222269 0.002249062 0 -0.06999993 0.001776397 0 -0.29 -0.0477004 0.02198785 -0.29 -0.0483976 0.02195149 -0.273366 -0.05924689 0.03447568 -0.04497706 -0.00278902 0.0525586 -0.276517 -0.04199975 0.03339707 -0.277261 -0.04199969 0.0330674 -0.275004 -0.04199999 0.03399825 -0.0217995 -0.004918515 0.05418109 -0.1555406 -0.008706688 0.04974883 0.0145511 -0.005652189 0.05349075 -0.1614161 -0.01310348 0.05109632 -0.02180105 -0.006255447 0.05490607 -0.1658548 -0.01642638 0.05143529 -0.1144469 -0.008704423 0.05429339 0.02742302 -0.007155597 0.05358058 -0.175279 -0.02347928 0.05052632 0.03084099 -0.007442474 0.05353206 -0.1785204 -0.02590537 0.0499764 -0.1853879 -0.03104507 0.04879504 -0.160584 -0.03233939 0.05289167 -0.0912646 -0.0192542 0.05801409 -0.04492026 -0.04802316 0.05699843 -0.1832496 -0.05615478 0.04916149 -0.1605961 -0.05659717 0.05289322 -0.02180445 -0.07336145 0.05598366 -0.0450229 -0.07629334 0.05705082 -0.02180379 -0.0830878 0.05600762 -0.02180308 -0.09142982 0.05604285 0.001465082 -0.09401428 0.05493921 -0.206405 -0.05598127 0.045385 -0.241445 -0.09268903 0.02552485 -0.206449 -0.06978815 0.04620826 -0.183571 -0.07670569 0.04888856 -0.04498887 -0.0994513 0.05706077 -0.06816965 -0.09640359 0.05798929 -0.04498809 -0.10164 0.05650728 -0.137521 -0.07720279 0.05588924 -0.1605679 -0.07282859 0.05274057 0.08520174 -0.1083744 0 0.07079839 -0.108904 0.006919085 0.0857008 -0.107922 0.04541528 0.07079875 -0.108199 0.04691314 0.07079869 -0.108671 0.04542875 -0.2900001 -0.04699945 0.02200013 -0.2733673 -0.05704897 0.0345841 -0.229139 -0.04355096 0.04157787 -0.20639 -0.05105185 0.04523867 -0.2061307 -0.04674798 0.04525697 -0.251901 -0.0426293 0.03839164 -0.251904 -0.04428809 0.03838986 -0.2386972 -0.04200005 0.04021733 -0.287212 -0.04200428 0.02574259 -0.273366 -0.04504698 0.03457695 -0.286655 -0.04200357 0.02636307 -0.2899999 -0.04199981 0.02199983 -0.273366 -0.0484367 0.03457885 -0.280868 -0.04199957 0.03112828 -0.281567 -0.04199957 0.03068238 -0.2604693 -0.03299999 0.03737092 -0.255026 -0.03499364 0.03799736 -0.255026 -0.03299999 0.03799736 -0.2573496 -0.03299999 0.03776812 -0.2634658 -0.03299999 0.03689032 -0.26542 -0.03299999 0.03651875 -0.268241 -0.03299999 0.035905 -0.2702291 -0.03299999 0.03541445 -0.275004 -0.03572165 0.03399825 -0.266839 -0.03299999 0.03622257 -0.2730174 -0.03299999 0.03462994 -0.275004 -0.03299999 0.03399819 -0.255026 -0.04039376 0.03799736 -0.277998 -0.04199969 0.0327183 -0.275764 -0.04199987 0.03370738 -0.278727 -0.04199957 0.03234988 -0.279882 -0.04199951 0.03172075 -0.282254 -0.04199969 0.03021496 -0.282925 -0.04200005 0.0297237 -0.283585 -0.04200047 0.0292111 -0.284234 -0.04200106 0.0286771 -0.284871 -0.04200178 0.02812165 -0.285487 -0.04200237 0.02755099 -0.255026 -0.04199999 0.03799736 -0.287752 -0.04200488 0.0251044 -0.288256 -0.04200476 0.02448278 -0.28873 -0.04200404 0.02386569 -0.289179 -0.04200309 0.02324616 -0.248912 -0.04199999 0.03880685 -0.29 -0.04909169 0.02189099 -0.29 -0.04978245 0.02180629 -0.273366 -0.06120836 0.0342226 -0.29 -0.05183595 0.02140694 -0.29 -0.05251067 0.02122616 -0.273365 -0.06301635 0.03385645 -0.229128 -0.04179376 0.04158568 -0.230597 -0.04199999 0.04139286 -0.251906 -0.04612159 0.03838789 -0.29 -0.05047017 0.0216974 -0.1834266 -0.04816842 0.0491352 -0.2221912 -0.04199987 0.04265743 -0.183577 -0.0705831 0.04898047 -0.114454 -0.08665579 0.05785816 -0.114455 -0.08308947 0.05777037 -0.137521 -0.08061701 0.05591595 -0.16057 -0.06975948 0.05278396 -0.0913214 -0.110004 0.04448294 -0.09132236 -0.108637 0.04759538 -0.114446 -0.107484 0.04545456 -0.09132677 -0.09926027 0.05646419 -0.06816649 -0.103894 0.05506175 -0.0681675 -0.101567 0.05640047 -0.1144559 -0.07959806 0.05769157 -0.0913257 -0.102055 0.05487215 -0.06816548 -0.106009 0.05336999 -0.251958 -0.08748608 0.02789068 -0.251941 -0.08931845 0.02476996 -0.251593 -0.08939105 0.02490186 -0.249106 -0.09001606 0.02557718 -0.248747 -0.0901196 0.02564138 -0.254574 -0.08893907 0.02333229 -0.273363 -0.08223527 0.01561635 -0.254874 -0.0889213 0.02309906 -0.273364 -0.08151715 0.01790708 -0.253951 -0.08899599 0.02376097 -0.255705 -0.08891397 0.02232199 -0.25544 -0.08890849 0.02259445 -0.255164 -0.08891087 0.02285325 -0.256786 -0.08905887 0.02077907 -0.256945 -0.0891112 0.0204364 -0.256608 -0.089015 0.02110916 -0.256408 -0.08897811 0.02142989 -0.273363 -0.08270239 0.01339375 -0.257081 -0.0891695 0.020087 -0.257283 -0.08930438 0.01936829 -0.257194 -0.08923339 0.01973229 -0.29 -0.06670761 0.005476474 -0.257388 -0.08945858 0.01863545 -0.257404 -0.08954137 0.01826769 -0.257348 -0.0893796 0.01900237 -0.257396 -0.08962786 0.01789897 -0.257364 -0.08971816 0.01752924 -0.273363 -0.08294969 0.01128005 -0.29 -0.06689935 0.004091322 -0.29 -0.06695765 0.003397166 -0.257299 -0.08985567 0.0169304 -0.257172 -0.09015178 0.01511746 -0.257203 -0.09007245 0.01572448 -0.257245 -0.0899738 0.01632875 -0.25715 -0.09027338 0.01328039 -0.257146 -0.09025228 0.01389545 -0.29 -0.06700003 0.002000033 -0.2733618 -0.08301478 0.009313642 -0.29 -0.0669912 0.00270003 -0.2571656 -0.09027534 0.01268035 -0.2571557 -0.09027397 0.005228638 -0.2624435 -0.0883131 0 -0.2597035 -0.08937919 0 -0.2571538 -0.09027385 0.001314401 -0.2733632 -0.08300763 0.001290917 -0.2661775 -0.0867334 -1.36076e-7 -0.2646644 -0.08739131 -1.26085e-6 -0.2770418 -0.08064955 0 -0.2786871 -0.07944875 -1.81834e-7 -0.2705506 -0.08459568 0 -0.284962 -0.07373738 0 -0.29 -0.06699997 1.94747e-4 -0.285647 -0.07296431 0 -0.282066 -0.07663226 0 -0.281303 -0.07730668 0 -0.2889902 -0.06857985 4.10738e-7 -0.286969 -0.07135885 0 -0.287607 -0.07052659 0 -0.29 -0.06699997 0 0.02451848 -0.1103794 0.04472666 0.001403689 -0.1109676 0.044716 -0.288229 -0.06967461 0 -0.286316 -0.0721715 0 -0.284262 -0.07449066 0 -0.283546 -0.07522428 0 -0.282814 -0.07593816 0 -0.280531 -0.0779674 0 -0.279748 -0.07861346 0 -0.274598 -0.08226495 0 -0.2726376 -0.08344584 0 -0.2679904 -0.08588606 0 -0.257153 -0.09027367 0 -0.06816345 -0.109388 0.04902315 -0.0449838 -0.110737 0.04776257 -0.04498445 -0.109775 0.04983937 -0.160546 -0.105309 0.03500479 -0.160545 -0.10618 0.03114396 -0.137518 -0.108369 0.03483486 -0.234353 -0.0957539 0.02217245 -0.2341009 -0.09587389 0.02191448 -0.2294009 -0.09629857 0.02461677 -0.257153 -0.0902118 0.01450777 -0.235446 -0.09524691 0.02309107 -0.235161 -0.0953772 0.02287775 0.08520168 -0.108376 0.02838259 0.0707302 -0.108907 0.0430423 -0.29 -0.06681597 0.004784107 -0.2453359 -0.09122365 0.02591198 -0.256189 -0.0889486 0.02174025 -0.255956 -0.08892738 0.02203696 -0.252628 -0.08918839 0.02447658 -0.254268 -0.08896386 0.02355289 -0.253628 -0.08903479 0.02395707 -0.29 -0.06657487 0.006162285 -0.29 -0.06641787 0.00684154 -0.252966 -0.08913117 0.02431446 -0.253301 -0.08907979 0.02414166 -0.252286 -0.08925056 0.02462869 -0.29 -0.06602656 0.008184731 -0.29 -0.06623446 0.007516324 -0.251242 -0.08946818 0.02502447 -0.250889 -0.08955007 0.02513736 -0.273364 -0.0805335 0.02019679 -0.29 -0.06554538 0.009493768 -0.29 -0.06579691 0.008843898 -0.250535 -0.0896359 0.02524185 -0.250179 -0.08972549 0.02533787 -0.249822 -0.08981919 0.02542525 -0.249464 -0.08991599 0.02550506 -0.29 -0.06527167 0.01013779 -0.29 -0.06497615 0.01077109 -0.248387 -0.09022569 0.02569866 -0.251955 -0.08447396 0.03153336 -0.273364 -0.07929825 0.02240669 -0.248027 -0.09033447 0.02574878 -0.247667 -0.09044629 0.02579158 -0.273364 -0.07785558 0.02446067 -0.29 -0.06395709 0.0126006 -0.2471227 -0.09062272 0.02584797 -0.246389 -0.09086066 0.02589088 -0.273364 -0.07626467 0.02630519 -0.29 -0.06275135 0.01431155 -0.29 -0.06432068 0.01200056 -0.29 -0.06465929 0.01139199 -0.29 -0.0613752 0.01588797 -0.245871 -0.09103769 0.02590745 -0.20644 -0.06671077 0.0459823 -0.229243 -0.05948227 0.04317766 -0.2442685 -0.09160709 0.02587854 -0.2292259 -0.05682927 0.04278194 -0.206431 -0.06385517 0.04579216 -0.2431908 -0.0920093 0.02578955 -0.243731 -0.09180599 0.02584058 -0.242673 -0.09220749 0.02572625 -0.236035 -0.09498035 0.02348679 -0.236338 -0.09484499 0.02367055 -0.206504 -0.0928598 0.03930938 -0.183556 -0.09673351 0.04133147 -0.206496 -0.0891813 0.04222667 -0.1144469 -0.105453 0.04863744 -0.137519 -0.103778 0.0458973 0.001376271 -0.108066 0.05203539 0.001376211 -0.108884 0.05110758 0.02453279 -0.1085 0.05054277 -0.09132337 -0.106817 0.05039554 0.08532106 -0.108267 0.04394817 0.08538866 -0.108206 0.0443263 -0.114448 -0.102962 0.05142205 -0.0913245 -0.1046 0.05283796 -0.114449 -0.100094 0.05374276 0.001376152 -0.110229 0.04878455 0.02453237 -0.109682 0.04851979 0.001376211 -0.109606 0.05004125 -0.06816446 -0.107856 0.05134707 -0.04498577 -0.107109 0.05325555 -0.04498505 -0.108557 0.05166667 -0.06816256 -0.110563 0.04641538 0.08523327 -0.1083469 0.04317975 0.08527046 -0.108313 0.04356485 -0.06816178 -0.111336 0.04350358 -0.09132045 -0.110869 0.04108428 -0.0681588 -0.1116177 0.04003554 0.08520162 -0.108376 0.04199242 -0.0681681 -0.1116201 0.01968401 -0.09007942 -0.1111986 0.01375442 -0.0217992 -0.111172 0.04662674 0.001376152 -0.1107259 0.04720807 -0.0217995 -0.110601 0.04854559 -0.137518 -0.1074399 0.03877735 -0.160548 -0.103831 0.03869634 -0.09238493 -0.1111294 0.01421248 -0.09132307 -0.111161 0.01765656 -0.160555 -0.09312421 0.04969078 -0.160557 -0.08969795 0.05118668 -0.137518 -0.105892 0.04249864 -0.1605499 -0.101793 0.04209715 -0.183561 -0.09046596 0.04601067 -0.160554 -0.0963484 0.04765439 -0.1605409 -0.106431 0.01943176 -0.1768975 -0.1045935 0.01832479 -0.1656001 -0.1058834 0.01777648 -0.183549 -0.102726 0.03113436 -0.183551 -0.101301 0.03480637 -0.206528 -0.09988868 0.02786117 -0.183547 -0.10354 0.02737969 -0.1970962 -0.101971 0.01930397 -0.1835449 -0.10377 0.02367848 -0.203427 -0.101063 0.0196107 -0.206542 -0.100979 0.02011907 -0.206513 -0.09595406 0.0357846 -0.234613 -0.0956313 0.02241915 -0.233864 -0.09598857 0.02164286 -0.206535 -0.100745 0.02389395 -0.2277461 -0.09720033 0.02078753 -0.233639 -0.09609919 0.02135866 -0.233425 -0.09620577 0.02106189 -0.183553 -0.09928178 0.0382508 -0.09132963 -0.111159 0.03727942 -0.04498326 -0.111406 0.04537135 -0.08970141 -0.1112083 0.01360607 -0.02178382 -0.1114263 0.04386323 -0.0449602 -0.111675 0.04226863 0.04770517 -0.1096863 0.04410278 -0.09046459 -0.1111871 0.01388025 0.04767161 -0.1096869 0.00711888 -0.08924108 -0.111222 0.01338338 -0.06815856 -0.11162 0.01293259 -0.08942461 -0.111217 0.01347786 0.06524032 -0.1091896 0 -0.088723 -0.111236 0.01306074 -0.08889257 -0.111232 0.01317727 -0.08906179 -0.111227 0.01328229 -0.0885545 -0.111241 0.01293319 -0.02180898 -0.1114272 0.00700128 0.001376152 -0.110968 0.007197976 -0.08839988 -0.111245 0.01280188 -0.08787316 -0.111259 0.01217907 -0.08777809 -0.111262 0.01200395 -0.08798575 -0.111256 0.01234757 -0.04497945 -0.1116772 0.006647944 -0.08769696 -0.111264 0.01181447 -0.08760118 -0.111267 0.01141798 -0.08763778 -0.111266 0.01161837 -0.02159136 -0.111318 0 -0.08758926 -0.111267 0.01121735 -0.06815838 -0.111621 0.006170094 -0.05655598 -0.1114708 0 -0.06988096 -0.111422 0 -0.03893512 -0.1114461 0 -0.08758974 -0.1112753 0 -0.08758956 -0.111267 0.005353629 -0.007944405 -0.111147 0 0.00519365 -0.1109282 0 -0.08825457 -0.111249 0.01266276 -0.0217998 -0.109835 0.05014526 0.04767096 -0.109454 0.04644978 0.02453225 -0.110143 0.04710096 0.08521395 -0.1083643 0.04271513 0.2786812 -0.0991885 0.0302326 0.2835146 -0.09892284 0.02503824 0.04767119 -0.108997 0.04785728 0.02453255 -0.109126 0.04962015 0.486922 -0.08045756 0.02522957 0.51 -0.07969349 0.02263969 -0.114446 -0.108988 0.0419442 -0.114445 -0.109911 0.03817445 -0.11445 -0.09694761 0.05555605 0.4666329 -0.07134431 0.03076982 0.4420859 -0.07355797 0.03254157 -0.1144426 -0.1102008 0.03416085 -0.1028434 -0.1107141 0.01472324 -0.0449866 -0.105459 0.05459749 -0.13752 -0.0913642 0.05477017 -0.114451 -0.09361499 0.05684417 0.04767137 -0.108447 0.04894858 -0.09132796 -0.09628748 0.05760127 -0.137519 -0.101173 0.04888397 -0.13752 -0.08776766 0.05562686 -0.114452 -0.09017169 0.0576092 -0.02180075 -0.106595 0.05376517 -0.02180039 -0.107822 0.05273199 -0.09132915 -0.09318017 0.0582841 -0.06816858 -0.09906738 0.05737739 0.3020705 -0.07500588 0.04172265 0.2789337 -0.07286411 0.04307925 0.02453297 -0.107803 0.05134665 0.001376271 -0.107145 0.05284935 -0.1375289 -0.1086449 0.03077214 -0.13752 -0.08415699 0.05594128 -0.160562 -0.08266139 0.05254828 -0.236645 -0.0947085 0.02384519 -0.237273 -0.09443247 0.02416825 -0.236957 -0.09457075 0.02401065 -0.16056 -0.08617538 0.05213397 -0.2375929 -0.09429347 0.02431768 -0.2379159 -0.09415388 0.02445906 -0.183558 -0.0937547 0.04394167 -0.2064869 -0.08516138 0.04438889 -0.23857 -0.09387385 0.02471995 -0.238241 -0.09401398 0.02459329 -0.02180147 -0.10369 0.05532544 0.00137633 -0.104902 0.05416464 0.2816616 -0.05507862 0.04295343 0.2557736 -0.05202686 0.04440093 0.02453368 -0.105081 0.05326747 0.02453398 -0.1037819 0.05373537 0.002249896 -0.1015135 0.05489534 -0.06817066 -0.07303911 0.05783462 -0.2063969 -0.05349725 0.04529815 0.2905175 -0.04831433 0.04240071 0.4691514 -0.04393219 0.03036922 0.463893 -0.04446786 0.03084105 0.1402996 -0.03337162 0.05037546 0.1171168 -0.03772664 0.05123841 0.1401281 -0.04102391 0.05029457 0.278946 -0.04101115 0.04295969 0.278947 -0.03806668 0.04289758 0.255796 -0.03831458 0.04434847 0.231088 -0.05158197 0.04569798 0.2292201 -0.04818361 0.04581421 0.350032 -0.0428915 0.03850287 0.419425 -0.04378175 0.03390568 0.417221 -0.04368954 0.03404575 0.423834 -0.0439285 0.03361928 0.421629 -0.04386115 0.03376334 0.51 -0.04337292 0.02715319 0.486955 -0.04367446 0.0289908 0.51 -0.04501974 0.02740395 0.371959 -0.03737711 0.03628838 0.302095 -0.03781366 0.04136645 0.302094 -0.04064977 0.04149007 0.4735654 -0.043926 0.03004109 0.4648169 -0.04395562 0.03069233 0.4606003 -0.0439893 0.03100645 0.231591 -0.05480504 0.04565954 0.3020793 -0.06437945 0.04175782 0.440756 -0.07631057 0.03232777 0.4176001 -0.07571995 0.03425675 0.417656 -0.07832056 0.03393656 0.394541 -0.08262526 0.03482395 0.41765 -0.08075857 0.0332393 0.394548 -0.08029955 0.03550249 0.4516939 -0.07796061 0.0308361 0.2758419 -0.08730852 0.04322153 0.302056 -0.08769106 0.04137086 0.2988802 -0.08562165 0.04186153 0.255787 -0.09430611 0.04277968 0.232654 -0.0941475 0.04480916 0.232655 -0.09566497 0.04408735 0.232657 -0.099222 0.04099607 0.232656 -0.09817999 0.04218119 0.212962 -0.09968745 0.04259186 0.209527 -0.09695446 0.04533559 0.232656 -0.09699881 0.04320907 0.2326599 -0.09964966 0.04039984 0.23726 -0.0992124 0.04039996 0.222881 -0.09995836 0.04115569 0.227837 -0.100094 0.04039996 0.255789 -0.08871608 0.04437476 0.2550619 -0.0848574 0.0444262 0.325173 -0.0914334 0.03735387 0.302049 -0.09136366 0.03994488 0.302046 -0.09290009 0.03890526 0.255783 -0.100427 0.03195399 0.286317 -0.09876906 0.02555769 0.288344 -0.09865766 0.02591466 0.294366 -0.09832549 0.0268712 0.296354 -0.09821546 0.027152 0.290361 -0.09854656 0.02625256 0.292368 -0.09843587 0.02657145 0.255784 -0.1002089 0.03451275 0.235629 -0.10125 0.03601574 0.235674 -0.1013399 0.03550779 0.235747 -0.101486 0.03138726 0.2550762 -0.1004638 0.02874946 0.235747 -0.1014862 0.01623308 0.273582 -0.09946566 0.02305376 0.275713 -0.09934955 0.02352029 0.277858 -0.09923249 0.02396535 0.265197 -0.09992027 0.02097278 0.267272 -0.09980809 0.02152526 0.271464 -0.09958076 0.02256578 0.269361 -0.09969496 0.02205628 0.25503 -0.100467 0.01788848 0.257035 -0.100359 0.01854825 0.261088 -0.100142 0.01980346 0.259055 -0.100251 0.01918655 0.253039 -0.100573 0.01720708 0.249098 -0.100783 0.01578009 0.251061 -0.100678 0.01650434 0.247149 -0.100886 0.01503437 0.2394919 -0.10129 0.01183664 0.241385 -0.101191 0.01266825 0.243292 -0.10109 0.01347845 0.245214 -0.100989 0.01426714 0.235747 -0.101486 0.01010894 0.237613 -0.101389 0.01098346 0.486915 -0.0858612 0.01804387 0.470484 -0.08715927 0.01868867 0.47228 -0.08711028 0.0183413 0.280018 -0.09911435 0.02438896 0.235754 -0.1015 0.03190445 0.2357562 -0.1015043 0.0327391 0.235709 -0.101409 0.03499668 0.235747 -0.101486 0.03397119 0.235733 -0.101458 0.03448557 0.278909 -0.0989651 0.03275817 0.298332 -0.09810578 0.0274136 0.300301 -0.09799635 0.02765619 0.30203 -0.09790009 0.0283553 0.30226 -0.09788739 0.02787977 0.30615 -0.09767049 0.02826958 0.302033 -0.09769618 0.0308907 0.255784 -0.09965986 0.03646957 0.235509 -0.101011 0.03700989 0.235574 -0.10114 0.03651648 0.27891 -0.0984199 0.03475499 0.235435 -0.100861 0.03749597 0.255785 -0.09890526 0.03811055 0.325168 -0.09656226 0.02769678 0.325154 -0.09640675 0.02892005 0.320415 -0.09684425 0.02787768 0.23535 -0.100692 0.03797459 0.329919 -0.09627705 0.02749079 0.278912 -0.09765756 0.03645455 0.255785 -0.09798491 0.03953164 0.2351509 -0.100293 0.03890997 0.235526 -0.100101 0.03922218 0.235255 -0.100502 0.03844594 0.278914 -0.09671396 0.03794455 0.302038 -0.09638619 0.03470057 0.347963 -0.09517288 0.02652865 0.33942 -0.09569668 0.02700358 0.33467 -0.09598851 0.02725976 0.278915 -0.0956012 0.03925895 0.30204 -0.09541487 0.03627425 0.255786 -0.0969128 0.0407747 0.348282 -0.0937891 0.03092867 0.325161 -0.09509527 0.03285604 0.348277 -0.09457707 0.0289945 0.236347 -0.09968036 0.03982526 0.236792 -0.09945237 0.04011619 0.302043 -0.09425157 0.03767669 0.278917 -0.09432107 0.0404067 0.3950244 -0.09212857 0.02394551 0.394507 -0.09195476 0.0247302 0.371394 -0.09326916 0.02689868 0.371399 -0.09247159 0.02892577 0.278923 -0.08935385 0.04274755 0.302053 -0.08963805 0.04077595 0.417644 -0.08309316 0.03214919 0.417638 -0.08524608 0.03068047 0.4507601 -0.0829581 0.028126 0.463823 -0.0871725 0.02031087 0.455964 -0.08782267 0.02063089 0.457793 -0.08771347 0.02046948 0.5099998 -0.07205259 0.02681839 0.486927 -0.07504266 0.02823716 0.51 -0.0733301 0.02641791 0.3712357 -0.06754589 0.03748166 0.3480192 -0.06936097 0.03895097 0.3694826 -0.07993626 0.03746831 0.4514263 -0.08053499 0.02968549 0.51 -0.08043706 0.02192938 0.486919 -0.08273488 0.0230481 0.51 -0.07866168 0.02350324 0.51 -0.0811401 0.02119088 0.4497338 -0.08508908 0.02623242 0.4438942 -0.08710342 0.02452486 0.486917 -0.0845465 0.02059787 0.5100002 -0.082771 0.01909601 0.51 -0.08351117 0.01789653 0.51 -0.08398765 0.01699805 0.474073 -0.08706867 0.01797068 0.479425 -0.08698928 0.0167194 0.486913 -0.08671605 0.01550829 0.477645 -0.08700829 0.0171597 0.51 -0.08441656 0.016088 0.51 -0.0849148 0.01482349 0.481201 -0.08697789 0.01625579 0.51 -0.08548921 0.0128712 0.4829744 -0.08697396 0.01576852 0.5099998 -0.08574676 0.01157695 0.4879584 -0.08687078 0.01380699 0.5099999 -0.08592426 0.01018291 0.4963446 -0.08669531 0.01050591 0.51 -0.08598679 0.009180605 0.5100001 -0.08600121 0.008480012 0.4983372 -0.08665621 0.009721934 0.4985937 -0.0866416 0.009436964 0.4990024 -0.08661824 0.008972883 0.4994636 -0.08659195 0.008434414 0.4998618 -0.08656924 0.007955551 0.5001335 -0.08655387 0.00762242 0.5003243 -0.08654296 0.007384598 0.5005148 -0.08653217 0.007143914 0.5007597 -0.08651822 0.006829977 0.5011709 -0.08649486 0.006290435 0.5014936 -0.08647656 0.005855023 0.5017263 -0.08646339 0.0055359 0.502013 -0.08644711 0.005133628 0.5023762 -0.08642661 0.004611849 0.5027548 -0.08640521 0.004051685 0.5031281 -0.08638411 0.003482043 0.5034837 -0.08636409 0.002922415 0.51 -0.08599972 0 0.5038354 -0.08634424 0.002351701 0.5040652 -0.08633136 0.001969158 0.5042604 -0.0863204 0.001638829 0.5045728 -0.08630287 0.00109601 0.5048362 -0.08628815 6.25876e-4 0.5050062 -0.08627861 3.15499e-4 0.5051758 -0.08626914 0 0.51 -0.08522677 0.01384949 0.475861 -0.0870347 0.01757675 0.468683 -0.0872159 0.01901274 0.51 -0.08200585 0.0201525 0.3928706 -0.07789462 0.03593313 0.51 -0.07783925 0.02410489 0.3222003 -0.08382141 0.04044973 0.325186 -0.08594346 0.03995978 0.348312 -0.08412188 0.03851234 0.486924 -0.07783597 0.02698785 0.51 -0.07581454 0.02533543 0.3248597 -0.07103163 0.04037272 0.3457183 -0.0819239 0.03898745 0.51 -0.07071608 0.02713745 0.486929 -0.072241 0.02897524 0.2337251 -0.07166236 0.04554647 0.2557867 -0.06816226 0.04439502 0.305956 -0.04396325 0.04137098 0.325236 -0.04308348 0.04012358 0.437064 -0.04412394 0.03271806 0.46389 -0.04685157 0.03109699 0.4767436 -0.04393666 0.02980947 0.486954 -0.04594606 0.02929216 0.495241 -0.03060024 0.02034616 0.495241 -0.03034007 0.01999998 0.351582 -0.02838778 0.03651589 0.351101 -0.02794647 0.03649157 0.359917 -0.03345584 0.03659045 0.359319 -0.03319329 0.03659588 0.255795 -0.02649217 0.04428887 0.348374 -0.03989118 0.0383386 0.1178236 -0.01537668 0.05128496 0.434859 -0.04411226 0.0328722 0.430449 -0.04406619 0.03317588 0.325238 -0.03755587 0.03975236 0.302095 -0.03505879 0.04123115 0.3755325 -0.03827953 0.03616559 0.3770962 -0.03864812 0.03610873 0.3707802 -0.04749149 0.03749012 0.255796 -0.03231245 0.04431396 0.232646 -0.03226196 0.04575848 0.255796 -0.03530275 0.04433155 0.3783437 -0.03893172 0.03606212 0.3796091 -0.03920966 0.03601366 0.415017 -0.04358357 0.0341838 0.1166708 -0.03073281 0.05128705 0.383786 -0.04005676 0.03584438 0.232646 -0.03542464 0.04572755 0.371501 -0.0420807 0.03698295 0.278947 -0.03518068 0.04282969 0.140152 -0.02679795 0.05043196 0.3866986 -0.0405867 0.03571814 0.3850984 -0.04030233 0.03578841 0.3879892 -0.04080599 0.03565996 0.3892155 -0.04100561 0.03560352 0.347995 -0.02414298 0.03564095 0.347787 -0.02379715 0.03547769 0.325214 -0.02260005 0.03756594 0.347408 -0.02310377 0.03510087 0.347073 -0.02243065 0.03466176 0.347235 -0.02276426 0.03488898 0.48279 -0.0290668 0.01999998 0.457889 -0.02652007 0.01999998 0.486936 -0.0279147 0.01726758 0.5100001 -0.02851229 0.01290357 0.486926 -0.02725034 0.01533585 0.486931 -0.02755528 0.016321 0.463842 -0.02606338 0.01823645 0.463825 -0.02547925 0.01595038 0.440728 -0.02410316 0.01861196 0.463834 -0.02573388 0.01713198 0.346432 -0.0208562 0.03329575 0.5100001 -0.02814763 0.01089507 0.486916 -0.02681398 0.01322668 0.486921 -0.02700197 0.01430708 0.440717 -0.02388906 0.01720356 0.4205368 -0.02269995 0.01999998 0.5100002 -0.02908635 0.01484948 0.4401629 -0.02380329 0.0157479 0.4155916 -0.02222943 0.01810419 0.4870901 -0.02670991 0.007446706 0.51 -0.02873569 0.01373594 0.302047 -0.01605498 0.03431385 0.244664 -0.01282227 0.03942304 0.325165 -0.01684486 0.03062778 0.51 -0.0282889 0.01179897 0.3457966 -0.01861941 0.02991455 0.486911 -0.02669548 0.01207959 0.463817 -0.02531456 0.01466798 0.3456975 -0.01813393 0.02861112 0.3456552 -0.01791435 0.02780276 0.345743 -0.01836818 0.02929049 0.463809 -0.02527356 0.01324546 0.3456263 -0.0177505 0.02698272 0.345612 -0.01759362 0.02384036 0.5100001 -0.03014725 0.0172832 0.3948453 -0.02097392 0.00990653 0.3629999 -0.01882916 0.01499998 0.5100001 -0.02799892 0.00640136 0.3941968 -0.02085709 0.01800304 0.394493 -0.02084368 0.02016258 0.5100001 -0.0280019 0.008878111 0.2319329 -0.01018136 0.02999997 0.395562 -0.02101165 0.01999998 0.23195 -0.01018506 0.03395116 0.432987 -0.0239734 0.01999998 0.51 -0.02804678 0.009825885 -0.141793 0.001582264 0.03867429 5.04947e-4 -0.001270532 0.04985564 0.445438 -0.02524667 0.01999998 -0.143903 3.50054e-6 0.04200267 -0.147318 -0.00255233 0.04540276 0.346087 -0.01977467 0.03197097 0.34602 -0.01953399 0.03161299 0.005408048 -0.00367856 0.05256372 0.346242 -0.02029305 0.03265714 0.463851 -0.02646106 0.01927596 0.302066 -0.01895028 0.03799378 0.346538 -0.02115529 0.03359878 0.346333 -0.02056878 0.03298187 0.348214 -0.02449059 0.03578805 0.325227 -0.02547156 0.03860789 0.350034 -0.02685737 0.03639996 0.349747 -0.02653336 0.03635287 0.349196 -0.02586644 0.03622245 0.278939 -0.02178585 0.04212999 0.347592 -0.0234493 0.03529727 0.325235 -0.0286172 0.03898584 0.348372 -0.02914798 0.03695267 0.255793 -0.02053707 0.04385524 0.302082 -0.0229277 0.04023468 0.278941 -0.02345198 0.04248839 0.348444 -0.02483999 0.03591895 0.355828 -0.03141754 0.03662425 0.355266 -0.03108417 0.03662806 0.348375 -0.03056955 0.03717178 0.353628 -0.03000926 0.03661066 0.30209 -0.02625477 0.04079085 0.255794 -0.02225857 0.04419088 0.302086 -0.02451908 0.04062515 -0.04506534 -0.01433545 0.05703997 -0.06816989 -0.01665991 0.05778902 -0.0220552 -0.01217889 0.05601137 0.0015257 -0.01088178 0.05493801 0.02471309 -0.01062339 0.0540511 0.04826438 -0.01120942 0.05331182 0.3639031 -0.03498739 0.0365228 0.360519 -0.0337097 0.03658437 0.358725 -0.03292185 0.03660076 0.255795 -0.02420657 0.04427659 0.349468 -0.02620345 0.03629338 0.325238 -0.03028875 0.03913909 0.352077 -0.02881467 0.03653669 0.350635 -0.02749097 0.03645479 -0.02180618 -0.03382575 0.05598992 0.001362621 -0.03913825 0.05494689 0.163266 -0.0273391 0.04946148 0.02446234 -0.03264552 0.05407637 0.354165 -0.03038024 0.03662157 0.353101 -0.0296247 0.03659278 0.352583 -0.02922695 0.03656458 0.04767549 -0.03411632 0.05336403 0.07080107 -0.03507345 0.05271625 0.325237 -0.04027599 0.03995096 0.35755 -0.03235107 0.03660964 0.354712 -0.03073829 0.03662687 -0.160582 -0.03521871 0.05289232 0.362955 -0.03465205 0.03654336 0.358135 -0.03264158 0.03660517 -0.1879994 -0.04199993 0.04834181 0.02453559 -0.04523414 0.05409634 0.04767537 -0.04605245 0.05339813 0.1630637 -0.04775887 0.0491715 0.09405386 -0.04154372 0.05203056 0.07100039 -0.04871696 0.05274802 0.1171274 -0.04465031 0.05120545 0.395234 -0.0418691 0.03531008 0.3906849 -0.04123425 0.03553438 0.1395416 -0.05096459 0.05023163 0.09434443 -0.04948645 0.05202239 0.399619 -0.04238569 0.03508025 0.397425 -0.04213845 0.0351969 -0.28608 -0.04200297 0.02696585 -0.2024044 -0.04199999 0.04584145 0.00121355 -0.05684149 0.05495393 0.1168838 -0.0535013 0.05118435 0.186738 -0.0552051 0.04793244 0.348367 -0.04823505 0.03893059 0.404012 -0.04281836 0.03483778 0.401814 -0.04261195 0.03496056 0.393046 -0.04157668 0.03541988 -0.289603 -0.04200166 0.02262425 -0.212317 -0.04199999 0.04421496 -0.04469645 -0.06313139 0.05698108 0.0243749 -0.06193119 0.05411863 0.04765611 -0.06469261 0.05342864 0.1630944 -0.05672341 0.04909932 0.1865818 -0.07342147 0.04792433 0.3430956 -0.05080389 0.03933042 0.406211 -0.04300576 0.03471219 0.408411 -0.0431751 0.03458386 0.410612 -0.04332727 0.03445297 0.412814 -0.04346317 0.03431957 0.07052296 -0.06335115 0.05277997 0.1398468 -0.06741029 0.05018395 0.328141 -0.05311745 0.04025375 0.371491 -0.05033469 0.03755265 0.394609 -0.04949557 0.03603994 0.417716 -0.04863178 0.03446429 0.3035058 -0.05353736 0.04170078 0.44081 -0.04774856 0.03281879 0.4405088 -0.05030727 0.03288996 -0.29 -0.05115467 0.0215643 -0.229152 -0.0455482 0.04162859 -0.06813031 -0.06113731 0.05775088 0.3497118 -0.05422478 0.0389375 0.3725896 -0.05324077 0.03750097 0.3953419 -0.05226641 0.03601825 0.4178428 -0.05125623 0.03449219 0.4629585 -0.04931724 0.0312314 0.4854284 -0.04831504 0.02949416 0.51 -0.04651647 0.02749508 -0.273365 -0.06472629 0.03338915 -0.29 -0.0531767 0.02102249 -0.29 -0.05383628 0.02079516 -0.251909 -0.04803669 0.0384013 -0.229165 -0.04763078 0.04175257 0.1169023 -0.08071404 0.05117928 0.09407114 -0.08208429 0.05203318 0.1631538 -0.07490241 0.04909271 0.5099999 -0.05265069 0.02749955 -0.273365 -0.06637358 0.03282207 -0.29 -0.05448955 0.02054446 -0.29 -0.05513137 0.02027189 -0.251912 -0.04993849 0.03843408 -0.273365 -0.06798446 0.03214919 -0.29 -0.05638438 0.01965975 -0.273365 -0.0695827 0.03135615 0.00163114 -0.08373343 0.05493533 0.0245108 -0.08238691 0.05410176 0.1639 -0.0942341 0.04912048 0.2330176 -0.08574765 0.04559957 0.4176906 -0.06069737 0.03441995 -0.29 -0.05576258 0.01997709 -0.251915 -0.05184215 0.03848177 -0.22918 -0.04977917 0.04193365 0.0710045 -0.0860095 0.05275249 0.1401968 -0.08686345 0.05019682 0.2307413 -0.09029668 0.04572534 0.394583 -0.06460195 0.03596293 0.4407026 -0.06178313 0.03277319 0.4877431 -0.05899989 0.0292598 0.4642329 -0.06068986 0.03104734 -0.29 -0.05699676 0.01931989 -0.251919 -0.05377858 0.03854286 -0.29 -0.05984735 0.01731926 -0.29 -0.05874919 0.01817977 -0.273365 -0.07119816 0.03041696 0.04806345 -0.1012775 0.05332976 0.02453416 -0.101948 0.05402916 0.09820157 -0.0965538 0.0518952 0.09467178 -0.09556305 0.05201196 0.1860845 -0.09295243 0.04801946 -0.29 -0.05759316 0.01896095 -0.29 -0.05817729 0.01858085 -0.251922 -0.05578404 0.03861719 -0.22921 -0.05434846 0.04244714 0.04767268 -0.103154 0.05304086 0.1106342 -0.09689295 0.05153244 0.1172729 -0.09411221 0.05118823 0.2297648 -0.09255272 0.04550302 0.255788 -0.0927357 0.04353415 0.51 -0.06121826 0.02749985 -0.29 -0.05930745 0.01775836 -0.251926 -0.05788969 0.03870534 -0.29 -0.06230926 0.01485365 0.09544211 -0.09906315 0.05192691 0.1632789 -0.09635287 0.0488919 0.1402064 -0.09557932 0.05022805 0.1408541 -0.09771877 0.05000185 -0.29 -0.06088209 0.01638245 -0.251929 -0.06012469 0.03880965 -0.29 -0.06317287 0.01375567 -0.29 -0.06357449 0.01318556 -0.240761 -0.09296399 0.02537792 -0.06817078 -0.09348011 0.05821084 -0.0218026 -0.0966764 0.05607789 0.1309874 -0.09744882 0.050601 0.1207399 -0.09716898 0.0511223 0.148254 -0.09792035 0.04948025 0.168208 -0.09846526 0.04781246 0.1731899 -0.09860128 0.04733276 0.186401 -0.09675288 0.04723554 0.51 -0.06869691 0.02742826 0.491177 -0.06916338 0.0289399 0.51 -0.06750297 0.02749526 -0.29 -0.06185048 0.01537907 -0.251933 -0.06261688 0.03893357 -0.244798 -0.09141516 0.02590125 -0.229259 -0.06244617 0.0436483 -0.206477 -0.08104729 0.04576706 -0.04498958 -0.09690219 0.05729997 0.16328 -0.09800529 0.04839396 0.186403 -0.0981974 0.04656046 0.188123 -0.09900909 0.04574304 0.209528 -0.09825277 0.04449218 0.454131 -0.08793956 0.02076905 0.440725 -0.0884934 0.02253997 0.4523469 -0.08806073 0.02088028 0.463848 -0.0742805 0.03067457 0.51 -0.06970405 0.0273084 -0.251937 -0.06561696 0.03907847 -0.229276 -0.06599038 0.0442121 -0.2421489 -0.09241116 0.02565002 -0.2400745 -0.09324425 0.02520418 0.04767245 -0.104443 0.0525738 0.02453345 -0.10613 0.0527029 0.09256356 -0.1016806 0.05143624 0.09202826 -0.1021681 0.05126744 0.153246 -0.09805667 0.04910099 0.193095 -0.09914487 0.04516297 0.255788 -0.09092098 0.04409128 0.417627 -0.08865326 0.0268743 0.5099999 -0.07458335 0.02592378 -0.25194 -0.06907176 0.03894335 -0.229293 -0.0700646 0.04446876 -0.2390825 -0.09365725 0.02490246 0.08798336 -0.105846 0.04886335 0.07079899 -0.1069509 0.04907125 0.08775067 -0.106058 0.04863417 0.00137633 -0.106103 0.05355966 -0.02180105 -0.105223 0.05463069 0.04767215 -0.105482 0.05201107 0.02453327 -0.107022 0.05206215 0.09094613 -0.103152 0.05084043 0.07079929 -0.104401 0.05136805 0.0938211 -0.1005374 0.05173349 0.158236 -0.09819298 0.04869657 0.1863999 -0.09506177 0.04774218 0.394518 -0.09002596 0.02887535 0.417621 -0.08981961 0.02472394 0.325181 -0.08797246 0.03934395 0.371433 -0.082237 0.03702718 -0.251944 -0.07284456 0.03824675 -0.22931 -0.07452267 0.04405158 -0.04498726 -0.103633 0.05568307 0.04767197 -0.106366 0.05137336 0.08987736 -0.1041234 0.05028676 0.07079917 -0.105359 0.05069476 0.09042537 -0.1036256 0.05058866 0.163223 -0.09832906 0.04826706 0.17817 -0.09873729 0.04682797 0.209526 -0.0954765 0.0460301 0.394512 -0.09114706 0.02685505 0.371404 -0.09139305 0.03082156 0.278921 -0.09122908 0.04217237 0.278919 -0.09286928 0.04138255 0.348306 -0.0862419 0.03787535 0.371427 -0.08445626 0.03636896 0.461439 -0.08751749 0.02007687 0.463256 -0.08743077 0.01984566 0.51 -0.07699102 0.02466571 -0.251948 -0.07683217 0.03683078 -0.229326 -0.07923799 0.04277515 -0.137519 -0.09486287 0.05335634 0.08881962 -0.1050855 0.04957669 0.07079905 -0.106202 0.04993289 0.08934277 -0.1046103 0.04995101 0.183148 -0.09887325 0.04629808 0.203034 -0.09941625 0.04392755 0.1980659 -0.09928065 0.04455786 0.325177 -0.08979749 0.03846657 0.348301 -0.08817911 0.0369479 0.371421 -0.08651667 0.03538864 0.394535 -0.0848186 0.03378909 -0.251952 -0.08081507 0.03458416 -0.229342 -0.0839529 0.04051029 -0.235737 -0.09511458 0.02329415 -0.137519 -0.09816676 0.05138659 0.04767155 -0.107828 0.04986387 0.0875234 -0.106264 0.04839479 0.08730179 -0.106466 0.04814517 0.08833873 -0.105523 0.04918634 0.255786 -0.09568989 0.04185646 0.348286 -0.09274989 0.03270715 0.348296 -0.08992797 0.03575408 0.371415 -0.0883904 0.03410744 0.394529 -0.08682745 0.03241574 0.459618 -0.08761167 0.02028477 -0.229358 -0.08830147 0.03728038 -0.160552 -0.09926956 0.04510688 -0.0218001 -0.108904 0.05152899 0.0866813 -0.10703 0.04733204 0.07079887 -0.107618 0.04808294 0.08649188 -0.107203 0.04703944 0.08708786 -0.10666 0.04788488 0.04767179 -0.107139 0.0506621 0.207999 -0.09955185 0.04327225 0.325157 -0.0958743 0.03100836 0.325169 -0.0928694 0.03603136 0.348291 -0.09145998 0.03432655 0.37141 -0.09002876 0.03256589 0.394523 -0.08858108 0.03075289 0.417632 -0.08712249 0.02889096 -0.160542 -0.106431 0.02335238 -0.183543 -0.103769 0.02010399 0.08598208 -0.107666 0.04609668 0.08583408 -0.107801 0.04576027 0.08631026 -0.107368 0.04673558 0.217923 -0.09982287 0.04188627 0.325165 -0.09409195 0.0345267 -0.1376392 -0.1086394 0.01799821 -0.1504347 -0.1074099 0.01703977 -0.1406239 -0.1082738 0.01656281 -0.1144429 -0.110203 0.02059012 -0.09085476 -0.1111749 0.01398485 0.08558166 -0.10803 0.04506069 0.08614009 -0.107522 0.04642128 0.0868805 -0.106849 0.04761385 0.235925 -0.0998966 0.03952729 0.302035 -0.09715658 0.03293156 0.407757 -0.09125787 0.02325677 0.4206163 -0.09035855 0.02256411 0.4377297 -0.08913117 0.02164983 0.466878 -0.08727997 0.01931369 -0.239571 -0.09345287 0.02505809 -0.218439 -0.09874737 0.02033728 -0.1582379 -0.1066499 0.01741886 0.08547639 -0.108126 0.04469639 0.3609473 -0.09436231 0.02581071 0.3777646 -0.09327733 0.02488654 0.465069 -0.08735156 0.01959127 -0.2348819 -0.09550589 0.02265447 -0.213438 -0.09954416 0.02009528 -0.185888 -0.1034795 0.01876074 -0.12545 -0.1094218 0.01582449 -0.1136656 -0.1101582 0.01525074 -0.0916441 -0.1111521 0.01413613 0.315661 -0.09712296 0.02803349 -0.208434 -0.100316 0.01985305 -0.160543 -0.106432 0.02725064 -0.09204787 -0.1111396 0.01418542 0.30421 -0.09777879 0.02808415 0.310906 -0.0973984 0.02816408 -0.133033 -0.108874 0.01619356 -0.09124982 -0.1111641 0.01407015 0.04951411 -0.1097593 0 0.03221422 -0.1102933 0 0.02453082 -0.110379 0.007227301 0.01857906 -0.110641 0 0.263135 -0.100032 0.02039885 -0.0881173 -0.111253 0.01251316 0.334 -0.01690888 0 0.318 -0.04202926 0 0.318 -0.01582509 0 0.334 -0.04255306 0 0.3135254 -0.04188275 0.004974961 0.313 -0.04186558 0.004999995 0.3130004 -0.0154848 0.005009293 0.3143938 -0.04191124 0.004809916 0.3140232 -0.01555371 0.004896521 0.3152776 -0.01563894 0.00445497 0.3152244 -0.04193842 0.004481494 0.3147178 -0.01560091 0.004699945 0.315838 -0.04195851 0.004119694 0.3159217 -0.01568281 0.004060149 0.316392 -0.04197657 0.003677845 0.316873 -0.04199236 0.003166437 0.3169259 -0.0157513 0.003100514 0.3164223 -0.01571691 0.003650844 0.3173211 -0.01577836 0.00252074 0.317548 -0.04201447 0.002077758 0.3172851 -0.04200583 0.002582252 0.317633 -0.01579982 0.001888751 0.3177386 -0.04202067 0.001603662 0.317885 -0.04202544 0.001063942 0.317798 -0.0158112 0.001404941 0.3179292 -0.01582014 8.56478e-4 0.3179703 -0.04202824 5.68769e-4 0.318 -0.04202926 0 0.3180068 -0.01582562 2.47705e-7 + + + + + + + + + + 0 0 1 0 0 1 -0.02347064 -0.9997246 0 -0.02347064 -0.9997246 0 -0.02347064 -0.9997246 0 -0.02347064 -0.9997246 0 -0.02777248 -0.8428809 -0.5373831 -0.02771151 -0.8505423 -0.5251761 -0.030519 -0.9272297 -0.3732479 -0.02511727 -0.7703053 -0.6371805 -0.03143477 -0.9629428 -0.2678673 -0.03222805 -0.9799656 -0.1965425 -0.03241133 -0.9915376 -0.1257085 1 0 0 1 -2.66963e-4 0 1 1.20703e-4 0 1 -1.15836e-4 0 1 -2.98126e-4 0 1 -4.60952e-4 0 -0.9845418 0.1751483 7.32455e-4 -0.9989218 0.04641956 -7.62978e-4 -0.9984812 -0.05508625 9.15562e-4 -0.9060589 0.423151 8.24023e-4 -0.9731415 0.2302078 -3.05194e-4 -0.7977272 0.6030182 -7.62966e-4 -0.7648358 0.6442248 7.62974e-4 -0.6003711 0.7997216 2.13633e-4 -0.6202111 0.7844349 -5.79865e-4 -0.2497672 0.9683058 -3.96747e-4 -0.273177 0.9619638 1.83115e-4 -0.09772074 0.9952139 4.88299e-4 -0.4319133 0.9019151 -1.83118e-4 0.426476 0.9044989 1.83115e-4 0.4018496 0.9157056 -4.88311e-4 0.2581583 0.9661025 5.49338e-4 0.7517594 0.6594375 3.05196e-4 0.765465 0.6434776 -3.66237e-4 0.5957041 0.803204 -2.74673e-4 0.9061745 0.4229038 -5.49345e-4 0.893473 0.449117 3.66228e-4 0.9860391 0.1665118 -8.85052e-4 0.9712823 0.2379298 5.4935e-4 0.9986147 0.05261486 6.40901e-4 0.9954794 -0.09497612 -6.40906e-4 0.8592087 -0.5116249 6.10385e-4 0.9500538 -0.3120864 0 0.9507322 -0.3100134 0 0.7758113 -0.6309647 -6.71434e-4 0.6977368 -0.7163537 8.85065e-4 0.4826963 -0.8757874 8.54546e-4 0.6506934 -0.7593407 -3.05189e-4 0.2393027 -0.9709447 8.54544e-4 0.2992392 -0.954178 -7.01938e-4 0.0878635 -0.9961323 -7.01931e-4 0.01596158 -0.9998725 6.40905e-4 -0.09778416 -0.9952076 -5.49349e-4 -0.1774402 -0.9841313 6.71429e-4 -0.3901884 -0.9207347 7.62981e-4 -0.2740318 -0.9617205 -6.71422e-4 -0.448873 -0.8935954 -5.49341e-4 -0.609218 -0.7930027 5.18821e-4 -0.6305283 -0.7761663 -2.74674e-4 -0.7715777 -0.6361351 2.44151e-4 -0.7762624 -0.63041 3.05195e-5 -0.8795777 -0.4757551 4.5778e-4 -0.8612666 -0.5081534 -3.05197e-5 -0.9289157 -0.3702905 -7.01944e-4 -0.9610211 -0.276474 9.15578e-4 -0.9858531 -0.1676099 -9.15568e-4 0.4982836 -0.8670141 -2.13633e-4 0.8764137 -0.481559 -1.83114e-4 0.9917271 -0.1283645 1.83116e-4 0.58669 0.8098117 3.05186e-5 0.1885451 0.9820643 -7.6297e-4 0.08145415 0.9966769 6.7141e-4 -0.03473025 0.9993966 -6.71412e-4 -0.4403642 0.8978192 0 -0.9129499 0.4080716 -2.13634e-4 -0.9952346 0.09750914 2.74674e-4 -0.9980905 -0.06177026 -2.7467e-4 -0.9970334 -0.0769695 2.74673e-4 -0.8293833 0.5586801 1.83114e-4 -0.7242737 0.6895127 2.7467e-4 -0.8216876 0.5699382 -2.74669e-4 -0.8982575 0.4394696 -1.83112e-4 -0.5975067 0.8018639 2.74674e-4 -0.7137437 0.700407 -2.74669e-4 -0.3157791 0.9488328 2.7467e-4 -0.3013476 0.9535145 -2.74674e-4 -0.45773 0.8890913 -2.74675e-4 -0.005859613 0.9999827 4.88303e-4 -0.131386 0.9913312 -3.96752e-4 -0.1511604 0.9885092 2.74671e-4 0.2695416 0.9629886 5.49337e-4 0.4009245 0.9161111 5.18818e-4 0.3543588 0.9351093 -6.40904e-4 0.5070081 0.8619412 -4.57781e-4 0.6488162 0.7609453 -2.74676e-4 0.6422355 0.7665075 3.05187e-5 0.7614217 0.6482568 2.74672e-4 0.8597681 0.5106847 2.74677e-4 0.7711103 0.6367016 -2.74677e-4 0.9733507 0.2293217 -2.74673e-4 0.970112 0.2426577 1.83115e-4 0.9970194 0.07715153 2.74669e-4 0.929609 0.3685475 -1.83114e-4 0.9957236 -0.09238201 2.74674e-4 0.9980829 0.06189185 -2.74668e-4 0.8330161 -0.5532484 7.32456e-4 0.724214 -0.689575 7.32454e-4 0.8042679 -0.5942665 -7.32457e-4 0.8951035 -0.445858 -7.32466e-4 0.5977709 -0.8016667 6.71413e-4 0.6887927 -0.7249581 -7.32466e-4 -0.02771115 -0.9996157 7.93491e-4 0.03219801 -0.9994811 -9.46103e-4 0.1461537 -0.9892615 9.46078e-4 -0.2008149 -0.979629 7.62975e-4 -0.1406009 -0.9900662 -7.01936e-4 -0.3677306 -0.929932 9.15588e-4 -0.2881933 -0.9575721 -8.2402e-4 -0.4514079 -0.8923172 -0.001068115 -0.5194375 -0.8545082 7.935e-4 -0.6181113 -0.7860905 -4.27273e-4 -0.6424661 -0.7663142 1.52598e-4 -0.7611964 -0.6485215 1.83112e-4 -0.7483263 -0.6633308 -1.83114e-4 -0.8598669 -0.5105183 2.13632e-4 -0.8523314 -0.5230022 -3.96745e-4 -0.9250386 -0.3798732 0 -0.9277341 -0.3732421 -1.83111e-4 -0.9701892 -0.2423489 1.83112e-4 -0.9733948 -0.2291346 -2.74669e-4 0.2278517 -0.9736953 -0.001068115 0.3159072 -0.9487898 9.15585e-4 0.399459 -0.9167506 -9.1556e-4 0.5525854 -0.833456 -6.71428e-4 0.4699686 -0.8826829 7.62986e-4 0.9163902 -0.4002856 7.32453e-4 0.9590205 -0.2833359 -7.32449e-4 0.9704844 -0.2411637 5.49348e-4 0.9936732 -0.1123105 -3.96749e-4 0.925002 0.3799622 1.83114e-4 0.8666384 0.4989367 -1.83118e-4 0.5248703 0.8511822 1.83116e-4 0.2093331 0.9778442 -6.71429e-4 0.1332471 0.9910826 6.71424e-4 0.04272598 0.9990866 -6.71409e-4 -0.4698119 0.8827666 1.83115e-4 -0.5865119 0.8099407 -1.83113e-4 -0.9041551 0.4272046 2.74671e-4 -0.9590646 0.2831873 -2.74672e-4 -0.9632257 0.2686936 2.74675e-4 -0.9936664 0.1123707 -2.74671e-4 -0.02347069 -0.9997246 0 -0.02347069 -0.9997246 0 0 0 1 1.21501e-7 0 1 -2.27703e-5 0 1 1.41513e-6 0 1 1.42545e-5 0 1 4.81725e-7 0 1 -2.27443e-7 0 1 -4.5884e-7 0 1 2.20291e-6 0 1 -2.77948e-6 0 1 1.18999e-6 0 1 -4.0977e-7 0 1 -1.50694e-6 0 1 -7.50472e-7 0 1 2.06773e-6 0 1 -3.14885e-6 0 1 -2.19311e-6 0 1 3.02915e-6 0 1 1.19162e-6 0 1 -3.97295e-6 0 1 1.43339e-6 0 1 -1.33673e-6 0 1 1.24255e-6 0 1 -1.47614e-6 0 1 -1.60901e-5 0 1 8.14855e-6 0 1 -1.93221e-6 0 1 3.94463e-6 0 1 -2.05367e-6 0 1 3.43797e-6 0 1 -3.17479e-6 0 1 7.40813e-7 0 1 -6.39036e-7 0 1 1.20963e-7 0 1 -2.24377e-6 0 1 -6.68812e-7 0 1 1.49624e-6 0 1 3.89069e-7 0 1 -1.09462e-6 0 1 2.70696e-6 0 1 1.27571e-5 0 1 -2.91211e-6 0 1 -4.45898e-7 0 1 1.35807e-6 0 1 -1.28676e-6 0 1 4.25686e-7 0 1 -2.69881e-7 0 1 -2.58742e-7 0 1 -6.04688e-7 0 1 6.47494e-7 0 1 3.30768e-7 0 1 -5.2697e-7 0 1 -2.09297e-7 0 1 4.89341e-7 0 1 -8.04461e-6 0 1 1.94857e-7 0 1 1.23606e-5 0 1 -1.23119e-5 0 1 -8.73414e-6 0 1 0 0 1 4.23025e-7 0 1 1.10663e-6 0 1 -6.74121e-7 0 1 -6.53397e-7 0 1 0 0 1 -3.04118e-7 0 1 -3.17984e-7 0 1 6.92831e-6 0 1 1.33154e-5 0 1 2.27154e-5 0 1 1.01838e-5 0 1 -4.07943e-6 0 1 -4.02718e-6 0 1 -1.58518e-5 0 1 7.76835e-6 0 1 7.16913e-6 0 1 -5.51927e-6 0 1 1.10952e-5 0 1 7.07475e-6 0 1 -4.1722e-6 0 1 5.27222e-6 0 1 5.64389e-6 0 1 -6.75945e-6 0 1 -2.57784e-6 0 1 -5.74829e-6 0 1 1.42258e-6 0 1 5.74132e-6 0 1 -3.39321e-6 0 1 3.19709e-7 0 1 1.58896e-7 0 1 6.32874e-7 0 1 6.81697e-7 0 1 3.65767e-7 0 1 -3.90011e-7 0 1 -4.79508e-7 0 1 4.28709e-7 0 1 -1.89381e-5 0 1 -2.61706e-5 0 1 -5.26641e-6 0 1 -5.18147e-6 0 1 1.02199e-5 0 1 6.44555e-6 0 1 -4.60101e-5 0 1 2.23418e-5 0 1 -1.59966e-5 0 1 1.58077e-5 0 1 -7.58877e-6 0 1 -3.69456e-6 0 1 3.45349e-6 0 1 -2.85902e-6 0 1 3.3969e-6 0 1 -7.01868e-6 0 1 6.73997e-6 0 1 -8.32833e-6 0 1 3.00782e-5 0 1 1.27048e-5 0 1 -2.50229e-5 0 1 1.0623e-5 0 1 -7.47703e-6 0 1 2.50131e-5 0 1 2.39722e-5 0 1 -2.41594e-5 0 1 1.21126e-5 0 1 1.10914e-5 0 1 8.90033e-6 0 1 2.65938e-5 0 1 -1.7226e-5 0 1 -5.30099e-6 0 1 7.99628e-5 0 1 3.17897e-5 0 1 -9.18518e-6 0 1 -1.36886e-5 0 1 -1.45346e-5 0 1 -2.71179e-6 0 1 2.2366e-6 0 1 1.50873e-6 0 1 -2.69746e-6 0 1 -2.21136e-6 0 1 1.94824e-6 0 1 -1.54518e-5 0 1 -3.46789e-6 0 1 1.69177e-5 0 1 -2.81921e-6 0 1 1.68608e-5 0 1 -1.19173e-6 0 1 7.99507e-6 0 1 4.96092e-7 0 1 2.054e-6 0 1 -4.99852e-6 0 1 2.93469e-6 0 1 -7.04694e-6 0 1 8.24721e-7 0 1 -5.61277e-7 0 1 -1.50096e-6 0 1 -1.49641e-6 0 1 7.46457e-7 0 1 2.79016e-6 0 1 1.14067e-6 0 1 -2.21855e-6 0 1 -1.33154e-6 0 1 2.45534e-6 0 1 -8.49993e-6 0 1 1.32896e-6 0 1 -3.40965e-6 0 1 2.63661e-7 0 1 -2.99743e-6 0 1 -4.25519e-6 0 1 -2.15366e-6 0 1 4.26951e-6 0 1 -1.45824e-6 0 1 -2.98412e-6 0 1 7.63131e-7 0 1 -1.29587e-6 0 1 5.35725e-6 0 1 -1.50615e-6 0 1 1.40149e-6 0 1 -3.62318e-7 0 1 -1.44086e-6 0 1 1.38644e-6 0 1 5.30895e-6 0 1 1.37089e-6 0 1 6.17306e-6 0 1 -1.60254e-6 0 1 -3.02313e-6 0 1 0.9997245 -0.02347803 -2.79323e-5 0.9997245 -0.02347415 1.63178e-4 0.9997246 -0.02347105 -1.57742e-4 0.9997244 -0.02347993 1.7074e-4 0.9997246 -0.0234667 -1.51581e-4 0.9997246 -0.02346932 -4.23002e-5 0.9997248 -0.02346217 -1.5785e-4 0.9997246 -0.02346873 -2.64116e-5 0.9997242 -0.0234844 1.45505e-4 0.9997246 -0.02346789 -2.74738e-5 0.9997246 -0.02346748 -4.60788e-5 0.9997251 -0.02345198 1.00424e-5 0.9997254 -0.02343767 1.45226e-4 0.9997257 -0.02341526 5.4762e-4 0.9997239 -0.02349787 -2.56358e-4 0.9997218 -0.02342146 0.002815186 0.9997256 -0.02341389 6.97621e-4 0.9997237 -0.02350378 -5.87594e-4 0.999722 -0.02354353 -0.001385629 0.9997245 -0.0234763 -8.51385e-5 0.9997255 -0.02342915 4.01708e-4 0.9997271 -0.02334374 0.001021444 0.9997253 -0.02344179 1.42092e-4 0.9997234 -0.02351546 -4.47368e-4 0.9997248 -0.0234645 4.06337e-5 0.9997245 -0.02347475 -4.30032e-5 0.9997249 -0.02345842 7.95794e-5 0.9997234 -0.0235185 -3.03903e-4 0.9997249 -0.02345865 3.84758e-5 0.9997255 -0.02342706 2.27749e-4 0.999725 -0.02345353 7.4083e-5 0.9997242 -0.02348738 -7.83227e-5 0.9997246 -0.02347034 4.35565e-6 0.9997246 -0.02347171 -5.92252e-6 0.9997245 -0.02347397 -2.97445e-6 -0.02347737 -0.9997245 0 -0.02347487 -0.9997245 -4.63444e-6 -0.02345949 -0.9997248 1.1756e-5 -0.02347266 -0.9997245 0 -0.023476 -0.9997245 -1.16872e-5 -0.02347052 -0.9997246 5.48232e-6 -0.02347218 -0.9997246 -4.51756e-6 -0.02347016 -0.9997246 1.35032e-5 -0.02347069 -0.9997246 -1.04872e-5 -0.02346807 -0.9997247 -2.85779e-5 -0.02346807 -0.9997247 -2.22333e-5 -0.02347946 -0.9997244 7.53027e-5 -0.02346718 -0.9997246 -1.76135e-5 -0.02346378 -0.9997247 -4.73877e-5 -0.02346479 -0.9997248 -3.70382e-5 -0.02347642 -0.9997245 3.70555e-5 -0.02347797 -0.9997245 3.87342e-5 -0.02347439 -0.9997245 1.27942e-5 -0.02345949 -0.9997249 -4.69699e-5 -0.02347266 -0.9997246 6.13816e-6 -0.02347368 -0.9997246 1.03871e-5 -0.02347302 -0.9997246 1.16269e-5 -0.02347028 -0.9997246 3.54563e-6 -0.02346515 -0.9997247 -1.8081e-6 -0.02346855 -0.9997247 0 -0.02346903 -0.9997246 0 -0.9997247 0.023467 -1.41337e-6 -0.9997219 0.02356541 9.02724e-4 -0.9997301 0.02314263 -0.00204581 -0.9993093 0.02827125 0.02411937 -0.9997227 0.02248412 -0.006991147 -0.9997172 0.0236991 0.001964807 -0.9993012 0.02513623 0.02766585 -0.9997112 0.02269327 -0.007918596 -0.9997301 0.02320057 -0.00123918 -0.9996835 0.02448529 0.005783915 -0.999718 0.02367264 0.001899003 -0.9997246 0.02346897 3.16682e-5 -0.9997276 0.02333164 -6.77896e-4 -0.9997125 0.02386748 0.002311587 -0.9997203 0.02362728 0.001057207 -0.9997256 0.02342969 3.53854e-5 -0.9997255 0.02343106 8.09551e-5 -0.9997166 0.02377837 -0.001138746 -0.9997212 0.02360731 -5.9043e-4 -0.9997308 0.02317017 0.001304209 -0.9997251 0.02344954 9.51296e-5 -0.9997249 0.02345895 4.69822e-5 -0.9997202 0.02364194 -8.665e-4 -0.99972 0.02363461 -0.001214921 -0.9997286 0.02327638 0.00108391 -0.9997267 0.02335947 9.34854e-4 -0.9997243 0.02348041 -1.04266e-4 -0.9997236 0.02350234 -6.48771e-4 -0.9997251 0.02344876 3.91608e-5 -0.9997244 0.02347582 -3.91018e-4 -0.9997251 0.0234453 2.83516e-4 -0.9997248 0.02345645 4.89542e-4 -0.999723 0.0235387 -1.15592e-4 -0.9997238 0.02350038 -2.71206e-4 -0.9997241 0.02348136 6.48735e-4 -0.999723 0.02353179 -6.06607e-4 -0.9997243 0.02347588 3.89052e-4 -0.9997256 0.02341395 7.7692e-4 -0.9997243 0.02348154 8.26721e-5 -0.999719 0.02367335 -0.001272201 -0.9997232 0.02352988 -2.4259e-4 -0.9997248 0.02346199 1.32627e-4 -0.9997282 0.02328848 0.001160681 -0.9997296 0.0232281 0.001078069 -0.9997172 0.02375072 -0.001214385 -0.9997274 0.02334457 4.79517e-4 -0.9997231 0.02351653 8.02594e-4 -0.9997044 0.02401554 0.003798604 -0.9997272 0.02335327 -5.81146e-4 -0.9997296 0.0231505 -0.002165257 -0.9989323 0.02385318 0.0395655 -0.9996801 0.02392435 0.008223056 -0.9995907 0.0229631 -0.01706296 -0.9996559 0.02361351 0.01142424 -0.9997227 0.0235092 0.001386344 -0.9997076 0.02372807 0.00464946 -0.9997298 0.02315318 -0.002120912 -0.9997248 0.02293962 -0.00490731 -0.9997131 0.02381205 0.002624809 -0.9997292 0.02314013 -0.002494573 -0.9997265 0.02338951 -1.51322e-4 -0.9997279 0.02330327 -0.00112611 -0.9997285 0.02329194 -6.24674e-4 -0.9997291 0.0232194 -0.001667618 -0.999724 0.02349466 4.11299e-5 -0.9997292 0.02322572 -0.001513719 -0.9997238 0.02350562 3.06327e-5 9.36722e-6 -1.13782e-5 1 -1.60299e-5 -5.49058e-7 1 1.16382e-6 -5.67261e-7 1 0 -5.85797e-7 1 0 -6.0184e-7 1 0 -6.16592e-7 1 -3.77235e-6 -6.36451e-7 1 1.60271e-6 -6.56212e-7 1 0 -6.81209e-7 1 0 -7.0351e-7 1 1.8199e-5 -7.25617e-7 1 0 -7.505e-7 1 0 -7.74811e-7 1 1.91608e-6 -1.262e-5 1 0 1.11369e-5 1 9.66668e-6 -8.52982e-7 1 -1.69105e-5 -8.9167e-7 1 0 -9.99212e-6 1 0 1.02047e-5 1 3.16013e-5 -1.0102e-6 1 0 8.01483e-6 1 -1.90297e-5 0 1 1.42409e-5 0 1 0 1.48856e-6 1 0 1.86747e-6 1 0 1.65159e-6 1 9.416e-6 6.45052e-6 1 0 2.02752e-6 1 8.29669e-5 0 1 -2.28389e-4 0 1 -9.79252e-5 0 1 0 1.76973e-6 1 0 2.19744e-6 1 4.22632e-6 -9.11417e-6 1 0 1.57802e-6 1 -0.8007143 -0.5990462 -4.73478e-4 -0.8006373 -0.5991494 3.15166e-4 -0.8007178 -0.5990417 2.12083e-6 -0.8004687 -0.5993744 5.76289e-4 -0.8010143 -0.5986452 -2.46771e-4 -0.800623 -0.5991686 1.10816e-4 -0.800341 -0.5995451 1.17681e-4 -0.8008414 -0.5988765 0 -1.45451e-6 0 1 2.34788e-6 0 1 -4.41251e-7 0 1 -0.0234822 -0.9997243 0 -0.02347481 -0.9997245 -1.17043e-5 -0.02348124 -0.9997243 0 -0.02347177 -0.9997246 8.64403e-6 -0.02347332 -0.9997245 7.91227e-6 -0.0234695 -0.9997246 1.30764e-5 -0.02346616 -0.9997246 1.55651e-5 -0.02346414 -0.9997247 4.026e-5 -0.0234782 -0.9997244 -1.81898e-5 -0.02347058 -0.9997246 2.80073e-5 -0.02347385 -0.9997245 -1.21794e-5 -0.02346676 -0.9997247 2.90469e-6 -0.02347135 -0.9997246 9.50222e-6 -0.02346473 -0.9997247 0 -0.02347236 -0.9997246 -2.82667e-6 -0.02347177 -0.9997246 -1.96296e-5 -0.02347129 -0.9997246 3.57748e-6 -0.02347546 -0.9997245 -6.21161e-5 -0.02346801 -0.9997247 1.12839e-4 -0.02348071 -0.9997243 -8.68483e-5 -0.0234676 -0.9997246 6.03387e-5 -0.02346265 -0.9997248 4.60301e-5 -0.02346873 -0.9997246 2.70268e-5 -0.02346247 -0.9997248 3.99684e-5 -0.02347916 -0.9997244 -2.92141e-5 -0.02347385 -0.9997245 8.30644e-6 -0.02346855 -0.9997246 1.19753e-5 -0.02347683 -0.9997244 2.28871e-6 -0.02347552 -0.9997245 4.55973e-6 -0.02348405 -0.9997243 0 -0.9997244 0.02348083 5.68446e-5 -0.9997193 0.02367979 -8.38291e-4 -0.9997314 0.02295833 0.00321567 -0.999716 0.02376312 -0.001836478 -0.9996798 0.02248769 0.01161116 -0.9997036 0.02399462 -0.00412923 -0.9997082 0.02394878 -0.003172695 -0.9994091 0.02642941 -0.02197694 -0.9996924 0.02429729 -0.004979848 -0.9997252 0.02341902 0.001057744 -0.9997185 0.02370661 -9.76053e-4 -0.9997301 0.02280765 0.004436075 -0.9997218 0.0235843 -4.7893e-4 -0.9997174 0.02373164 -0.001442074 -0.9997277 0.0233252 8.62087e-4 -0.9997304 0.02320438 -8.02692e-4 -0.999724 0.02349609 7.17222e-5 -0.9997249 0.02345347 6.36511e-5 -0.9997268 0.02337551 -3.44098e-4 -0.9997284 0.02329736 -7.29417e-4 -0.9997222 0.02356976 5.09773e-4 -0.9997223 0.02355849 6.29352e-4 -0.9997248 0.02346253 9.74835e-5 -0.999725 0.02345246 3.01261e-5 -0.9997267 0.02337765 -5.10151e-4 -0.9997252 0.02344286 -1.88894e-4 -0.9997232 0.02351826 6.29141e-4 -0.9997252 0.02343827 -5.00479e-4 -0.9997238 0.02349704 4.68279e-4 -0.9997243 0.02347302 7.59234e-4 -0.9997248 0.02346193 1.27068e-4 -0.9997276 0.0233317 -6.76857e-4 -0.999724 0.02349209 3.03389e-4 -0.9997242 0.02347576 -6.24684e-4 -0.9997233 0.02352154 6.17703e-4 -0.9997246 0.02346694 -3.60653e-4 -0.9997259 0.02340149 -7.73264e-4 -0.9997246 0.02347326 -7.42498e-5 -0.9997256 0.02342021 -4.97844e-4 -0.9997235 0.02351737 2.26373e-4 -0.9997248 0.02346539 -1.4683e-4 -0.999722 0.02357554 5.16222e-4 -0.999721 0.02361851 5.44089e-4 -0.9997264 0.02338415 -5.57452e-4 -0.9997199 0.02366173 5.85485e-4 -0.9997245 0.02347254 -3.21795e-5 -0.9997272 0.02333748 9.94541e-4 -0.9997227 0.0235508 -4.55919e-4 -0.9997209 0.0235635 0.001745104 -0.9997215 0.02358025 -9.65264e-4 -0.9997199 0.02325499 0.004406571 -0.9995892 0.02530354 -0.01346087 -0.9997187 0.02336472 0.00408715 -0.9997199 0.02323848 0.004493772 -0.9997234 0.02250659 0.006843984 -0.9996458 0.02148234 0.01571089 -0.9997203 0.02358514 0.001827597 -0.9997205 0.02357697 0.001752793 -0.999723 0.02352285 -8.37726e-4 -0.9997153 0.02371621 -0.002638041 -0.9997214 0.02358525 -0.001001834 -0.9997262 0.02339512 5.18843e-4 -0.9997149 0.02379411 -0.002024173 -0.9997283 0.02324253 0.001792609 -0.9997274 0.02333676 7.89794e-4 -0.9997242 0.02348709 -2.1914e-5 -0.9997271 0.02336186 -1.40562e-4 -0.9997222 0.02357381 -1.42183e-6 -0.02346259 -0.9997248 0 -0.02348315 -0.9997243 9.29155e-6 -0.02346241 -0.9997248 -9.26596e-6 -0.02348417 -0.9997243 3.21202e-5 -0.02346169 -0.9997248 -9.22775e-6 -0.02346342 -0.9997248 -1.35625e-5 -0.02346307 -0.9997248 -1.8231e-5 -0.02346444 -0.9997248 -1.77259e-5 -0.02348536 -0.9997242 4.47877e-5 -0.02348655 -0.9997242 6.91704e-5 -0.02346378 -0.9997248 -2.62766e-5 -0.02346634 -0.9997246 -2.51934e-5 -0.02346533 -0.9997248 -2.55747e-5 -0.02346724 -0.9997247 0 -0.02346587 -0.9997247 -2.47907e-5 -0.02346837 -0.9997246 -3.13209e-5 -0.02348619 -0.9997242 1.11704e-4 -0.02346819 -0.9997247 -1.50464e-5 -0.02346819 -0.9997247 0 -0.02346873 -0.9997246 -1.44165e-5 -0.0234692 -0.9997246 -1.4733e-5 -0.02346944 -0.9997246 -1.37808e-5 -0.0234698 -0.9997246 0 -0.02347022 -0.9997246 0 -0.0234704 -0.9997246 0 -0.02347058 -0.9997246 4.5679e-6 -0.02347058 -0.9997246 0 -0.02347111 -0.9997246 1.47987e-6 -0.02347159 -0.9997245 0 -0.02347177 -0.9997246 -1.49842e-6 -0.02347242 -0.9997246 0 -0.0234735 -0.9997245 1.50385e-6 -0.02347266 -0.9997246 0 0.9997245 -0.02347618 4.37382e-6 0.9997247 -0.02346706 1.11673e-5 0.9997249 -0.02345669 -8.07146e-5 0.9997276 -0.02333658 -3.76711e-4 0.9997216 -0.02359688 3.84614e-4 0.9997278 -0.02332806 -4.57352e-4 0.9997232 -0.02352946 2.20743e-4 0.9997264 -0.0233938 -3.01909e-4 0.9997211 -0.0236091 6.42835e-4 0.9997262 -0.02339863 -3.91706e-4 0.9997255 -0.02343273 -2.29948e-4 0.9997229 -0.02353376 5.27256e-4 0.9997254 -0.02342683 -6.4281e-4 0.9997171 -0.02368998 0.002186715 0.9997248 -0.02346396 -1.79371e-4 0.9997251 -0.02345031 -6.16505e-5 0.9997252 -0.02343857 -3.02267e-4 0.9997243 -0.02348619 8.7609e-5 0.9997246 -0.02346998 -1.91108e-5 0.9997239 -0.02350246 2.3305e-4 0.9997249 -0.02345871 -6.97996e-5 0.9997246 -0.02347153 2.66134e-6 0.9997244 -0.02347999 -8.75772e-5 0.9997249 -0.02345865 1.1697e-4 0.9997245 -0.02347373 -2.93118e-5 0.9997246 -0.02347338 -2.22387e-5 0.9997245 -0.02347439 -6.64063e-5 0.9997248 -0.02346169 1.53129e-4 0.9997245 -0.02347475 -1.40849e-4 0.9997246 -0.02346676 9.14225e-5 0.9997246 -0.02347183 5.21626e-5 0.9997245 -0.02347254 -4.06292e-5 0.9997257 -0.02342283 -3.63772e-4 0.9997245 -0.02347344 -1.75347e-4 0.9997246 -0.02346897 1.55217e-4 0.9997246 -0.02347028 2.71064e-5 0.9997248 -0.02346467 1.48251e-4 0.9997246 -0.02346974 1.65298e-5 0.9997245 -0.02347469 -9.27095e-5 0.9997245 -0.02347421 -5.38212e-5 0.9997246 -0.02346718 3.35088e-5 0.9997248 -0.02346462 -7.64426e-5 0.9997245 -0.02347487 -5.37313e-5 0.9997248 -0.02345925 -5.99146e-5 0.9997239 -0.02350252 2.7953e-4 0.9997251 -0.02345287 -1.26978e-4 0.9997243 -0.02338045 -0.00218898 0.9997256 -0.02342259 -4.4002e-4 0.9997259 -0.02339291 -0.00100702 0.9997254 -0.0234248 -7.59949e-4 0.9997246 -0.0234704 -1.48108e-4 0.9997221 -0.02355498 9.2453e-4 0.9997227 -0.02354836 5.05301e-4 0.9997257 -0.02342075 -4.12433e-4 0.9997243 -0.02348238 7.604e-5 0.9997229 -0.02353477 4.79706e-4 0.9997256 -0.02342516 -2.55601e-4 0.9997248 -0.02345871 -8.19225e-5 0.9997248 -0.02346217 -3.01762e-5 0.9997245 -0.02347123 -5.84456e-6 0.9997243 -0.02348232 7.09098e-5 0.9997244 -0.0234794 6.76138e-5 0.9997249 -0.02345842 -8.57202e-5 0.9997237 -0.0235064 2.01512e-4 0.9997246 -0.0234695 -2.42065e-6 0.9997246 -0.02347099 -4.28979e-6 -0.02346366 -0.9997248 0 -0.02347975 -0.9997243 1.57414e-5 -0.02346664 -0.9997247 -1.2375e-5 -0.0234695 -0.9997246 -1.2245e-5 -0.02347207 -0.9997245 8.13651e-6 -0.0234701 -0.9997246 8.29586e-6 -0.02347207 -0.9997246 1.4133e-5 -0.02347493 -0.9997245 3.15833e-5 -0.0234645 -0.9997247 -7.24797e-5 -0.02347165 -0.9997246 1.5169e-5 -0.02347016 -0.9997246 1.17447e-5 -0.02347135 -0.9997246 1.53008e-5 -0.02346962 -0.9997246 -1.1199e-5 -0.02346968 -0.9997246 -2.88866e-5 -0.02347278 -0.9997245 5.82802e-5 -0.02347064 -0.9997246 3.61249e-6 -0.02346706 -0.9997246 1.56621e-5 -0.02347153 -0.9997245 0 -0.02347481 -0.9997245 0 -1 0 0 -5.10518e-7 0 1 -2.23227e-7 0 1 7.37674e-7 0 1 -1.62883e-6 0 1 0 0 1 2.91511e-6 0 1 -3.4885e-6 0 1 -3.50848e-7 0 1 -4.07438e-7 0 1 8.38723e-7 0 1 5.90464e-7 0 1 0 0 1 0 0 1 -2.81633e-7 0 1 0 0 1 2.56568e-5 0 1 0 0 1 -7.359e-7 0 1 2.95168e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.49381e-7 0 1 0 0 1 0 0 1 0 0 1 2.49833e-7 0 1 2.69284e-7 0 1 -4.30899e-6 0 1 2.88311e-6 0 1 2.74171e-6 0 1 2.83472e-6 0 1 -5.41688e-6 0 1 -1.1964e-5 0 1 2.99215e-6 0 1 5.0379e-6 0 1 0 0 1 3.13286e-6 0 1 -9.31154e-7 0 1 -9.39059e-7 0 1 4.54744e-7 0 1 -0.7010883 -0.5866105 0.4054177 -0.6699005 -0.6883037 0.2783368 -0.5663453 -0.7451269 0.3521919 -0.6637656 -0.504485 0.5521868 -0.6037651 -0.6405715 0.4744849 -0.5139186 -0.6672794 0.5390973 -0.5066433 -0.5452497 0.6678439 -0.4057208 -0.6779206 0.613037 -0.221236 -0.7781868 0.5877755 -0.3119101 -0.6668834 0.6767412 -0.3502077 -0.3534733 0.8674164 -0.4798277 -0.3979133 0.7819402 -0.3396781 -0.5266384 0.7792759 -0.1845484 -0.4429833 0.8773298 -0.1733497 -0.1727088 0.9695987 -0.03921663 -0.1728281 0.984171 -0.1045592 -0.1345292 0.9853777 -0.3158426 -0.222393 0.92238 -0.2513239 -0.2813851 0.9260987 -0.01834213 -0.08057117 0.9965801 -0.01913565 -0.1017213 0.9946289 0.02969491 -0.02215677 0.9993135 -0.07083553 -0.3070251 0.9490617 -0.7648019 -0.6114143 0.2031028 -0.728155 -0.6773102 0.1050772 -0.6256153 -0.7659431 0.1481102 -0.6985537 -0.4272075 0.5740354 -0.7588559 -0.4650796 0.4558933 -0.7787439 -0.5237202 0.3453624 -0.8210358 -0.4870608 0.2977788 -0.8361852 -0.5270296 0.1517701 -0.601768 -0.7952261 0.07409942 -0.5099835 -0.8566258 0.07816082 -0.8576077 -0.4797244 0.1854014 -0.8160244 -0.5700695 0.09552532 -0.8702862 -0.4859271 0.08047914 -0.5104656 -0.8301246 0.2243167 -0.6010425 -0.4069717 0.6878386 -0.6186324 -0.3698366 0.6931918 -0.3540552 -0.9325497 0.07068282 -0.2193983 -0.9712549 0.09234929 -0.3078798 -0.9336192 0.183208 -0.3885995 -0.8678405 0.3095855 -0.1123716 -0.9837252 0.1402052 -0.04388672 -0.9870241 0.1544581 -0.05142545 -0.9587414 0.2795897 -0.08630657 -0.9945098 0.05917555 -0.4445401 -0.8888056 0.1113944 -0.4554714 -0.7795569 0.4299267 -0.2625874 -0.8801438 0.395468 -0.3401727 -0.7906132 0.5091299 -0.1835439 -0.9445461 0.2722944 -0.04425317 -0.8778612 0.4768663 -0.1421265 -0.8624032 0.485861 -0.05417174 -0.9274204 0.370077 -0.2015795 -0.6344032 0.7462562 -0.1227795 -0.5918016 0.7966783 -0.05261468 -0.6857917 0.7258937 -0.006561577 -0.5740029 0.818827 -0.4481402 -0.2955455 0.8436962 -0.06824052 -0.8057025 0.5883764 -0.1157299 -0.7393959 0.6632498 -0.03268611 -0.4994783 0.8657096 -0.01312309 -0.3852084 0.9227364 0 0 1 0 0 1 1.51266e-6 0 1 -1.96393e-6 0 1 -1.98216e-6 0 1 -1.96886e-6 0 1 1.97834e-6 0 1 -8.85206e-7 0 1 0.6728177 -0.7398084 9.86464e-6 0.6727899 -0.7398336 5.02714e-6 0.6726459 -0.7399646 8.10417e-5 0.6725608 -0.740042 5.14633e-5 0.672717 -0.7398999 2.84384e-5 0.6841573 -0.7293325 -0.00172472 0.6705107 -0.7418998 4.30194e-4 0.6733357 -0.7393369 -1.91976e-4 0.6698138 -0.7425292 -9.40386e-5 0.6728941 -0.7397388 -5.78554e-5 0.6731868 -0.7394725 -1.47835e-4 0.6733086 -0.7393617 -1.59126e-4 0.6729953 -0.7396467 -1.49213e-4 0.6726582 -0.7399535 4.72331e-5 0.6728518 -0.7397774 -8.41038e-5 0.6731589 -0.739498 -2.44312e-4 0.6726405 -0.7399695 1.48588e-4 0.6727327 -0.7398856 0 0.6724392 -0.7401524 2.58469e-4 0.6729699 -0.7396698 -1.56114e-4 0.6726796 -0.7399339 5.39557e-5 0.6728274 -0.7397995 5.28609e-6 0.6729497 -0.7396883 9.27206e-6 0.6728046 -0.7398203 3.02225e-6 0.6729483 -0.7396895 4.13721e-6 0.6727758 -0.7398465 4.41281e-6 0.672674 -0.739939 -2.03702e-6 0.6727068 -0.7399092 -4.77158e-6 0.6728531 -0.7397762 2.80985e-6 0.672764 -0.7398571 -5.12366e-6 0.672873 -0.7397581 1.69253e-5 0.6728281 -0.7397989 1.4284e-5 0.6727094 -0.7399069 -2.15829e-5 0.6728246 -0.7398021 4.72487e-6 0.6728108 -0.7398146 9.43882e-6 0.6729049 -0.7397291 3.80108e-5 0.6726871 -0.7399271 -3.08355e-5 0.6727257 -0.739892 -3.12044e-5 0.6727595 -0.7398613 -5.80921e-6 0.672789 -0.7398344 0 0.6727506 -0.7398694 -1.22443e-5 0.6729047 -0.7397292 1.9402e-5 0.6728068 -0.7398183 5.03719e-6 0.672811 -0.7398145 3.98006e-6 0.6727455 -0.739874 1.87633e-5 0.6727988 -0.7398256 2.85421e-7 0.6727421 -0.7398771 1.50891e-5 0.6728097 -0.7398156 -4.24257e-6 0.6727264 -0.7398914 1.5417e-5 0.6729046 -0.7397294 -2.1344e-5 0.6728848 -0.7397473 -1.18656e-5 0.6728345 -0.7397931 -7.54666e-6 0.6728907 -0.739742 -1.24564e-5 0.6726593 -0.7399523 2.36198e-5 0.6728068 -0.7398183 -2.21683e-6 0.6727778 -0.7398446 3.99543e-6 0.6728655 -0.7397649 -4.77243e-6 0.6727976 -0.7398266 8.60757e-7 0.6727984 -0.7398259 0 0.6726436 -0.7399667 1.04032e-5 0.6727705 -0.7398513 1.51728e-6 0.6728398 -0.7397882 1.05328e-6 0.6730259 -0.739619 0 0.6727315 -0.7398868 3.27504e-6 0.5383513 0.4809759 0.6919828 0.663064 0.4092648 0.6267764 0.5756647 0.3297361 0.7482542 -0.6031791 -0.5219068 0.6031486 -0.5177267 -0.6182568 0.5913694 -0.5677527 -0.5919241 0.5720865 0.7078974 -0.7047539 0.04693877 0.709546 -0.7024351 0.05594205 0.7381876 -0.6649426 0.1137129 0.8591355 -0.01608341 0.5114955 0.816181 0.1261978 0.5638464 0.879919 0.1840285 0.4380368 0.7658114 0.641752 0.04107844 0.8177362 0.571689 0.06692898 0.7250583 0.6841923 0.0785579 0.9858773 0.0984534 0.1354727 0.9594825 0.07516795 0.2715568 0.9556478 0.2534315 0.1500324 0.991271 -0.05682712 0.1189647 0.9683451 -0.07822078 0.2370429 0.2569443 0.1873597 0.9480907 0.3672683 0.2906651 0.8835315 0.3714823 0.1341633 0.9186954 0.7356097 0.4715556 0.486327 0.618173 0.5525866 0.5590262 0.4479584 0.3884768 0.8052448 0.4810402 0.2364305 0.8442162 0.8195449 0.5481945 0.1668205 0.7508665 0.6230212 0.2191897 0.9895551 0.1217716 0.07715255 0.9870232 -0.1485372 0.06100797 0.9562478 -0.2884338 0.04895222 0.9682711 -0.2307224 0.09601223 0.5460511 0.4033429 0.7342635 0.9242211 0.3722155 0.08527135 0.9223842 -0.2576438 0.2877968 0.9532464 -0.2294151 0.1966982 0.8907682 -0.3967515 0.2216315 0.8447737 -0.5118389 0.1561366 0.9124988 -0.3774636 0.1576936 0.8647609 -0.4945938 0.08697962 0.9015735 0.4014216 0.1613255 0.8711724 0.3726097 0.3197198 0.7839196 0.5231319 0.3343698 0.6310535 0.4760445 0.6124976 0.7243875 0.5998972 0.3396854 0.6835119 0.5871622 0.4336497 0.9312105 -0.1118844 0.3468844 0.9169217 0.03653156 0.3973917 0.7222104 -0.6901345 0.04611474 0.7199881 -0.6921237 0.0508151 0.7529699 -0.6528059 0.08295118 0.7683874 -0.6374896 0.05646091 0.9343783 -0.3464549 0.08310395 0.7197725 -0.693129 0.03872925 0.7216278 -0.6911696 0.03921723 0.7146272 -0.698849 0.03030508 0.8175981 -0.5374662 0.2065511 0.9268052 0.2267877 0.2993317 0.8805465 -0.2956112 0.3704753 0.8585425 -0.4260209 0.2853263 0.1958728 0.08160859 0.9772277 0.2432706 0.02261489 0.9696949 0.7877653 -0.08096778 0.6106311 0.7375009 0.05459916 0.6731355 0.721283 -0.5508656 0.4198786 0.7688527 -0.397153 0.5011337 0.7725172 -0.5043092 0.3858618 0.8807533 -0.1578452 0.4464957 0.7052724 -0.6948043 0.1408469 0.6941398 -0.7170601 0.06320625 0.6934296 -0.7173262 0.06781393 0.6461887 -0.02835255 0.7626509 0.7049331 -0.1562889 0.6918404 0.8288457 -0.3426718 0.4422566 0.8184393 -0.2144294 0.5330827 0.7223964 -0.6303496 0.2842586 0.6130432 -0.239852 0.752761 0.5449199 -0.1204897 0.8297859 0.7461367 -0.2802285 0.6039471 0.5148036 -0.3291227 0.7916158 0.4366434 -0.2189474 0.872585 0.6764894 -0.7328889 0.07236111 0.6681217 -0.7285798 0.1509469 0.6872698 -0.7111361 0.1481419 0.1155767 -0.09573912 0.988674 0.07995861 0.03311264 0.9962481 0.5575253 -0.5893875 0.5846264 0.6097416 -0.6522548 0.4503097 0.5527654 -0.7041105 0.4457342 -0.3070179 -0.3803238 0.872407 -0.2465963 -0.4176573 0.8745014 -0.4007259 -0.3699924 0.8381673 0.4131689 -0.4216226 0.8071716 0.3245424 -0.3208496 0.8897908 0.580199 -0.4311742 0.6909834 0.6659414 -0.3532053 0.6570907 0.4931029 -0.8536598 0.1676739 0.3548734 -0.8845284 0.3027777 0.4731711 -0.8567072 0.2053338 -0.009247362 -0.2027412 0.9791887 -0.03900384 -0.054111 0.9977729 -0.283917 -0.2732965 0.9190758 -0.1296153 -0.321551 0.9379792 -0.1735317 -0.186075 0.9670899 -0.001648008 -0.6176158 0.7864782 0.1171339 -0.6907787 0.7135157 0.03119069 -0.7689945 0.638494 -0.3519498 -0.5135195 0.7825786 -0.2217227 -0.6211287 0.7516903 -0.3107795 -0.7025882 0.6401454 -0.4454935 -0.5976029 0.666638 0.6490812 -0.745949 0.1491776 0.6679729 -0.7407305 0.07162845 0.6657139 -0.7424084 0.07519912 -0.3725817 -0.7198934 0.5856077 0.661685 -0.7457957 0.07721334 0.6594575 -0.7483596 0.07123166 0.6311759 -0.5224957 0.5732497 -0.4071281 -0.474057 0.7807155 -0.500053 -0.4600732 0.7336756 0.6586562 -0.7492055 0.0697354 0.6304906 -0.7628512 0.1433169 -0.1802466 -0.7797055 0.599642 -0.2360632 -0.8013941 0.5495832 0.6083099 -0.7340797 0.301805 -0.494779 -0.5555124 0.6682813 0.6128916 -0.7788563 0.1332173 0.650575 -0.7565677 0.06601274 0.6485009 -0.7582172 0.06747776 0.6512185 -0.7554416 0.07226943 0.4834877 -0.6566547 0.5788303 0.6438428 -0.7619844 0.0696153 0.5707129 -0.7682956 0.2898428 0.4971868 -0.7546461 0.4281526 0.6423152 -0.7640883 0.06000149 0.5968942 -0.7934376 0.1190553 0.3966251 -0.8460481 0.3562179 0.4447203 -0.8024314 0.3979044 0.5026833 -0.8301859 0.2410414 0.535188 -0.8006456 0.2693336 0.6351414 -0.7705259 0.05371433 0.6346125 -0.7704526 0.06058025 0.582916 -0.8062552 0.1008048 0.6347699 -0.7709162 0.05249309 0.6293321 -0.7752739 0.05377441 0.7874783 -0.6020762 -0.1318415 0.5944144 -0.7996838 0.08472013 0.6367494 -0.7705449 0.02847427 0.6275616 -0.777013 0.04916602 -0.08600229 -0.9962899 -0.003173947 0.8210672 0.3270779 0.4678341 0.7070996 -0.7045665 0.0599702 0.702359 -0.7094698 0.05783301 0.7138781 -0.6985269 0.0493803 0.7073532 -0.7053999 0.04541319 0.753003 0.2652738 0.6021765 0.7015578 -0.709554 0.06595319 0.7226853 -0.6790434 0.1289419 0.7020398 -0.7097002 0.05887204 0.8187142 -0.4622778 0.3405969 0.6689246 0.1889457 0.7189154 0.6870761 -0.7230886 0.07120102 0.6907384 -0.7193043 0.07403928 0.7883724 -0.5703431 0.2306032 0.5714465 0.1001648 0.8145035 0.6807324 -0.7284644 0.07709163 0.6767932 -0.7328569 0.06979733 0.6860354 -0.7241536 0.07040721 0.7570708 -0.5988264 0.2612484 0.4632545 0.001861631 0.8862233 0.6728972 -0.7355235 0.0788322 0.7023201 -0.4576739 0.545235 0.6664715 -0.6006423 0.4416388 0.6975749 -0.7134448 0.06622642 -0.08737659 -0.1689545 0.9817432 0.34764 -0.1032757 0.9319231 0.6385143 -0.7670901 0.06222778 0.6853039 -0.6640626 0.298964 0.6845207 -0.7250505 0.07571876 0.2279188 -0.2121708 0.9502824 0.4915054 -0.5119225 0.7045267 0.64691 -0.6990058 0.3047927 0.3110535 -0.5145873 0.799028 0.2119852 -0.4232991 0.8808407 0.1076391 -0.3215137 0.9407672 0.4022747 -0.5929593 0.6975489 0.6695898 -0.7387766 0.07654196 0.1021769 -0.5231837 0.8460725 0.2113454 -0.6051347 0.7675579 -0.009613394 -0.4282082 0.903629 0.3152593 -0.6720547 0.6700404 0.4113166 -0.7223143 0.5559504 0.6545419 -0.7523555 0.07440543 -0.1204911 -0.5290561 0.8399891 0.2330134 -0.7467721 0.6229256 0.343096 -0.7843415 0.5168109 -0.09638118 -0.7038454 0.7037844 0.09097933 -0.8753977 0.4747651 0.1579661 -0.8151001 0.5573676 0.2807813 -0.8409705 0.4625262 0.6422437 -0.7638317 0.06390696 -0.04443538 -0.8381074 0.5436925 -0.0789836 -0.865371 0.4948683 0.225448 -0.8914459 0.3930615 0.1139584 -0.9054107 0.4089562 0.305893 -0.9042505 0.2979274 0.9997253 -0.02344185 0 0.9997254 -0.02343606 4.84805e-5 0.9996863 -0.02399641 0.00717622 0.9997251 -0.02344626 -2.11405e-6 0.9997226 -0.02352494 0.00120449 0.9997207 -0.02360463 0.001166224 0.9997091 -0.02389246 0.003331005 0.9997308 -0.02280974 -0.004260778 0.9997273 -0.02306079 -0.003697633 0.999608 -0.02470046 0.01318883 0.9996976 -0.02426266 0.004021942 0.999724 -0.02349418 -1.60523e-4 0.6464288 0.724314 0.2397899 0.4961199 0.7283709 0.4725896 0.6985161 0.5897163 0.4053517 0.1144157 0.9812464 0.155128 0.2610636 0.9608143 0.09317594 0.1280267 0.9886596 0.0784946 0.3738318 0.8975747 0.2336868 0.1984382 0.9519665 0.2332 0.5062908 0.8274188 0.2429976 0.8798305 0.377855 0.2883124 0.8436189 0.489288 0.221144 0.7510418 0.6120582 0.247631 0.9293133 0.3306158 0.1645296 0.9817728 0.1792088 0.06329685 0.9412369 0.3292696 0.07519882 0.9901733 0.1378259 -0.02368307 0.771647 0.6306789 0.0824933 0.3182854 0.7173553 0.6197547 0.5373007 0.6488505 0.5387961 0.2099729 0.7834312 0.5849334 0.5340824 0.8407678 0.08868819 0.1067271 0.9066461 0.4081693 0.1022073 0.7879941 0.60714 0.2577978 0.854972 0.4500703 -0.02313458 -0.706712 -0.7071231 -0.02313613 -0.7067345 -0.7071005 0.9997251 -0.02344852 2.48159e-4 0.9996458 -0.02367287 0.01216602 0.9997142 -0.02337026 0.005043864 0.9997271 -0.02322369 -0.002563655 0.9997158 -0.02370131 0.002556025 0.9995301 -0.0230503 -0.02020841 0.9997207 -0.02360433 0.001184821 0.9997233 -0.02352702 2.93599e-4 0.9996756 -0.02421259 0.007910072 0.9997286 -0.02294021 -0.00407797 0.9997203 -0.02356112 0.002065539 0.9997244 -0.02347737 1.05478e-4 0.9997193 -0.02321547 -0.004746139 0.9997238 -0.0235055 3.95443e-5 0.9997204 -0.02336192 0.003672778 0.9997231 -0.02350544 -0.001131653 0.9997243 -0.02348244 0 -0.02347052 -0.9997246 -1.70707e-4 -0.02347445 -0.9997245 -3.28708e-5 -0.02347677 -0.9997245 0 0 0 1 0 0 1 0 0 1 -4.40928e-7 0 1 0 0 1 0 0 1 -2.2027e-7 0 1 0 0 1 0 0 1 -2.42335e-7 0 1 -0.02346998 -0.9997246 -8.36122e-6 -0.02347093 -0.9997246 0 -0.02347201 -0.9997246 7.9477e-5 0.9997246 -0.0234524 -7.9314e-4 0.9997243 -0.02348375 1.91027e-4 0.999724 -0.02328652 0.003104925 0.9997115 -0.02369499 -0.00395137 0.9997245 -0.02343827 0.001346051 0.9997235 -0.02351492 -3.32152e-4 0.9997243 -0.02345657 0.001132965 0.999659 -0.02292984 0.01249939 0.9997174 -0.02368551 -0.002078533 0.9990856 -0.02364581 -0.03562194 0.9996768 -0.02368658 -0.009238064 0.999032 -0.02292162 0.03754663 0.9995085 -0.02396899 -0.02020722 0.9997243 -0.02348089 4.63757e-4 0.9997254 -0.02343499 -9.28934e-5 0.9997232 -0.02342706 -0.00218898 0.9997221 -0.02347606 0.002143263 1.22098e-7 0 1 -1.24533e-5 0 1 4.85045e-7 0 1 1.19888e-7 0 1 -7.05423e-7 0 1 6.2196e-6 0 1 6.84403e-7 0 1 -6.82236e-7 0 1 0 0 1 5.15373e-7 0 1 -4.30293e-7 0 1 0 0 1 2.98627e-7 0 1 0 -1 4.11166e-6 0 -1 0 6.82784e-7 0 1 -0.03271895 -0.9994646 0 -0.03271716 -0.9994647 -5.70386e-6 -0.03271615 -0.9994647 1.88945e-6 -0.03272002 -0.9994646 0 -0.03271883 -0.9994647 -1.8802e-6 0.9936974 0.1120961 9.15569e-5 0.9492888 0.3144052 4.88302e-4 0.9928252 0.1195748 0 0.8512262 0.5247987 -6.40892e-4 0.652875 0.7574656 -4.57794e-4 0.7386003 0.6741433 7.93505e-4 0.4172284 0.9088016 3.9675e-4 0.3823779 0.9240061 -1.52597e-4 0.2250177 0.9743548 -1.52596e-4 0.2462321 0.969211 2.13637e-4 0.9674742 0.2529698 -1.83112e-4 9.46094e-4 0.2009381 0.9796036 -9.46092e-4 0.1286684 0.9916872 0.001068115 0.04370337 0.999044 -0.001068115 -0.0253002 0.9996793 0.001068115 -0.114507 0.9934219 -0.001068115 -0.1825339 0.9831991 0.001068174 -0.2699128 0.9628843 -0.001068115 -0.3351624 0.9421598 0.001068174 -0.4185431 0.9081963 -9.15577e-4 -0.4752149 0.8798694 8.24011e-4 -0.5568181 0.8306341 -3.05194e-4 -0.5859429 0.8103524 5.18824e-4 -0.6780112 0.7350513 -1.83115e-4 -0.674048 0.7386877 1.83116e-4 -0.7695755 0.638556 -3.05189e-4 -0.7630331 0.6463594 0 -0.8330538 0.5531921 -2.13633e-4 -0.8382329 0.5453123 1.83113e-4 -0.8772346 0.480062 -4.57795e-4 -0.8929758 0.4501045 3.05191e-4 -0.9133453 0.4071859 -6.71418e-4 -0.916363 0.400348 3.96753e-4 -0.9307511 0.3656533 -6.10381e-4 0.2589237 0.9658976 -1.52593e-4 0.3672618 0.9301177 6.40902e-4 0.3530758 0.9355945 -1.83113e-4 0.4851583 0.8744264 3.96742e-4 0.4961718 0.8682243 -4.27266e-4 0.6131268 0.7899844 1.83113e-4 0.6233767 0.7819217 -3.96751e-4 0.7267253 0.6869282 1.83116e-4 0.7232162 0.6906217 3.66232e-4 0.8071137 0.5903961 -1.83116e-4 0.8093137 0.5873766 -1.52596e-4 0.8661338 0.4998123 3.6623e-4 0.8748632 0.4843701 -3.05194e-4 0.9116747 0.4109128 3.66231e-4 0.9222912 0.3864956 -3.35714e-4 0.9483624 0.317189 3.96743e-4 0.9575554 0.2882493 -3.66233e-4 0.9754621 0.2201672 4.27266e-4 0.9824373 0.1865932 -4.57786e-4 0.993091 0.1173459 3.05189e-4 0.9962606 0.08639913 -4.88298e-4 0.9980199 0.06289887 2.13632e-4 0.999278 0.03799593 0.3584207 -0.9335602 2.44156e-4 0.2184264 -0.9758535 -3.05193e-4 0.3664445 -0.93044 0 0.5940555 -0.8044242 -6.10383e-5 0.7763164 -0.6303431 -7.93499e-4 0.6468542 -0.7626135 6.71422e-4 0.9332692 -0.3591774 -6.40898e-4 0.9802435 -0.1977944 -2.44153e-4 0.9689163 -0.2473868 0.00100708 0.8895028 -0.4569284 0.001068115 0.1969377 -0.980416 2.13632e-4 1.48313e-6 0 1 1.75814e-6 0 1 -1.79217e-6 0 1 -4.10213e-6 0 1 3.07352e-7 0 1 -6.248e-7 0 1 5.62743e-7 0 1 -2.26521e-7 0 1 8.73076e-7 0 1 -7.06215e-7 0 1 3.31994e-7 0 1 -7.76022e-7 0 1 4.63176e-7 0 1 -3.93621e-7 0 1 4.27653e-7 0 1 -2.66005e-7 0 1 4.79722e-6 -5.85626e-7 1 -1.48786e-7 0 1 0 -5.65144e-7 1 -2.34957e-6 -5.53649e-7 1 3.54497e-7 -5.4204e-7 1 0 -5.31998e-7 1 -9.15892e-6 -6.82628e-7 1 3.1e-6 -6.40617e-7 1 0 -5.24195e-7 1 0 -5.16806e-7 1 0 -5.07239e-7 1 7.3012e-7 -4.98541e-7 1 -1.98482e-6 -4.90958e-7 1 0 -5.15837e-7 1 0 -4.83455e-7 1 -4.50039e-7 -4.73934e-7 1 -4.42459e-7 -5.58485e-7 1 1.77964e-6 -4.66985e-7 1 0 -5.43683e-7 1 0 -3.89776e-7 1 0 -4.60169e-7 1 0 -3.05445e-7 1 0 -2.46183e-7 1 0 -4.51942e-7 1 0 -2.06177e-7 1 0 -4.4153e-7 1 -4.72152e-6 -1.98672e-5 1 0 -1.72035e-7 1 3.7522e-6 1.87488e-5 1 0 -1.4441e-7 1 0 -1.08081e-6 1 0 -4.20318e-7 1 0 -1.25481e-7 1 0 0 1 0 -4.59564e-7 1 -1.49132e-7 -4.61108e-7 1 -2.1566e-6 -1.7289e-5 1 3.24185e-7 0 1 2.15268e-7 -4.24525e-7 1 4.75861e-7 0 1 -5.44544e-6 0 1 3.30679e-6 1.86013e-5 1 0 -4.2075e-7 1 -6.73022e-7 -6.2963e-7 1 -1.58639e-6 -1.84522e-5 1 -2.90552e-6 0 1 1.15523e-6 0 1 2.81949e-6 2.19935e-5 1 1.35491e-6 0 1 0 -4.16296e-7 1 0 -3.35883e-7 1 -8.40695e-6 0 1 -1.19395e-6 -1.43207e-5 1 8.08308e-6 0 1 -1.12487e-6 0 1 1.16956e-6 2.27187e-5 1 -3.87324e-6 0 1 9.45014e-7 0 1 -4.82882e-7 0 1 6.44497e-7 0 1 0 0 1 7.85021e-6 0 1 -2.46335e-6 3.61787e-7 1 0 1.27597e-6 1 6.81193e-6 1.00072e-6 1 -5.49267e-7 0 1 1.53546e-6 0 1 -2.38381e-6 7.11453e-6 1 7.65275e-6 1.15744e-5 1 6.99213e-6 3.87264e-5 1 0 1.55708e-4 1 0 4.00011e-5 1 0 4.04278e-5 1 -7.70974e-6 4.59837e-5 1 1.95582e-6 5.75203e-6 1 0 1.64359e-5 1 0 1.0079e-5 1 3.07002e-6 4.37905e-6 1 1.93242e-6 -4.77376e-6 1 0 6.97452e-6 1 3.28415e-6 0 1 0 0 1 3.36692e-7 0 1 0 1.00394e-6 1 -1.09658e-6 1.27434e-6 1 0 8.39183e-7 1 0 1.27411e-6 1 -8.26741e-7 8.97386e-7 1 0 1.30124e-6 1 1.1239e-6 5.96179e-7 1 0 4.42408e-7 1 -1.35942e-7 -8.78371e-7 1 0 1.27645e-6 1 0 2.45952e-7 1 0 1.2725e-6 1 5.00416e-6 7.21547e-7 1 -1.04555e-6 1.3599e-7 1 0 1.2634e-6 1 -4.69502e-7 0 1 0 5.26148e-7 1 -4.63541e-7 0 1 0 1.24812e-6 1 0 0 1 0 2.98576e-7 1 0 -1.47419e-6 1 0 1.1793e-6 1 8.51832e-6 2.51867e-7 1 0 1.89e-7 1 0 1.61519e-7 1 0 -1.44716e-7 1 1.82013e-6 1.11819e-6 1 -5.28631e-6 1.25874e-7 1 -9.09802e-7 -2.38501e-7 1 0 0 1 1.40482e-6 1.08386e-6 1 0 0 1 -2.87352e-7 2.91022e-6 1 -1.01942e-6 -3.50736e-7 1 0 1.10704e-5 1 5.62606e-7 0 1 -1.10077e-6 -4.19304e-7 1 -9.57163e-6 0 1 0 1.12593e-5 1 -1.21328e-6 -5.0193e-7 1 1.49622e-6 1.13999e-5 1 0 -2.34059e-6 1 1.38515e-5 0 1 -2.29379e-6 -1.08529e-6 1 0 1.15227e-5 1 -2.20324e-5 0 1 0 -1.59441e-6 1 0 1.15971e-5 1 2.60341e-6 -2.82587e-6 1 0 1.14523e-5 1 0 -3.46993e-6 1 0 1.25841e-5 1 -9.35223e-7 1.24459e-5 1 -1.47845e-7 0 1 0 1.22255e-5 1 2.61682e-5 0 1 8.46379e-7 1.18159e-5 1 -5.66937e-7 1.13236e-5 1 7.08734e-7 1.55763e-6 1 0 1.5123e-6 1 0 -2.08373e-6 1 1.63553e-7 -1.68604e-6 1 1.04951e-5 0 1 -7.6205e-7 0 1 0 0 1 -2.17419e-7 0 1 -9.28482e-7 0 1 1.95691e-6 0 1 0 1.49303e-6 1 -1.94719e-7 0 1 1.40927e-7 0 1 -1.52695e-6 1.48116e-6 1 -1.82477e-7 0 1 -1.79491e-7 0 1 0 1.46233e-6 1 3.16398e-5 1.40895e-6 1 2.16355e-7 0 1 0 0 1 -1.03194e-6 5.41254e-5 1 -2.23553e-7 0 1 1.3939e-6 0 1 0 2.95918e-7 1 0 1.03892e-6 1 0 1.31344e-6 1 0 1.22983e-6 1 0 0 1 0 1.18423e-6 1 0 5.96836e-7 1 0 3.49858e-7 1 0 4.51725e-7 1 0 5.15253e-7 1 5.57583e-7 5.87452e-7 1 -2.06685e-6 5.53194e-7 1 0 1.90049e-7 1 0 9.94279e-7 1 1.26688e-6 9.44991e-7 1 0 7.38285e-7 1 -2.05414e-6 3.83791e-7 1 -3.48967e-6 2.63991e-7 1 -3.0826e-6 8.58696e-7 1 4.01823e-6 3.16829e-7 1 2.22633e-6 8.21705e-7 1 0 9.07936e-7 1 2.83997e-6 7.73557e-7 1 0 2.21441e-7 1 0 6.9037e-7 1 -8.60358e-7 6.36381e-7 1 6.24085e-7 1.03235e-6 1 1.00304e-6 0 1 0 4.72981e-7 1 1.24024e-6 1.59896e-7 1 2.5053e-7 3.73447e-7 1 -2.11009e-7 4.78277e-7 1 2.65684e-7 0 1 0 4.21529e-7 1 2.85739e-7 1.36408e-7 1 -7.21722e-7 4.0144e-7 1 6.41467e-7 1.08436e-6 1 0 1.12231e-6 1 0 3.36303e-7 1 0 7.82971e-7 1 0 1.27803e-6 1 0 3.20463e-7 1 8.82464e-7 1.34473e-6 1 0 1.37184e-6 1 -3.06654e-6 1.39972e-6 1 1.96978e-7 0 1 -2.05472e-7 0 1 6.82383e-6 1.41964e-6 1 -1.8118e-7 0 1 -3.08103e-6 1.44001e-6 1 0 0 1 0 0 1 0 0 1 1.38501e-6 0 1 5.061e-6 1.50148e-6 1 1.07359e-6 0 1 -1.39821e-6 0 1 1.89806e-6 0 1 8.58268e-7 0 1 3.16116e-7 3.30636e-5 1 0 0 1 -2.24466e-7 1.27549e-6 1 -4.82547e-7 0 1 0 0 1 0 1.68089e-7 1 0 1.27412e-6 1 -1.07653e-6 2.98349e-7 1 0 3.65616e-7 1 2.62243e-6 5.77711e-7 1 0 4.50367e-7 1 -2.0788e-6 2.05545e-7 1 -4.58925e-7 0 1 -2.50464e-6 0 1 -8.77997e-7 -1.90615e-7 1 -1.68035e-6 0 1 -9.57828e-7 -2.90318e-7 1 0 -9.16172e-7 1 5.21025e-6 -1.29652e-6 1 -7.67337e-6 -2.04292e-6 1 -1.64033e-5 -4.50128e-6 1 1.35002e-6 -2.60534e-6 1 1.69534e-5 -4.13579e-6 1 -1.71575e-6 -2.49769e-6 1 0 1.51112e-6 1 -1.70896e-5 -2.01451e-6 1 -2.49693e-6 -2.32283e-6 1 -4.77993e-6 1.50379e-6 1 1.09845e-6 1.23696e-5 1 0 -3.38973e-5 1 1.01276e-6 0 1 -8.99541e-6 0 1 0 1.64195e-6 1 -5.14642e-7 0 1 0 1.50835e-6 1 0 1.15762e-5 1 7.35237e-7 0 1 5.26807e-7 0 1 -9.68794e-6 0 1 -3.70343e-6 0 1 -6.11262e-7 -4.12424e-7 1 5.02275e-6 0 1 1.23447e-6 -1.58328e-7 1 0 -4.32749e-7 1 -2.98076e-6 -5.0292e-7 1 9.64682e-6 2.0847e-5 1 -4.48503e-6 -2.0596e-5 1 0 -5.75338e-7 1 0 -1.16093e-6 1 0 -5.8984e-7 1 0 -6.1659e-7 1 0 -2.08762e-7 1 -3.80908e-6 -6.28952e-7 1 -5.48546e-6 -6.56057e-7 1 0 -8.98328e-7 1 4.74976e-6 -5.76901e-7 1 -1.08878e-6 -6.048e-7 1 9.59327e-7 -4.39101e-7 1 0 -4.038e-7 1 1.32281e-6 -1.81645e-7 1 -2.85668e-7 0 1 -6.98087e-7 -1.15215e-5 1 -4.06025e-7 0 1 1.91919e-7 0 1 3.63675e-7 0 1 -4.66159e-7 0 1 2.17351e-7 0 1 -1.64214e-7 0 1 -2.00657e-7 0 1 0 0 1 4.03467e-7 0 1 1.66353e-5 0 1 -4.51311e-7 0 1 1.85692e-6 0 1 0.9997245 -0.02347451 0 0.999704 -0.02433097 5.0019e-4 0.9997146 -0.02389156 1.92668e-4 0.9997243 -0.02348589 -4.1762e-5 0.9997202 -0.02365869 8.70587e-5 0.9997331 -0.02310192 -1.76577e-4 0.9996872 -0.02500563 5.02964e-4 0.9997532 -0.02221006 -4.99604e-4 0.9997224 -0.0235669 2.07692e-5 0.9997199 -0.02367061 9.48476e-5 0.9995992 -0.02812182 -0.003256022 0.9997246 -0.02347111 0 0.9996963 -0.02462738 -9.00573e-4 0.9997519 -0.02225077 0.001072764 0.9997084 -0.02414125 -6.4129e-4 0.9997456 -0.02253645 0.001054883 0.9997202 -0.02365088 -4.73779e-4 0.9997298 -0.02324342 5.50821e-4 0.9997474 -0.02247816 -2.42384e-4 -0.02345097 -0.9997251 0 -0.0234512 -0.999725 0 -0.8148248 -0.579707 -7.01935e-4 -0.7035269 -0.7106685 -4.88306e-4 -0.8063129 -0.5914894 0 -0.9134395 -0.4069734 -9.76614e-4 -0.8917746 -0.4524794 7.62983e-4 -0.9483437 -0.3172438 8.85048e-4 -0.9700739 -0.2428084 -9.15567e-4 -0.9825353 -0.1860756 6.40903e-4 -0.9947503 -0.1023316 -3.96753e-4 -0.9972463 -0.0741617 6.10384e-5 -0.9996142 -0.02777212 -3.35707e-4 -0.999385 -0.03506666 -3.05193e-5 -0.7164443 -0.6976443 3.05195e-5 -0.628421 -0.7778735 3.6623e-4 -0.6128519 -0.7901978 -6.1038e-5 -0.5216587 -0.8531544 3.05188e-5 -0.5172353 -0.8558432 2.44152e-4 -0.4037131 -0.9148856 -2.44157e-4 -0.3923533 -0.9198146 2.44153e-4 -0.2720799 -0.9622747 -2.44155e-4 -0.2601103 -0.9655789 2.44149e-4 -0.1397463 -0.9901874 -2.13633e-4 -0.1301624 -0.9914927 1.22075e-4 -0.07461923 -0.9972122 -2.13634e-4 -0.06802594 -0.9976836 0 0.9997252 -0.02344173 0 0.9997254 -0.02343243 0 0.04568725 0.9989558 2.74673e-4 0.06070238 0.998156 -2.74671e-4 -0.09747892 0.9952376 -2.74675e-4 0.209058 0.9779033 3.05194e-5 0.2025269 0.9792767 2.74675e-4 0.3546928 0.9349828 5.18824e-4 0.3278684 0.9447234 -9.15577e-5 0.4452104 0.8954259 -6.40898e-4 0.497952 0.8672043 7.62981e-4 0.5766327 0.8170032 -7.93503e-4 0.632328 0.7747002 9.15577e-4 0.6989419 0.7151779 -9.15564e-4 0.7641102 0.6450852 8.85058e-4 0.803411 0.5954244 -7.93492e-4 0.8581572 0.5133867 5.79857e-4 0.8827539 0.4698356 -4.57781e-4 0.9158811 0.4014495 4.27269e-4 0.9342612 0.3565892 -4.27272e-4 0.9571678 0.2895339 4.27266e-4 0.973308 0.2295019 -7.01934e-4 0.9849731 0.1727075 4.27267e-4 0.988546 0.1509172 -9.76613e-4 0.9940937 0.1085253 3.96746e-4 -0.1039476 0.9945829 -3.0519e-5 -0.2529126 0.9674891 -5.18826e-4 -0.2255949 0.9742213 6.10376e-5 -0.3476125 0.9376382 6.40901e-4 -0.4025759 0.9153864 -7.62975e-4 -0.486723 0.8735561 7.93504e-4 -0.5378328 0.8430514 -6.40895e-4 -0.6186582 0.7856602 5.18829e-4 -0.6412554 0.7673276 -6.10371e-5 -0.7270216 0.6866146 6.10378e-5 -0.7289754 0.6845399 1.22076e-4 -0.8032949 0.5955815 -9.15575e-5 -0.8080281 0.5891439 9.15578e-5 -0.8735564 0.4867231 -1.52597e-4 -0.87213 0.4892742 -3.66223e-4 -0.9469665 0.321332 -5.79856e-4 -0.9238696 0.3827076 0 -0.9653144 0.2610896 5.7986e-4 -0.9902643 0.1391991 -5.1883e-4 -0.9926925 0.1206722 1.22076e-4 -0.998305 0.05819958 -2.13633e-4 -0.9987082 0.05081433 0 0.9997242 -0.02348458 0 0.9997244 -0.02347964 0 0.6686359 -0.7435901 2.4415e-4 0.559866 -0.8285833 2.4415e-4 0.6592757 -0.7519014 -2.44154e-4 0.5517246 -0.8340265 -1.22076e-4 0.4616939 -0.8870394 9.15575e-5 0.3599442 -0.9329739 1.22077e-4 0.4556536 -0.8901573 -9.1558e-5 0.3507522 -0.9364684 -2.4415e-4 0.2310291 -0.9729469 2.44152e-4 0.218759 -0.9757789 -2.44151e-4 0.09506684 -0.995471 2.44153e-4 0.0852704 -0.9963579 -1.22077e-4 0.0282914 -0.9995997 2.13635e-4 0.0215463 -0.9997679 0 0.7596507 -0.6503313 -2.44153e-4 0.7631593 -0.6462103 -3.0519e-5 0.8438838 -0.5365259 -5.18825e-4 0.8307569 -0.5566355 6.10379e-5 0.8892973 -0.4573293 6.40902e-4 0.9096542 -0.4153658 -6.40902e-4 0.9516229 -0.3072685 -6.10386e-5 0.9436488 -0.3309485 5.18824e-4 0.9811505 -0.1932454 0 0.9819233 -0.1892797 2.44153e-4 0.9922596 -0.1241812 -2.7467e-4 0.9934294 -0.1144468 2.44153e-4 -0.02345436 -0.9997249 1.26242e-5 -0.02344501 -0.9997252 1.53938e-5 -0.02352857 -0.9997233 0 -0.02343863 -0.9997254 3.05572e-5 -0.02350437 -0.9997238 -1.49588e-5 -0.02343696 -0.9997254 4.20421e-5 -0.02349925 -0.9997239 -2.11492e-5 -0.02343648 -0.9997254 5.23789e-5 -0.02350056 -0.9997239 -3.26331e-5 -0.0234403 -0.9997254 6.0015e-5 -0.02350282 -0.9997239 -4.7613e-5 -0.02344202 -0.9997253 6.86082e-5 -0.02350747 -0.9997237 -6.95036e-5 -0.02349478 -0.999724 -5.61303e-5 -0.02344596 -0.9997252 7.12145e-5 -0.02346831 -0.9997246 1.027e-5 -0.0234794 -0.9997244 4.71016e-5 -0.02348273 -0.9997243 6.19003e-5 -0.02346539 -0.9997248 -1.68e-5 -0.02345365 -0.9997249 -6.41789e-5 -0.02346467 -0.9997248 -2.18114e-5 -0.02347594 -0.9997245 2.08704e-5 -0.02347588 -0.9997245 1.58581e-5 -0.02345025 -0.9997251 -6.10581e-5 -0.02347666 -0.9997245 1.80298e-5 -0.02347278 -0.9997245 1.23965e-5 -0.02349877 -0.9997239 7.78288e-5 -0.02350771 -0.9997237 8.67038e-5 -0.02343595 -0.9997254 -8.80092e-5 -0.02343577 -0.9997254 -6.28355e-5 -0.0234574 -0.9997249 -2.73866e-5 -0.02345591 -0.9997249 -2.72748e-5 -0.02337688 -0.9997264 9.13581e-4 -0.02347135 -0.9997246 0 -0.02348124 -0.9997243 2.6943e-5 -0.02351301 -0.9997235 -4.37543e-4 -0.02349776 -0.9997239 -3.10216e-4 -0.02343738 -0.9997253 3.10606e-4 -0.02343791 -0.9997253 4.07381e-4 -0.02351933 -0.9997233 -5.74519e-4 -0.02339214 -0.9997259 0.001046597 -0.02351999 -0.9997231 -7.36112e-4 -0.02342361 -0.9997255 6.83521e-4 -0.02360469 -0.9997188 -0.002287566 -0.02341389 -0.9997254 0.001058936 -0.02347028 -0.9997246 -6.41867e-5 -0.02344369 -0.9997251 5.57394e-4 -0.02346038 -0.9997248 2.75379e-4 -0.0235117 -0.9997232 -9.69263e-4 -0.02348387 -0.9997242 -5.32153e-4 -0.02345025 -0.9997249 5.11784e-4 -0.02346628 -0.9997247 1.61455e-4 -0.02347093 -0.9997246 -2.94894e-7 -0.02282816 -0.9997392 7.32454e-4 -0.02258408 -0.9997447 7.93497e-4 -0.02102768 -0.999778 0.001312315 -0.0391556 -0.999216 -0.005859553 -0.02288913 -0.999738 3.96746e-4 -0.02240109 -0.9997488 7.32461e-4 -0.02362191 -0.9997211 -9.15579e-5 -0.02490371 -0.9996892 -0.001159727 -0.02850455 -0.9995827 -0.004699885 -0.04092562 -0.9988487 -0.02502536 -0.03778219 -0.9983286 -0.04373329 -0.03695821 -0.998147 -0.04834169 -0.03799557 -0.9983537 -0.04297012 -0.03705024 -0.9982824 -0.04538202 -0.03524893 -0.9982014 -0.04849398 -0.03454774 -0.998193 -0.0491665 -0.03601282 -0.9982268 -0.04739654 -0.03366285 -0.9981974 -0.04968553 -0.03979676 -0.9976062 -0.05655175 -0.03140419 -0.9982817 -0.04947155 -0.0461449 -0.9919024 -0.1183227 -0.04367297 -0.9980694 -0.04416126 -0.05078339 -0.9821585 -0.1810685 -0.05105811 -0.9856699 -0.1607737 -0.05011314 -0.9806254 -0.1893741 -0.04773187 -0.9800305 -0.1930335 -0.04538166 -0.9809095 -0.1890954 -0.04339772 -0.9822472 -0.1825023 -0.04474073 -0.9809095 -0.189248 -0.04388612 -0.9787709 -0.2002038 -0.0431838 -0.9778167 -0.204963 -0.03781318 -0.9904678 -0.132453 -0.03189241 -0.9901922 -0.1360236 -0.03811848 -0.9763097 -0.2129936 -0.0362572 -0.9754043 -0.2174211 -0.03891152 -0.9772144 -0.2086575 -0.04055994 -0.9769183 -0.2097277 -0.02993893 -0.9758707 -0.216287 -0.02578842 -0.9903365 -0.1362666 -0.03222817 -0.9764289 -0.2134202 -0.0193488 -0.9910333 -0.1322069 -0.01892167 -0.9817001 -0.1894915 -0.01593077 -0.9920129 -0.125127 -0.02478182 -0.9782111 -0.2061287 -0.02322524 -0.9781464 -0.2066162 -0.01074254 -0.9996066 -0.02591025 -0.008430361 -0.9999505 0.005295336 -0.004833579 -0.9999884 -1.69891e-4 -0.008850395 -0.9996982 -0.02291947 -0.01284843 -0.9990684 -0.04120057 -0.00589013 -0.9999583 -0.006988823 -0.01406919 -0.9958009 -0.09045797 -0.01446616 -0.9943233 -0.1054141 -0.01709049 -0.9981765 -0.05789405 -0.01767039 -0.9972947 -0.07135301 -0.01684629 -0.9910953 -0.132085 -0.02032554 -0.9919555 -0.1249443 -0.02398788 -0.9933319 -0.1127676 -0.0207529 -0.9937598 -0.1095937 -0.01168882 -0.9878154 -0.1551902 -0.01657158 -0.9899626 -0.1403551 -0.01513743 -0.9887866 -0.1485667 -0.007395386 -0.9999724 7.98704e-4 -0.01928818 -0.9824154 -0.1857097 -0.02188205 -0.9786522 -0.2043551 -0.02060061 -0.979674 -0.199536 -0.02594149 -0.9787877 -0.2032287 -0.02829068 -0.9764114 -0.2140573 -0.0257582 -0.978417 -0.2050284 -0.02713143 -0.9771603 -0.2107648 -0.03271651 -0.9765524 -0.2127796 -0.03439503 -0.9756354 -0.2166858 -0.04236108 -0.9771741 -0.2081736 -0.03668338 -0.9989669 -0.02682584 -0.0163275 -0.9822149 -0.1870493 -0.01721251 -0.9994252 -0.02920633 -0.01272648 -0.9995022 -0.02887111 -0.02331656 -0.9993165 -0.02868789 -0.02984768 -0.9991652 -0.02789443 -0.01519054 -0.9998825 0.002096712 -0.0143451 -0.9998971 -3.25184e-4 -0.01895326 -0.9998174 -0.002433657 -0.02191108 -0.9997515 0.004122316 -0.02522689 -0.9996705 -0.004760682 -0.02853816 -0.9995784 0.005358994 -0.03135681 -0.9994999 -0.004118621 -0.03585219 -0.9993356 0.006567418 -0.04513591 -0.9989809 -3.64182e-4 -0.05578947 -0.9984425 3.96752e-4 -0.04260414 -0.999092 4.57781e-4 -0.03518855 -0.9993807 0 -0.8232997 -0.5676056 -0.001220762 -0.7433437 -0.6689086 -0.001220703 -0.7972406 -0.6036604 0.00125122 -0.7038636 -0.7103338 0.001403868 -0.8940235 -0.4480189 -0.00100708 -0.8658872 -0.5002382 0.001037597 -0.9147964 -0.4039143 9.76597e-4 -0.9376281 -0.3476393 -7.3245e-4 -0.9568621 -0.2905409 0.00100708 -0.9685565 -0.2487922 -9.15575e-4 -0.9848007 -0.173686 8.85063e-4 -0.9904989 -0.1375192 -7.3246e-4 -0.9986785 -0.05139422 -2.74672e-4 -0.9972281 -0.07440447 5.79855e-4 -0.9996261 -0.02734518 4.27269e-4 -0.9998628 -0.01657176 -6.1038e-5 -0.653679 -0.756771 -0.001220703 -0.6092517 -0.7929763 0.001068115 -0.5578934 -0.8299122 -8.85061e-4 -0.5234928 -0.85203 7.32456e-4 -0.4687147 -0.8833493 -7.32462e-4 -0.4359349 -0.8999779 7.32459e-4 -0.3778852 -0.9258523 -7.32454e-4 -0.3441604 -0.9389106 7.32451e-4 -0.277477 -0.960732 -8.85045e-4 -0.2518454 -0.9677675 2.74674e-4 -0.2219653 -0.9750541 -0.001037597 -0.1732856 -0.9848716 1.83113e-4 -0.09756964 -0.9952287 4.57787e-4 -0.1466448 -0.9891893 3.35712e-4 -0.1375792 -0.9904907 4.88302e-4 -0.1245794 -0.9922097 3.05192e-5 -0.1610773 -0.9869418 3.05186e-5 -0.1653194 -0.9862402 0 -0.1550676 -0.987904 9.15574e-5 -0.1412119 -0.9899794 1.83115e-4 -0.1547008 -0.9879615 1.22076e-4 -0.1112421 -0.9937933 -2.13634e-4 -0.09497612 -0.9954796 -3.05193e-4 -0.0782507 -0.9969338 -1.22076e-4 -0.05975604 -0.998213 3.96746e-4 0.9997247 -0.02346509 0 0.9997248 -0.02346509 0 0.1012621 0.994859 0.001312315 0.06103861 0.9981346 -0.001312315 -0.06100821 0.9981364 0.001312315 0.2571857 0.9663615 0.001037597 0.2217488 0.9751029 -0.001312255 0.3864328 0.9223176 3.05191e-4 0.3767305 0.9263223 -0.001129209 0.4909304 0.8711986 4.88306e-4 0.5172128 0.8558562 -0.001068174 0.5973498 0.8019803 9.15572e-4 0.6231045 0.7821384 -6.10378e-4 0.68208 0.7312774 3.05195e-4 0.6933332 0.7206172 -3.3571e-4 0.7422598 0.6701121 4.2727e-4 0.7716198 0.6360836 -8.24021e-4 0.794777 0.6069017 -3.0519e-5 0.8447731 0.5351247 1.22077e-4 0.8579176 0.5137861 -0.001098632 0.9066585 0.4218642 0.001098632 0.919175 0.3938493 -4.88306e-4 0.9615371 0.2746726 0.001190245 0.95726 0.2892289 -2.44152e-4 0.9924414 0.1227161 0.001037597 0.9829547 0.1838462 -8.24012e-4 0.9966243 0.08209574 -5.18821e-4 0.9987829 0.04931807 6.40891e-4 0.9994073 0.03442543 0 -0.09741544 0.9952433 -0.001037597 -0.232095 0.9726932 -3.05187e-4 -0.2218425 0.9750819 0.00112915 -0.3363808 0.941726 -3.35709e-4 -0.3766044 0.9263737 9.76608e-4 -0.4178618 0.9085107 3.05187e-5 -0.4891321 0.8722097 3.05193e-5 -0.5215424 0.8532249 9.76614e-4 -0.5593539 0.828929 3.05191e-5 -0.6238349 0.7815561 3.05188e-5 -0.6491132 0.7606915 6.40904e-4 -0.6861279 0.7274811 3.0519e-5 -0.7421869 0.670193 3.66226e-4 -0.7411872 0.6712985 1.52596e-4 -0.7944471 0.6073335 -9.15578e-5 -0.8409324 0.54114 -4.27272e-4 -0.8007684 0.5989741 3.05194e-4 -0.8619757 0.5069494 4.88302e-4 -0.8825033 0.4703063 3.05195e-5 -0.9173454 0.3980921 3.6623e-4 -0.916735 0.399496 1.52596e-4 -0.946799 0.3218256 -9.15578e-5 -0.9697064 0.244273 -4.27264e-4 -0.9500838 0.3119947 3.05189e-4 -0.9787116 0.2052398 4.57784e-4 -0.9864845 0.1638545 3.05186e-5 -0.996441 0.08429306 3.66226e-4 -0.9962819 0.08615416 1.22075e-4 -0.9992236 0.03940004 -2.13633e-4 -0.9994105 0.034334 0 0.9997252 -0.02344608 0 0.9997252 -0.02344608 0 0.5443682 -0.8388463 4.57786e-4 0.6497225 -0.7601714 -5.18826e-4 0.6589992 -0.7521436 4.88306e-4 0.5347529 -0.8450084 -3.96746e-4 0.4366351 -0.8996387 3.35709e-4 0.4280312 -0.903764 -2.44153e-4 0.3388891 -0.9408263 2.44156e-4 0.3298189 -0.9440442 -3.35709e-4 0.2223043 -0.9749773 3.96754e-4 0.2110419 -0.9774768 -4.88311e-4 0.08813869 -0.9961081 4.57784e-4 0.07834172 -0.9969267 -2.4415e-4 0.02127176 -0.9997738 3.96748e-4 0.01446598 -0.9998955 0 0.7542927 -0.6565383 -5.18834e-4 0.7622773 -0.6472505 4.88307e-4 0.8424453 -0.5387817 -5.18822e-4 0.8467426 -0.5320028 1.22075e-4 0.910763 -0.4129289 -7.32468e-4 0.9047316 -0.4259822 2.13632e-4 0.9448497 -0.3275035 8.24023e-4 0.9546934 -0.2975901 -8.24011e-4 0.9801939 -0.1980408 -2.44156e-4 0.9771474 -0.2125626 6.10374e-4 0.9944931 -0.1048023 0 0.9948348 -0.1015069 1.22077e-4 0.9982511 -0.05911558 -1.83115e-4 0.9985119 -0.05453693 0 -0.0234704 -0.9997246 0 0.9997246 -0.02346885 0 0.9997245 -0.02347159 -1.09139e-5 0.999722 -0.02358233 0 0.9997256 -0.02342885 1.67225e-5 0.9997236 -0.02351331 1.32723e-6 -0.02347081 -0.9997246 0 -0.02347087 -0.9997246 0 0.9997246 -0.02346926 0 0.9997246 -0.02347064 0 0.02347093 0.9997246 0 0.02347087 0.9997246 0 0.9997246 -0.02347064 0 0.9997246 -0.02346926 0 0 -1 -7.49902e-7 0 -1 -2.59782e-7 0 -1 2.46239e-7 -1 0 0 -1 1.1535e-5 0 -1 -7.04964e-5 0 -1 3.58095e-5 0 -1 1.63891e-4 0 -1 -2.88272e-5 0 -1 -7.78938e-5 0 -1 -8.17072e-6 0 -1 2.36834e-5 0 -1 -2.28083e-5 0 -1 -2.98012e-6 0 -1 -3.51331e-6 0 -1 1.97351e-5 0 0.03546261 0.999089 0.02374351 0.024293 0.9996767 -0.007507622 0.03024464 0.9995093 0.00814867 0.0167244 0.4851915 0.874248 0.009643971 0.1614757 0.9868296 0.02301126 0.6466669 0.7624254 -9.15566e-5 -0.3765416 0.9263997 0.02493423 0 0.9996891 0.02496469 0 0.9996884 -4.27267e-4 -0.0730015 0.9973317 0.01535135 0.5251216 0.8508887 0.02835243 0.6111192 0.7910307 -0.01287913 0.3586016 0.9334019 0.02810823 0.6764603 0.7359425 0.02063119 0.6535762 0.7565796 0.05581974 0.9568405 -0.2852027 0.06091552 0.9958596 0.0674771 0.05584937 0.9906406 0.1245473 0.05066186 0.9319038 -0.3591499 0.03524965 0.9827482 0.1815586 0.03506684 0.9937451 0.1060247 -0.04953289 0.6140192 0.7877354 -0.03503578 0.4601352 0.8871573 -0.0315569 0.6300396 0.7759217 -0.051822 0.5382714 0.8411769 -0.0509966 0.5586742 0.827818 0.06558489 0.9978432 0.002746641 -0.0255137 0.2976809 0.9543245 -0.003875911 -0.5902142 0.8072375 0.04471069 0.9576328 -0.2845004 0.04773163 0.9394959 -0.3392183 0.01528996 0.9998299 0.01031535 0.05676543 0.9975458 -0.04098707 0.01156675 0.438164 0.8988206 0.02896273 0.532988 0.845627 -0.06363344 0.4474788 0.8920277 -0.06708133 0.3974217 0.9151809 -0.01101732 0.3586894 0.933392 0.0589168 0.9954394 -0.07502871 -0.06573772 0.4908662 0.8687514 0.04266583 0.9753019 -0.2167168 0.01312315 0.3402871 0.94023 -0.009613573 0.2552641 0.9668236 -0.06424278 0.3359548 0.9396846 0.02945065 0.4622381 0.8862667 0.03021401 0.3858241 0.9220775 0.01211583 0.9996667 0.02279734 0.009154975 0.9999581 -5.65959e-5 0.04074257 0.9738546 -0.2234891 0.01574754 0.2308119 0.972871 -0.06164902 0.2402786 0.9687444 -0.005554378 0.1571714 0.9875558 0.01599192 0.9997423 -0.01611399 0.02517801 0.9976617 -0.06354027 -0.06592059 0.2804983 0.9575883 0.03375405 0.9899154 -0.1375797 -0.001281738 0.02874881 0.9995859 0.02026438 0.101139 0.9946659 -0.05823057 0.1144469 0.9917213 0.06777346 0.9973648 -0.02588874 -0.04791504 0.639407 0.767374 -0.03003078 0.6596713 0.750954 -0.06247234 0.1525949 0.9863123 0.07511508 0.9850565 -0.1549887 0.03823977 0.9971957 0.0643332 0.04272663 0.9984605 0.03537154 0.02319413 0.9903588 0.1365706 0.03170883 0.9994847 0.005005002 0.04733461 0.9713215 0.233011 0.0335102 0.9634646 0.2657318 0.0421769 0.9988785 0.02151566 0.04358124 0.9248502 -0.3778262 0.02383506 0.9997003 -0.005584895 0.03970491 0.9376897 0.345198 0.03180116 0.9318171 0.3615323 0.04370403 0.9563618 0.2888984 0.04443544 0.9990042 0.004028439 0.04614514 0.9989274 -0.003845393 0.0330823 0.9988179 0.03561538 0.03497427 0.9750084 0.2193982 0.03265488 0.999454 -0.005035519 0.04464864 0.9989947 0.004028439 0.0306102 0.9995178 0.005218684 0.03036648 0.8937215 0.4475932 0.03308254 0.890605 0.4535731 0.03506606 0.9992764 0.01474052 0.03216707 0.9994694 -0.005127191 0.03186219 0.9994793 -0.005096733 0.03094655 0.9995074 0.005218744 0.03769087 0.9992215 -0.01165819 0.02932924 0.8532955 0.5206022 0.02938985 0.8490709 0.5274609 0.04577833 0.9989444 -0.003845334 0.03033602 0.8614033 0.5070149 0.0272842 0.8230435 0.5673226 0.02661293 0.7321306 0.6806443 0.02865725 0.7889443 0.6137962 0.05151659 0.9827218 0.177775 0.03650057 0.915903 0.3997367 0.02493387 0.7855855 0.6182507 0.0282303 0.7296242 0.6832655 0.0265519 0.7606668 0.6485994 0.02325552 0.7464979 0.6649813 0.02151578 0.6972952 0.7164611 0.02609366 0.5317922 0.8464729 0.03244161 0.2934399 0.9554269 -0.05322575 0.02008175 0.9983806 0.004516839 -0.08401948 0.996454 0.03521949 0.1982242 0.9795238 -0.009857654 0.006470024 0.9999305 -0.02978616 0.01620537 0.9994249 -0.02557498 0.04916626 0.9984632 -0.05163776 -1.83113e-4 0.9986659 0.04068225 -1.52597e-4 0.9991722 0.02560573 0.03155702 0.999174 -0.03543227 -0.2551371 0.9662556 -0.03164845 -0.2769931 0.9603506 -0.05432349 -0.01611393 0.9983934 -0.02527016 -0.2761406 0.960785 -0.02075308 -0.2532185 0.9671865 0.00814861 0.002563595 0.9999635 0.001068174 0.1925463 0.9812874 0.007355034 0.1251581 0.9921095 0.04467934 0.00238043 0.9989986 0.0145272 0.0787093 0.9967918 0.02490383 0.05621677 0.998108 0.02954697 0.05539441 0.9980273 0.04217743 0.09558594 0.9945273 0.04986757 2.4415e-4 0.9987559 0.03985834 0.1913567 0.980711 0.04294043 0.1729216 0.9839991 0.0518828 1.22077e-4 0.9986532 0.0463581 0.1484436 0.9878337 0.05383545 9.15569e-5 0.9985499 0.05585026 -0.001617491 0.9984379 0.04980772 0.1235427 0.9910885 0.0537129 0.08874839 0.9946048 0.05838209 6.10372e-4 0.9982942 0.0600754 0.0034042 0.9981881 -0.003845453 0.2681141 0.9633795 -0.02423173 -0.01797544 0.9995447 0.001648008 -0.07852596 0.9969108 -0.05166816 -9.15562e-5 0.9986643 0.04068213 -0.002014219 0.9991702 -0.0806005 0.814276 0.5748549 -0.08008313 0.8225308 0.5630541 -0.07126218 0.8659193 0.4950814 0.02410966 0.01440477 0.9996055 0.03973531 0.02462852 0.9989067 -0.05932903 0.06558549 0.9960817 0.03759944 0.1011707 0.9941583 -0.03326535 0.6914005 0.7217056 -0.02697873 0.7063609 0.7073375 -0.04507672 0.6904646 0.7219604 -0.04239153 0.7261192 0.6862608 -0.02508687 0.7355169 0.6770418 -0.0368365 0.6349495 0.7716749 -0.0372945 0.7730531 0.6332442 -0.02087479 0.7772809 0.6288074 -0.03524976 0.7959438 0.6043435 -0.01864713 0.8030795 0.5955802 -0.01382523 0.8431269 0.5375369 -0.04367315 0.887167 0.4593772 -0.01544278 0.8251519 0.5646997 -0.01800614 0.8147342 0.5795551 -0.06805813 0.8495674 0.5230713 -0.06589037 0.8485183 0.525048 -0.004913508 0.9235652 0.3834099 -0.07083612 0.7355545 0.6737521 -0.073062 0.8331637 0.548179 -0.06668478 0.76805 0.6369084 -0.004577934 0.8706651 0.491855 -0.06006222 0.8948297 0.4423486 -4.883e-4 0.896396 0.4432539 -0.03289973 0.890796 0.453211 -0.02551424 0.8948613 0.4456147 -0.01919645 0.8882884 0.4588849 -0.03451758 0.9111301 0.4106708 0.005310237 0.9199305 0.3920454 -0.03195321 0.9210596 0.3881085 -0.06531113 0.873857 0.4817765 0.01059013 0.9407569 0.3389166 -0.0174266 0.9394822 0.3421543 -0.08905506 0.7666428 0.635868 -0.08636921 0.7938647 0.6019296 -0.08874875 0.7743847 0.62646 -0.1343138 0.05639898 0.9893326 -0.1344367 0.06451737 0.9888196 -0.1344978 0.05530065 0.9893696 -0.134804 0.1084353 0.9849212 -0.1339808 0.03518903 0.9903591 -0.1342823 0.04535079 0.9899049 -0.1336118 0.02551376 0.9907053 -0.1334307 0.01568692 0.9909341 -0.1334293 0.01440495 0.9909537 -0.1333082 0.006561636 0.9910529 -0.1330032 -3.96751e-4 0.9911156 -0.1328188 -0.03027486 0.9906778 -0.1341919 -0.003051877 0.9909508 -0.1352604 -0.04748761 0.9896715 -0.1369375 -0.002288877 0.9905771 -0.1377947 -0.04950231 0.9892231 -0.1410593 -0.0495935 0.9887582 -0.1397163 -8.24015e-4 0.9901914 -0.1409683 0.001312315 0.9900133 -0.1445969 0.01663261 0.9893509 -0.1425554 0.5409233 0.828903 -0.1304099 0.5872261 0.7988485 -0.1342546 0.005279839 0.9909329 -0.134468 0.5169055 0.8454153 -0.1370301 0.4428607 0.8860571 -0.1222907 0.003967463 0.9924864 -0.1377646 0.3672706 0.9198551 -0.1272028 0.4187501 0.8991484 -0.1284861 0.3259764 0.936606 -0.1112109 0.004364192 0.9937873 -0.1273861 0.2388718 0.9626594 -0.1167972 0.3011335 0.9464023 -0.1145366 0.09750717 0.9886221 -0.1045275 3.66228e-4 0.994522 -0.1342533 0.07364243 0.9882069 -0.1345594 0.08267664 0.9874505 -0.1348007 0.091861 0.9866055 -0.1349544 0.1009259 0.9856984 -0.1348944 0.1171933 0.9839051 -0.1350165 0.1085259 0.9848821 -0.1345589 0.1237856 0.9831435 -0.134987 0.1545194 0.9787248 -0.1347109 0.1402348 0.9809114 -0.1347409 0.1325435 0.9819761 -0.1347406 0.1892778 0.9726351 -0.1342535 0.1464916 0.9800594 -0.1344073 0.1542449 0.9788479 -0.1345283 0.1623007 0.9775279 -0.1344655 0.172919 0.9757142 -0.1341604 0.2201623 0.9661933 -0.1339482 0.1804898 0.9744133 -0.1338856 0.1933056 0.9719607 -0.1331557 0.2015189 0.9703915 -0.1332778 0.2508992 0.9587944 -0.1333058 0.2134785 0.9678102 -0.1331239 0.2264207 0.9648895 -0.1320253 0.2815381 0.950424 -0.1322693 0.2301438 0.9641259 -0.1323016 0.242263 0.9611477 -0.1320564 0.2536448 0.9582409 -0.1305296 0.311324 0.9412966 -0.1310173 0.2577621 0.9572843 -0.1309892 0.2713785 0.9535175 -0.1287598 0.3410195 0.9311965 -0.1306834 0.2833713 0.9500645 -0.1295248 0.2885316 0.948669 -0.1291892 0.302937 0.9442136 -0.1267157 0.3704113 0.920184 -0.1276921 0.3129432 0.941149 -0.09665417 0.7002317 0.7073427 -0.09702014 0.6970863 0.7103927 -0.1014773 0.6648671 0.7400367 -0.1050172 0.6291877 0.7701262 -0.1080691 0.6031548 0.7902692 -0.1095032 0.5782797 0.8084563 -0.1275998 0.3236231 0.9375428 -0.1102656 0.5805656 0.8067125 -0.1272642 0.331772 0.9347359 -0.1041929 0.6456971 0.7564517 -0.1010786 0.6661977 0.7388938 -0.111548 0.5557868 0.8238072 -0.1239711 0.3995336 0.9082974 -0.1254959 0.3423669 0.9311476 -0.106299 0.6249149 0.7734222 -0.1253432 0.3545441 0.9266 -0.1137742 0.5317296 0.8392373 -0.1247003 0.3692178 0.9209387 -0.1138681 0.5228597 0.8447791 -0.1209766 0.4304376 0.8944765 -0.1226887 0.3826543 0.9157091 -0.117742 0.4708767 0.8743066 -0.1212834 0.4221113 0.8983944 -0.1192085 0.4503127 0.8848774 -0.1154531 0.5051187 0.8552927 -0.1175293 0.4788763 0.8699795 -0.09326797 0.7323185 0.6745449 -0.0911917 0.7537053 0.6508552 -0.09238046 0.7351068 0.6716278 -0.001556396 0.9482112 0.317637 -0.01208537 0.9425401 0.3338748 -0.01635843 0.9615461 0.2741563 -0.01947093 0.9537118 0.3000912 0.01632785 0.9563876 0.2916437 0.01556491 0.9705488 0.2404016 -5.18827e-4 0.9746005 0.22395 -0.01287889 0.9681182 0.2501628 0.0032655 0.9775186 0.2108241 0.01702946 0.9768459 0.2132654 0.01007133 0.972465 0.2328312 -0.00225836 0.9842889 0.1765506 0.03451675 0.989817 0.1380977 0.0185554 0.9950947 0.09717172 0.03763008 0.996847 0.06985831 0.001007139 0.9885225 0.1510708 0.02066117 0.9963447 0.08288884 0.01599192 0.9985802 0.05081403 0.01956248 0.9995202 0.02401822 0.04632788 0.9989192 -0.003784358 0.03018337 0.9995304 0.005279779 0.0328083 0.9994494 -0.004974603 0.03109902 0.9995025 0.005249261 0.04510682 0.9989738 0.004089474 0.03717249 0.9992325 -0.01236027 0.04553467 0.9989556 -0.003814876 0.03158682 0.9994879 -0.005127131 0.04876905 0.9987894 0.006439447 0.03036618 0.9995211 0.005951106 0.06131225 0.9981173 0.001648008 0.04284954 0.9794965 0.1968515 0.0368058 0.9559133 0.2913335 0.03366243 0.9766997 0.2119545 0.02493393 0.9893937 0.1431033 0.01791471 0.9998376 0.001983702 0.01464909 0.9998927 3.0519e-5 0.05499523 0.9931502 0.1030933 0.06385606 0.9979592 1.61586e-4 0.0456565 0.9989498 -0.003845393 0.04489368 0.9989836 0.004059016 0.004821896 0.9919782 0.1263167 -0.02893221 0.9301344 0.3660781 -0.05206531 0.002105772 0.9986416 -0.06430321 0.2003563 0.9776107 -0.05670452 0.8232233 0.5648788 0.06797486 0.9944381 -0.08045101 3.66225e-4 0.1194809 0.9928364 -6.10384e-5 0.06451755 0.9979166 3.05192e-5 0.04767096 0.9988632 -3.66234e-4 0.1442963 0.9895344 3.05188e-5 0.1949539 0.9808125 -3.9675e-4 0.21925 0.9756687 3.35711e-4 0.3472776 0.9377624 -4.27273e-4 0.2900878 0.957 4.2727e-4 0.2976545 0.9546737 -3.35715e-4 0.3539347 0.9352702 -2.74675e-4 0.4091435 0.9124701 2.74674e-4 0.4665789 0.8844796 -2.74668e-4 0.4639443 0.8858644 1.83117e-4 0.5002156 0.8659009 -2.13631e-4 0.5996923 0.8002306 -3.05192e-5 0.5563964 0.830917 4.27264e-4 0.6100115 0.7923924 3.05196e-5 0.5378467 0.8430427 1.83116e-4 0.5699176 0.821702 3.05192e-4 0.6516456 0.7585237 3.35705e-4 0.7018381 0.7123365 9.15568e-5 0.7229328 0.6909185 0 0.704416 0.7097874 2.44154e-4 0.6806103 0.7326457 0 0.6752601 0.7375797 -1.22077e-4 0.641852 0.7668286 2.44151e-4 0.7651985 0.6437946 1.83115e-4 0.7576061 0.6527119 6.10386e-5 0.7349053 0.6781698 1.52597e-4 0.7451927 0.6668493 3.05188e-4 0.8244042 0.5660015 6.10386e-5 0.8128809 0.5824299 2.44152e-4 0.8051234 0.5931075 1.22076e-4 0.778541 0.6275938 2.13637e-4 0.7834378 0.6214703 9.15573e-5 0.8652166 0.5013983 1.83117e-4 0.8505772 0.5258502 3.05196e-4 0.8593695 0.5113551 2.13635e-4 0.8329929 0.5532838 2.74667e-4 0.8413351 0.5405139 3.05192e-4 0.8999186 0.4360578 3.9675e-4 0.9077333 0.4195477 6.10386e-5 0.9162814 0.4005355 5.18825e-4 0.8775162 0.4795469 5.79859e-4 0.8932583 0.4495437 2.44153e-4 0.8815771 0.4720402 -2.7467e-4 0.9307656 0.3656165 9.1556e-5 0.9237698 0.3829483 -1.52595e-4 0.9376047 0.347703 -5.49336e-4 0.9436073 0.3310667 -5.18826e-4 0.9489332 0.3154768 -0.001098692 0.9562937 0.292406 -0.001281797 0.9705675 0.240826 -7.01942e-4 0.9683446 0.2496167 -4.57791e-4 0.9785442 0.2060366 -6.40906e-4 0.9847364 0.1740517 0 0.9851443 0.1717288 9.15567e-5 0.9937867 0.1113024 -1.83111e-4 0.9942033 0.1075169 0 0.996864 0.07913506 0 0.7968211 0.6042155 -9.15577e-5 0.5113192 0.859391 2.13636e-4 0.4289809 0.9033136 9.15573e-5 0.3929945 0.9195408 2.13636e-4 0.2483981 0.968658 2.44153e-4 0.04510724 0.9989821 -1 1.0359e-5 0 -1 -2.33492e-6 0 -1 -1.16523e-5 0 -1 2.39757e-5 0 -0.9999986 0.001660466 0 -1 -1.32857e-5 0 -1 -5.25508e-4 0 -1 -2.99516e-4 0 -1 -2.53078e-5 0 -1 7.01557e-5 0 -1 -6.1583e-5 0 -1 -1.45845e-6 0 -1 2.98433e-6 0 -0.5983195 0.8012577 -1.61003e-4 -0.5990094 0.8007418 -6.48391e-4 -0.5992646 0.8005509 5.59236e-4 -0.5988544 0.8008578 -6.94162e-4 -0.5994893 0.8003823 9.11705e-4 -0.6000218 0.7999826 0.001350581 -0.5988752 0.8008422 -6.34971e-4 -0.5984876 0.8011314 -0.001068472 -0.5986601 0.8010029 -7.15105e-4 -0.597324 0.8019968 -0.002299726 -0.600704 0.799469 0.002020895 -0.6024551 0.7981438 0.003817558 -0.6005041 0.7996202 0.001617252 -0.6005262 0.7996051 -2.5341e-4 -0.599144 0.8006414 0 -0.59937 0.8004721 -2.26501e-5 -0.5990512 0.8007107 3.28252e-5 -0.5994825 0.800388 -6.52037e-5 -0.5981674 0.8013712 2.20921e-4 -0.5991137 0.8006641 2.4649e-5 -0.5992459 0.8005651 -1.54397e-5 -0.5995394 0.8003453 -8.75399e-5 -0.5990075 0.8007435 4.81706e-5 -0.5983931 0.8012028 2.75665e-4 -0.599693 0.8002303 -1.65999e-4 -0.5987064 0.8009687 1.84537e-4 -0.5999188 0.8000609 -2.57772e-4 -0.5986828 0.8009862 1.95142e-4 -0.5996981 0.8002263 -1.98469e-4 -0.5998649 0.8001012 -3.02013e-4 -0.5988661 0.8008493 1.39802e-4 -0.599 0.8007491 9.27795e-5 -0.5990812 0.8006883 5.80995e-5 -0.599937 0.8000472 -3.47484e-4 -0.5989706 0.8007711 1.08079e-4 -0.5992113 0.8005909 -2.70742e-5 -0.5984684 0.8011465 3.70301e-4 -0.5996823 0.8002382 -2.5593e-4 -0.5994932 0.80038 -1.66501e-4 -0.5988471 0.8008634 2.01632e-4 -0.5995306 0.8003519 -2.07837e-4 -0.5993552 0.8004834 -9.91627e-5 -0.5987467 0.8009385 2.91663e-4 -0.5992933 0.8005297 -5.45904e-5 -0.5990056 0.8007448 1.32377e-4 -0.5993851 0.8004609 -1.48883e-4 -0.5991519 0.8006354 3.49669e-5 -0.5990533 0.8007091 1.41624e-4 -0.5993814 0.8004636 -1.70853e-4 -0.599174 0.8006189 2.11508e-6 -0.5992436 0.8005667 -5.77743e-5 -0.5991894 0.8006074 9.53424e-6 -0.599372 0.8004707 -1.72937e-4 -0.5986905 0.8009803 -4.48798e-4 -0.5994929 0.8003801 2.6348e-4 -0.5993029 0.8005224 8.15855e-5 -0.5989551 0.8007826 -1.76457e-4 -0.5992407 0.800569 3.97402e-5 -0.5995399 0.800345 2.68163e-4 -0.5990096 0.800742 -1.13213e-4 -0.5990409 0.8007184 -1.09384e-4 -0.5994259 0.8004304 1.56577e-4 -0.5989137 0.8008136 -1.56687e-4 -0.5994012 0.8004488 1.10052e-4 -0.5998634 0.8001024 3.4525e-4 -0.5990051 0.8007454 -8.85336e-5 -0.598936 0.8007969 -1.01107e-4 -0.599117 0.8006616 -3.17521e-5 -0.5987573 0.8009306 -1.88057e-4 -0.5995113 0.8003664 1.56656e-4 -0.5999644 0.8000267 3.18804e-4 -0.5988972 0.8008261 -1.24723e-4 -0.5995647 0.8003264 1.3681e-4 -0.598653 0.8010085 -1.90671e-4 -0.5989612 0.8007781 -5.94234e-5 -0.5994078 0.8004438 8.92142e-5 -0.598963 0.8007768 -5.8802e-5 -0.5992066 0.8005945 1.0067e-5 -0.5992247 0.800581 1.00306e-5 -0.5991224 0.8006576 -1.21853e-5 -0.5983995 0.8011979 -1.85862e-4 -0.5995246 0.8003564 1.00467e-4 -0.5998612 0.8001042 1.42622e-4 -0.5994074 0.8004442 5.37095e-5 -0.5991654 0.8006253 1.37304e-5 -0.6000057 0.7999958 1.46177e-4 -0.5997194 0.8002104 8.29366e-5 -0.5987772 0.8009156 -5.96164e-5 -0.5985823 0.8010613 -6.36056e-5 -0.5984554 0.8011562 -8.13019e-5 -0.59883 0.8008763 -2.87839e-5 -0.6001977 0.7998518 1.04233e-4 -0.6003975 0.7997018 9.06774e-5 -0.5987516 0.8009349 -3.27917e-5 -0.5988813 0.8008379 -1.19516e-5 -0.5983855 0.8012084 -4.52834e-5 -0.6088497 0.7932626 -0.006062805 -0.5990115 0.8007404 0 -0.5969973 0.8022421 0.001372754 -0.5984396 0.8011679 6.04162e-4 -0.5985963 0.8010509 1.61404e-4 -0.5983012 0.8012712 5.17752e-4 -0.5989575 0.8007809 -2.66175e-4 -0.5988517 0.8008601 -5.88209e-5 -0.6002721 0.7997958 5.48597e-5 -0.5991335 0.800649 -6.77182e-4 0 -0.6752601 0.7375797 -3.05194e-4 -0.7018841 0.7122912 0 -0.7044773 0.7097265 -1.22076e-4 -0.7229626 0.6908873 -2.44153e-4 -0.6805155 0.7327337 -4.27273e-4 -0.6098715 0.7925003 2.13635e-4 -0.5996728 0.8002453 -6.1039e-5 -0.5584766 0.8295204 -1.83113e-4 -0.5697574 0.8218131 3.05188e-5 -0.5248925 0.8511686 -6.10386e-5 -0.5378112 0.8430653 -9.15574e-5 -0.4879397 0.8728774 -1.83116e-4 -0.5001205 0.8659558 3.05188e-5 -0.4438045 0.8961237 3.05195e-5 -0.4669171 0.8843011 1.52597e-4 -0.4010238 0.9160677 -6.10383e-5 -0.4291907 0.903214 -2.13633e-4 -0.3927182 0.9196589 3.05193e-4 -0.3531394 0.9355707 -3.3571e-4 -0.347033 0.9378529 4.27268e-4 -0.2907256 0.9568064 -4.27261e-4 -0.297618 0.9546849 4.27269e-4 -0.2195245 0.9756069 -2.44151e-4 -0.2483621 0.9686673 0 -0.1950772 0.9807879 3.96752e-4 -0.1441126 0.9895613 -3.96743e-4 -0.1197553 0.9928034 6.10386e-5 -0.06445676 0.9979205 -3.05192e-5 -0.04770141 0.9988617 -2.44152e-4 -0.04522907 0.9989767 -3.0519e-4 -0.6515802 0.7585797 1.22076e-4 -0.641786 0.7668837 -6.10385e-5 -0.7349345 0.6781381 -1.52597e-4 -0.7451639 0.6668814 -2.44151e-4 -0.7651985 0.6437946 -1.83115e-4 -0.757578 0.6527446 -2.44151e-4 -0.7834495 0.6214554 -1.22077e-4 -0.7785142 0.6276272 0 -0.7968211 0.6042155 -2.44157e-4 -0.8051379 0.5930876 -3.05188e-4 -0.8244042 0.5660015 -6.10388e-5 -0.812945 0.5823405 -2.13631e-4 -0.8329789 0.553305 -2.74674e-4 -0.8413262 0.5405278 -3.05189e-4 -0.8593212 0.5114361 -1.83114e-4 -0.8505635 0.5258722 -5.18831e-4 -0.8774963 0.4795832 -9.15583e-5 -0.8651956 0.5014345 -2.4415e-4 -0.8815966 0.4720038 -5.79867e-4 -0.8932705 0.4495193 -3.96745e-4 -0.9077216 0.4195729 -3.05187e-4 -0.8999364 0.4360211 -9.15567e-5 -0.9238066 0.3828594 -6.10379e-5 -0.9162701 0.400561 2.7467e-4 -0.9307656 0.3656165 1.52597e-4 -0.9376147 0.3476762 5.18826e-4 -0.9489027 0.3155684 5.49347e-4 -0.9435943 0.3311034 7.32457e-4 -0.9681558 0.2503477 0.001068174 -0.9562656 0.2924983 0.001312315 -0.9705675 0.240826 5.18828e-4 -0.9784479 0.2064934 3.05192e-5 -0.9852818 0.170938 6.71429e-4 -0.9847416 0.174022 -6.10382e-5 -0.9938547 0.1106927 0 -0.996864 0.07913506 2.13636e-4 -0.994203 0.1075201 0 -0.9968663 0.07910472 -0.5991452 0.8006404 -1.66891e-4 -0.5992079 0.8005936 0 -0.599216 0.8005874 -2.31777e-5 -0.5991974 0.8006014 -5.15905e-6 -0.5989315 0.8008002 3.84049e-4 -0.5993699 0.8004723 -2.6347e-4 -0.5991758 0.8006175 8.73555e-5 -0.5990752 0.8006927 1.02639e-4 -0.5994954 0.8003783 -3.29684e-4 -0.5989667 0.800774 1.65593e-4 -0.5994537 0.8004095 -2.27401e-4 -0.5989235 0.8008064 1.4034e-4 -0.5992785 0.8005406 -5.93137e-5 -0.5993545 0.8004838 0 -0.5992107 0.8005914 2.65894e-5 -0.5991967 0.8006018 -6.70351e-6 -0.5989812 0.800763 3.31978e-4 -0.5991969 0.8006016 3.18519e-4 -0.599504 0.8003715 6.97216e-4 -0.5990519 0.8007094 0.001203358 -0.5992532 0.8005594 -5.88954e-4 -0.5992615 0.8005523 -0.001378715 -0.5991514 0.8006358 2.08323e-4 -0.5990967 0.8006767 5.44891e-4 -0.5993048 0.800521 -4.07213e-4 -0.5992157 0.8005877 -9.31734e-5 -0.5995209 0.8003587 -9.88345e-4 -0.599053 0.8007094 3.90376e-4 -0.5991991 0.8006001 -7.78383e-5 -0.5991103 0.8006666 1.42449e-4 -0.5989167 0.8008111 5.80053e-4 -0.599105 0.8006706 1.30731e-4 -0.5990365 0.8007218 2.78067e-4 -0.5992954 0.800528 -1.73641e-4 -0.5997157 0.8002129 -8.24742e-4 -0.5990755 0.8006926 1.75978e-4 -0.5994235 0.800432 4.87079e-4 -0.5996816 0.8002383 9.23782e-4 -0.5987074 0.8009677 -5.53578e-4 -0.5988076 0.8008929 -5.03813e-4 -0.5992075 0.8005938 -7.76252e-6 -0.5992578 0.800556 3.21639e-4 -0.597549 0.8018276 0.002776086 -0.5993067 0.8005196 2.62787e-4 -0.5999056 0.8000704 -9.27643e-4 -0.5976264 0.8017721 0.002086341 -0.6005354 0.7995963 -0.001773834 -0.5985491 0.8010855 9.94428e-4 -0.5987057 0.8009689 6.83353e-4 -0.599988 0.800008 -0.001358211 -0.599631 0.8002761 -9.77237e-4 -0.5988872 0.8008332 6.30561e-4 -0.5989953 0.8007523 6.51873e-4 -0.599 0.8007487 6.85845e-4 -0.5992713 0.8005458 -6.67283e-4 -0.599265 0.8005506 -5.94976e-4 -0.599142 0.8006429 0 -0.5989911 0.8007558 -1.37334e-4 -0.6005349 0.7995969 -0.001628816 -0.5964754 0.8026245 0.003318011 -0.6004493 0.7996613 -0.001652061 -0.5992107 0.8005915 9.8414e-6 -0.5988786 0.8008391 -0.001083374 -0.5992205 0.800584 1.54514e-4 -0.5991261 0.8006546 -4.24247e-4 -0.5991818 0.8006131 -1.56654e-5 -0.5993228 0.8005076 1.17534e-4 -0.5993006 0.8005235 0.001077592 -0.5990601 0.8007041 -1.77966e-4 -0.5996257 0.8002805 5.09501e-4 -0.599721 0.8002089 7.13748e-4 -0.599085 0.8006854 -1.46584e-4 -0.5989381 0.8007953 -3.7635e-4 -0.5990785 0.8006904 -2.17999e-4 -0.5990066 0.800744 -3.03649e-4 -0.5992093 0.8005926 5.71226e-5 -0.5986887 0.8009813 -9.68751e-4 -0.5992154 0.8005879 3.35521e-5 -0.599043 0.8007168 -3.72684e-4 -0.5994564 0.8004072 5.84077e-4 -0.5991748 0.8006183 -8.38584e-5 -0.5991246 0.8006557 -1.57472e-4 -0.5993299 0.8005022 3.22696e-4 -0.5989594 0.8007792 -5.73852e-4 -0.5992583 0.8005558 1.96246e-4 -0.5994815 0.8003884 6.6416e-4 -0.5988844 0.8008353 -7.07676e-4 -0.5989528 0.8007843 -5.57603e-4 -0.5991743 0.8006188 -7.15668e-6 -0.5995227 0.8003575 7.38361e-4 -0.5992023 0.8005977 3.05404e-6 -0.5993504 0.8004868 7.73443e-5 -0.5991265 0.8006544 -4.11489e-5 -0.5991377 0.800646 -3.77186e-5 -0.5993615 0.8004785 9.69321e-5 -0.5992258 0.80058 2.73698e-5 -0.5993099 0.8005172 8.92777e-5 -0.5990242 0.8007309 -1.45677e-4 -0.5991742 0.8006188 -3.28962e-5 -0.5994653 0.8004008 2.63906e-4 -0.5991441 0.8006413 -5.94653e-5 -0.5990163 0.8007369 -1.82959e-4 -0.599344 0.8004918 -1.01549e-4 -0.5991933 0.8006044 4.60664e-6 -0.5992204 0.8005843 -1.82054e-5 -0.5988444 0.8008655 1.96491e-4 -0.599424 0.8004318 -1.1872e-4 -0.599175 0.8006181 1.15426e-5 -0.5991738 0.800619 1.18486e-5 -0.5993827 0.8004627 -1.3312e-4 -0.5990135 0.800739 2.54142e-4 -0.5991877 0.8006086 -5.17669e-6 -0.5989856 0.8007599 2.88773e-4 -0.5994316 0.800426 -3.24559e-4 -0.599847 0.8001143 -7.69992e-4 -0.5987778 0.8009151 4.45347e-4 -0.5995094 0.8003677 -3.49042e-4 -0.5987656 0.8009243 5.13095e-4 -0.5991311 0.8006511 5.99873e-5 -0.5993694 0.8004726 -2.18166e-4 -0.5990541 0.8007086 1.70815e-4 -0.599044 0.8007161 1.34015e-4 -0.5994002 0.8004496 -1.93916e-4 -0.5992475 0.8005638 -2.94758e-5 -0.5993717 0.8004708 -1.79256e-4 -0.5986093 0.8010411 5.27309e-4 -0.5985073 0.8011173 5.77694e-4 -0.5997375 0.8001967 -4.75959e-4 -0.5991819 0.8006131 -1.4439e-4 -0.5997481 0.8001887 -4.92655e-4 -0.5989181 0.8008097 -0.001053869 -0.5994673 0.8003984 0.001137971 -0.5988455 0.8008633 -0.001502037 -0.5994659 0.8003993 0.001255452 -0.5992714 0.8005459 4.43594e-4 -0.5993629 0.8004771 8.53524e-4 -0.5989669 0.800773 -0.001213014 -0.5992931 0.8005296 4.99538e-4 -0.5992295 0.8005774 2.20947e-4 -0.599305 0.8005204 7.59189e-4 -0.5993137 0.8005136 0.001032471 -0.5990948 0.800678 -7.21952e-4 -0.5991394 0.8006445 -6.76792e-4 -0.5991875 0.8006088 -1.54033e-4 -0.5991774 0.8006165 -5.84896e-5 -0.5991742 0.8006188 -1.93521e-4 -0.5991895 0.8006073 2.12658e-4 -0.5991867 0.8006094 1.00707e-4 -0.5991829 0.8006123 0 2.96231e-7 -1 -9.47187e-6 2.97893e-7 -1 0 1.65703e-7 -1 0 0 -1 0 0 -1 2.80082e-7 0 -1 -1.58258e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -3.11325e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -2.00401e-6 -1 8.46382e-6 2.4131e-6 -1 0 -1.91807e-7 -1 0 -1.73125e-7 -1 0 -2.15958e-7 -1 1.66062e-6 0 -1 0 0 -1 0 -3.14832e-7 -1 -1.47743e-6 -3.45834e-7 -1 0 -9.57857e-7 -1 0 0 -1 -1.34771e-4 0 -1 1.49276e-4 -2.43772e-6 -1 3.18847e-5 -1.40289e-5 -1 0 -5.73622e-6 -1 -3.23102e-4 -1.15466e-5 -1 1.63305e-4 -1.49117e-5 -1 0 -8.15881e-6 -1 1.26167e-4 0 -1 -6.39959e-5 2.76848e-7 -1 -2.89436e-5 -1.068e-6 -1 -2.27555e-5 -5.54571e-7 -1 -2.2832e-5 -6.37865e-7 -1 1.53121e-5 -3.29361e-7 -1 1.62405e-6 0 -1 0 -2.98929e-7 -1 0 -3.04776e-7 -1 0 -2.21617e-7 -1 2.65495e-6 -2.54176e-7 -1 2.32227e-5 0 -1 0 -2.10451e-7 -1 -1.63883e-5 -1.89179e-7 -1 0 0 -1 2.11238e-5 0 -1 0 -1.70162e-7 -1 -1.89372e-5 -1.51535e-7 -1 0 -1.53951e-7 -1 1.67718e-5 -1.4138e-7 -1 1.50353e-5 0 -1 -1.56216e-5 -9.85057e-7 -1 1.59822e-6 -9.44789e-7 -1 0 -8.00261e-5 -1 0 -2.43554e-4 -1 3.84615e-4 2.3975e-6 -1 -2.25677e-6 -3.03597e-7 -1 9.66729e-7 0 -1 0 2.60048e-7 -1 0 -1.38627e-7 -1 -2.13296e-6 -1.89791e-7 -1 0 1.75895e-7 -1 3.33814e-6 0 -1 -8.3798e-7 0 -1 0 0 -1 -4.94131e-7 -0.9341574 -0.2208052 0.280348 -0.931811 -0.2346007 0.2769309 -0.941539 -0.2063994 0.2662775 -0.9547625 -0.1377636 0.2635332 -0.951347 -0.1536035 0.2671048 -0.9558809 -0.1428282 0.2566941 -0.9512228 -0.1605921 0.2634113 -0.9591904 -0.1315075 0.2503191 -0.9505059 -0.1899791 0.2458589 -0.9443465 -0.2056363 0.2567555 -0.9634362 -0.1585177 0.2160162 -0.9579881 -0.1653819 0.234324 -0.9693014 -0.1520179 0.1932498 -0.9664391 -0.1498168 0.2086876 -0.9299947 -0.2406779 0.2778204 -0.9468227 -0.1841213 0.2638676 -0.9420713 -0.1947439 0.2730872 -0.9607963 -0.1510075 0.2325236 -0.9466972 -0.1741715 0.2709776 -0.9625424 -0.138984 0.2327998 -0.9972133 -0.03201454 0.06738626 -0.9997766 0.008087515 -0.0195322 -0.998243 -0.01739573 0.05664306 -0.9953796 -0.04342859 0.08563649 -0.9412766 -0.1486595 0.3031483 -0.9591823 -0.1644975 0.2300218 -0.9939434 -0.05752831 0.09363234 -0.9731714 -0.1488735 0.1754254 0.9582442 -0.2067986 0.1974902 0.0893296 -0.6458164 0.758249 0.896016 -0.2651516 0.3561602 -0.6154319 -0.4688758 0.6335607 0.9818987 -0.1366046 0.1312026 0.9543563 -0.1542119 0.2557788 0.08487397 -0.8292076 0.5524592 -0.496033 -0.691846 0.5246908 0.8934839 -0.3741059 0.2484579 -0.8556395 -0.4180841 0.3051016 0.4148424 -0.7709667 0.4832351 -0.6068481 -0.6644992 0.4360919 -0.9988757 -0.002044737 0.04736495 -0.9986495 -0.008575856 0.05124175 -0.9999999 0 -4.88311e-4 0.9554218 -0.2645065 0.1311698 0.9708217 -0.2185493 0.09869968 -0.9428833 -0.2529411 0.2167761 0.9951403 -0.08856678 0.04303205 0.9937136 -0.1061772 0.03549408 0.9881023 -0.131749 0.07934844 0.9957679 -0.08899283 0.02295011 0.9925441 -0.121039 0.01434397 0.9783461 -0.1970303 0.06338787 0.9897279 -0.1401427 0.02826046 0.99605 -0.0883221 0.00915569 0.9961532 -0.08756011 0.003479182 0.9937998 -0.1111817 7.32463e-4 0.9931059 -0.08917534 0.07608288 0.9428269 -0.2577034 0.2113448 -0.5540214 -0.6040124 0.572913 0.9834818 -0.08716285 0.1586388 0.9473434 -0.1495435 0.2831562 0.9606982 -0.08478361 0.2643309 0.6800564 -0.2187302 0.6997718 0.8644927 -0.07486408 0.497039 -0.9243224 -0.002044737 0.3816069 -0.003296017 -0.08414113 0.9964485 -0.5881048 -0.1174378 0.8002132 -0.9629694 -0.04028517 0.2665844 -0.9824616 -0.003112912 0.1864394 -0.9784817 -0.03387647 0.2035337 -0.8293232 -0.1738667 0.5310305 0.2618271 -0.445219 0.8562866 0.9710372 -0.2217848 0.08887261 0.874146 -0.43425 0.2174759 0.9546303 -0.2783626 0.1058089 0.9529323 -0.2828827 0.1090757 0.9753279 -0.20991 0.06836265 0.9894165 -0.1431022 0.02401822 0.992141 -0.1243037 0.01431334 -0.9831383 -0.04852515 0.1763081 0.5843895 -0.6537606 0.4807143 0.7146425 -0.6074888 0.3467615 0.9857196 -0.1646782 0.0351879 0.9934054 -0.1144781 0.006378531 -0.9971696 -0.01016271 0.0744962 -0.9643168 -0.1881511 0.186259 -0.4923661 -0.7440884 0.4515619 -0.4733577 -0.7454087 0.4693596 0.9829023 -0.1778661 0.04760998 -0.997733 -5.18826e-4 0.06729477 0.8182231 -0.4705165 0.3303412 -0.995182 -0.0537433 0.08200353 -0.9998905 -0.01028484 0.01065105 -0.9998381 -0.01110893 0.01416087 -0.9993713 -0.02380472 0.0262767 -0.9870549 -0.1092285 0.1174382 -0.9769663 -0.162787 0.1379753 -0.9493675 -0.2481533 0.192669 -0.844076 -0.4391136 0.307758 -0.9973621 -0.01971524 0.06985807 0.2169929 -0.8571985 0.4670385 -0.9867839 -0.1062075 0.1223828 -0.9742069 -0.1651095 0.1538173 -0.9945421 -0.05645948 0.08774113 -0.9998583 0.008819937 -0.01434385 -0.9984725 -0.00463891 0.05505698 -0.9999445 0.002929747 -0.01013219 -0.9999088 0.003082334 -0.01315343 -0.9976394 -0.02301138 0.06470048 -0.9998434 -0.008484363 0.01553428 -0.9993478 0.01529002 -0.03271645 -0.9986729 -0.00576806 0.0511803 -0.9999615 9.46095e-4 -0.008728444 -0.998896 -1.66449e-4 0.04697775 -0.9988998 -1.72248e-4 0.04689675 -0.9989013 -6.9246e-4 0.04686063 -0.9988957 -1.74303e-4 0.04698371 -0.1211608 -0.06125181 0.9907414 0.007385671 0.003143489 0.9999678 -0.01303148 -0.007416069 0.9998876 -0.04034596 -0.02328592 0.9989144 -0.04815822 -0.02462846 0.9985361 0.02221769 0.009674429 0.9997064 0.02414059 0.01049852 0.9996535 -0.2247129 -0.1097775 0.9682217 -0.1967851 -0.09619522 0.9757162 -0.2173243 -0.1061138 0.9703144 -0.2650588 -0.1295232 0.9554934 -0.3088521 -0.1506722 0.9390997 -0.3712662 -0.1804906 0.9108154 -0.3513041 -0.1709979 0.9205136 -0.4217089 -0.2053 0.8831838 -0.3886013 -0.1890056 0.9018126 -0.4948453 -0.2406778 0.8349865 -0.4584355 -0.2227934 0.8603488 -0.5378059 -0.2612121 0.8015816 -0.4961826 -0.2409192 0.8341228 -0.5772736 -0.2801676 0.7669819 -0.6160661 -0.2992129 0.7286524 -0.6140441 -0.2978053 0.7309322 -0.6428543 -0.3118136 0.6996504 -0.6651427 -0.3228356 0.6733219 -0.7086951 -0.3428874 0.616587 -0.686619 -0.333055 0.6462422 -0.7342612 -0.3558537 0.578125 -0.7118211 -0.3450153 0.6117804 -0.7562657 -0.3669323 0.5416852 -0.7979187 -0.3868586 0.4622405 -0.7778555 -0.3771929 0.5026594 -0.7794989 -0.3773738 0.4999707 -0.7998302 -0.387494 0.4583886 -0.8196187 -0.3972355 0.4128307 -0.8459574 -0.410359 0.3405315 -0.837451 -0.4057853 0.3660796 -0.8531799 -0.4130849 0.3185042 -0.8661226 -0.419511 0.2717391 -0.8772408 -0.4249173 0.2233693 -0.8870604 -0.4296746 0.1688302 -0.892127 -0.4318112 0.1328485 -0.8961957 -0.4338301 0.09286981 -0.8857941 -0.4287666 0.1775617 -0.8964946 -0.4341933 0.08816927 -0.8990836 -0.4350759 0.04855537 -0.9000118 -0.4353872 0.02041733 0.03982788 -0.7038702 0.7092112 0.04446625 -0.6533213 0.7557738 0.03329676 -0.8075163 0.5889049 0.02426266 -0.8999171 0.4353857 0.02429288 -0.8982573 0.438798 0.03784358 -0.7692322 0.6378477 0.02945101 -0.8671426 0.4971886 0.01641941 -0.9558072 0.2935358 0.003326475 -0.998143 0.06082361 0.003418087 -0.9980064 0.06302201 0.007171869 -0.9913985 0.1306809 0.02142447 -0.9343771 0.3556407 0.008545339 -0.9882989 0.1522901 0.01144456 -0.9820094 0.1884852 0.003997981 -0.9971259 0.0756573 0.004059016 -0.9973725 0.07233083 0.005127131 -0.9959836 0.08938974 0.04995965 -0.519953 0.8527327 0.04593157 -0.5814242 0.812303 0.05472129 -0.3631812 0.9301102 0.05069231 -0.4294046 0.9016885 0.0446186 -0.5970414 0.8009687 0.05099678 -0.4322673 0.9003025 0.05636912 -0.2394849 0.9692624 0.05636781 -0.05880934 0.9966766 0.05755859 -0.04001021 0.9975401 0.05658197 -0.1217398 0.990948 0.05490434 -0.1555878 0.9862951 0.05362188 -0.3009479 0.9521319 0.05273699 -0.2182117 0.9744755 0.05502516 -0.08795481 0.9946036 0.05395823 -0.1391684 0.9887976 0.05285966 -0.1654459 0.9848013 0.05173075 -0.3368758 0.940127 0.05633807 -0.05649071 0.9968124 0.05761933 -0.03769063 0.997627 0.0571019 -0.1172863 0.9914552 0.03857588 -0.7150892 0.697968 0.003784298 -0.9976598 0.06827056 0.003387629 -0.998077 0.0618934 0.03177052 -0.821976 0.5686354 0.04849523 -0.4689602 0.881887 0.02874875 -0.843358 0.5365825 0.03466916 -0.7586322 0.6505962 0.04626679 -0.5083552 0.8599038 0.05072242 -0.3520357 0.9346113 0.05572718 -0.08249211 0.9950324 0.02066171 -0.9206826 0.3897649 0.01358115 -0.9668885 0.2548379 0.04034632 -0.6525608 0.7566616 0.1806148 -0.859523 0.4781198 0.3710175 -0.8119537 0.4506411 0.2671363 -0.787126 0.5559415 0.1643786 -0.7503552 0.640271 0.1191774 -0.8277413 0.5483077 0.1124947 -0.7270954 0.6772572 0.3451095 -0.6994053 0.6258848 0.2176012 -0.664462 0.7149406 0.1433784 -0.6239923 0.7681642 0.267746 -0.5732138 0.7744277 0.1549757 -0.4958429 0.8544721 0.09903657 -0.5095272 0.8547362 0.1788134 -0.4207106 0.8893977 0.1376433 -0.3228973 0.9363715 0.1055645 -0.3349134 0.9363169 0.04321491 -0.2291672 0.9724273 0.00552392 -0.2110388 0.9774621 0.1143547 -0.9150209 0.3868589 0.2793151 -0.8849148 0.3727049 0.3734903 -0.8912435 0.2572743 0.1726766 -0.9411152 0.2906632 0.2617631 -0.9503371 0.1683439 0.1089542 -0.9708522 0.2134831 0.1470409 -0.9832327 0.1078544 0.1562896 -0.9858667 0.0603367 0.07651066 -0.9918007 0.1023601 0.06000047 -0.9971495 0.04574805 0.4382483 -0.8887347 0.1344958 0.4517203 -0.8520456 0.2645132 0.4925504 -0.8595445 0.136299 0.4497888 -0.8910322 0.06125158 0.3328985 -0.9389399 0.08700895 0.4241285 -0.819874 0.3846058 0.3980636 -0.7399715 0.5422064 0.3429422 -0.6276541 0.6988856 0.2688792 -0.5096497 0.8172889 -0.1054739 -0.9943423 0.01260435 -0.1052586 -0.9943872 0.01071202 -0.09695905 -0.9952881 9.15572e-4 -0.0569787 0.01635807 0.9982415 -0.06326532 0.002716124 0.9979931 -0.04849404 0.04574739 0.9977754 -0.1047722 -0.994466 0.007751822 -0.1045283 -0.9944989 0.006775259 -0.06042802 -0.9892801 -0.1329416 -0.05218786 -0.9694438 -0.2396981 -0.04358088 -0.9529815 -0.2998782 -0.1442652 -0.08444714 0.9859291 -0.1488121 -0.186473 0.9711245 -0.135993 -0.08438527 0.9871095 -0.1005907 -0.01785361 0.9947677 -0.1030011 0.004608333 0.9946706 -0.1127676 -0.0164802 0.9934847 -0.09747892 0 0.9952377 -0.09747892 -1.52597e-4 0.9952376 -0.1239054 -0.01635795 0.9921593 -0.1123417 0.02011221 0.9934661 -0.1237233 0.02322483 0.992045 -0.1326066 0.02014279 0.9909641 -0.1341909 -0.01629698 0.9908215 -0.1017206 0.008789539 0.9947743 -0.1371223 -0.5723246 0.8084813 -0.1442628 -0.4822902 0.8640512 -0.1488123 -0.5738248 0.8053446 -0.137978 -0.1884264 0.9723465 -0.1565014 -0.4830547 0.8614903 -0.1497284 -0.3865595 0.9100292 -0.1622406 -0.3870459 0.9076748 -0.1279674 -0.6567451 0.7431758 -0.140204 -0.6586291 0.7392907 -0.1338272 -0.7363394 0.6632457 -0.1246705 -0.7359681 0.6654385 -0.1254653 -0.8670265 0.482207 -0.1123099 -0.9153258 0.3867367 -0.1159431 -0.8665983 0.48535 -0.1571446 -0.7417138 0.6520477 -0.165812 -0.743728 0.6475918 -0.1566551 -0.8103155 0.5646664 -0.1207633 -0.8064624 0.5788218 -0.1072461 -0.8660871 0.4882536 -0.1141409 -0.8052733 0.5818135 -0.1022687 -0.9152608 0.3896649 -0.0929625 -0.9150369 0.3925119 -0.1566851 -0.8676582 0.4718254 -0.1461552 -0.8675314 0.475424 -0.09845387 -0.9527383 0.2873963 -0.1100534 -0.9522095 0.2849304 -0.0962572 -0.9782591 0.1836944 -0.08401906 -0.9790526 0.1854645 -0.08783453 -0.9530263 0.2898724 -0.1087382 -0.9772708 0.1819832 -0.09525108 -0.9920949 0.0817005 -0.08224928 -0.9931868 0.08255445 -0.08621662 -0.9961457 0.01614463 -0.07281887 -0.9796065 0.187266 -0.06940019 -0.9940959 0.08340847 -0.1320879 -0.9911173 0.0154733 -0.130681 -0.9913693 0.01046788 -0.1230842 -0.992395 0.001556456 -0.1152399 -0.9933344 0.002594113 -0.1102037 -0.9939087 9.46086e-4 -0.1163706 -0.9931945 0.00476098 -0.1049856 -0.9944338 0.00891155 -0.1035812 -0.994612 0.004242122 -0.1038558 -0.9945804 0.004882991 -0.1042239 -0.9945372 0.00576812 -0.1002135 -0.9949654 0.001012861 -0.09924912 -0.9950553 0.003814876 -0.07990002 -0.9964613 -0.02609413 -0.09793639 -0.9951729 0.006286919 -0.1002135 -0.9949654 0.001050353 -0.06277781 -0.9883927 -0.1383432 -0.03473073 -0.9993787 0.00601226 -0.03491407 -0.9993852 0.003204524 -0.1002317 -0.9949639 8.1156e-4 -0.1000521 -0.9949822 5.1242e-4 -0.07083529 -0.9935863 -0.08813971 -0.05627721 -0.9983413 -0.01214659 -0.03219783 -0.9855598 -0.1662386 -0.02639907 -0.9481694 -0.3166669 -0.02511709 -0.9874405 -0.1559823 -0.03537148 -0.9441045 -0.3277433 -0.04022461 -0.984954 -0.1680706 -0.05005043 -0.9861463 -0.1581472 -0.02451545 -0.9985445 0.04804283 -0.0156818 -0.9997352 -0.01684236 -0.0110076 -0.9996623 -0.0235421 -0.06091648 -0.9410017 0.332874 -0.06222808 -0.9428215 0.3274376 -0.05307281 -0.9733788 0.2229731 -0.0879243 -0.6563043 0.7493558 -0.08933037 -0.7287432 0.6789355 -0.08343935 -0.7295606 0.6788072 -0.0795331 -0.7284024 0.6805177 -0.0743758 -0.7283156 0.6811936 -0.07544213 -0.657891 0.749325 -0.07272726 -0.3000038 0.9511616 -0.08255285 -0.2978007 0.951052 -0.08716386 -0.3985551 0.9129931 -0.08163934 -0.6569911 0.7494649 -0.08328574 -0.5775374 0.8121047 -0.0847212 -0.4914503 0.8667751 -0.09143364 -0.5757942 0.8124659 -0.07547318 -0.1953513 0.9778249 -0.06430429 -0.1966668 0.9783594 -0.07529115 -0.4940469 0.8661691 -0.06918799 -0.4010892 0.9134225 -0.06100815 -0.3034538 0.9508911 -0.07983791 -0.3983046 0.9137721 -0.06863749 -0.08856648 0.9937026 -0.05871891 -0.01696866 0.9981303 -0.06167811 -0.03701907 0.9974094 -0.02588021 -0.0197153 0.9994707 -0.03204464 -0.01904368 0.999305 -0.04559493 -0.09317368 0.9946053 -0.05813843 -0.09033578 0.994213 -0.06659221 -0.08884048 0.9938173 -0.05023413 -0.017762 0.9985796 -0.04184186 -0.01837253 0.9989554 -0.05957359 -0.017457 0.9980713 -0.03964382 0.06341791 0.9971995 -0.03112965 0.07208651 0.9969125 -0.04333722 0.06781357 0.9967564 -0.0493192 0.01791483 0.9986224 -0.04226833 -0.9934129 0.1065101 -0.03860634 -0.9942126 0.1002544 -0.03180092 -0.9992876 0.02032572 -0.1686766 -0.01614433 0.9855393 -0.1769163 -0.01556444 0.9841028 -0.1749656 9.15571e-5 0.9845746 -0.09131342 -0.6555828 0.7495819 -0.04513788 -0.8912827 0.4511958 -0.05026507 -0.8928384 0.4475637 -0.04962348 -0.9348203 0.3516372 -0.1609268 -0.08401882 0.9833837 -0.1496954 -0.01614451 0.9886003 -0.1510667 -0.08355975 0.9849857 -0.1620882 -0.1861984 0.9690499 -0.1724609 -0.1869877 0.9671054 -0.1370309 -0.01599198 0.9904378 -0.138772 -0.08255511 0.9868775 -0.2009685 -0.3900956 0.898575 -0.2056413 -0.4009976 0.8926996 -0.187569 -0.2945377 0.9370515 -0.1799094 -0.286848 0.9409309 -0.1620286 -0.2756226 0.947512 -0.194468 -0.3775218 0.9053505 -0.1697484 -0.2831581 0.9439317 -0.2228844 -0.4923721 0.8413634 0.03368955 5.45336e-5 0.9994325 0.03358399 -1.68322e-5 0.999436 0.03665125 -7.93156e-5 0.9993282 0.03532123 -2.26293e-6 0.999376 0.03363144 -1.98949e-6 0.9994344 0.0169993 -0.2850208 0.9583706 0.02923756 -0.1376426 0.9900504 0.01452696 -0.265942 0.9638796 0.03540235 -0.02777248 0.9989873 0.03799653 -0.02523946 0.9989591 0.02621567 -0.1447814 0.9891163 -0.00915569 -0.5453742 0.8381427 -0.002990841 -0.4619944 0.8868778 -0.01419144 -0.5380551 0.8427902 -0.01791501 -0.6094463 0.792625 -0.02371335 -0.6044309 0.7963047 0.02511721 -0.1185058 0.9926357 0.01880007 -0.2318574 0.9725682 -0.02322518 -0.6778043 0.7348755 -0.03427308 -0.7362155 0.675879 -0.02768081 -0.738227 0.6739842 -0.03790438 -0.7929408 0.6081186 -0.03140413 -0.7936186 0.6076047 -0.0466637 -0.8462952 0.5306665 -0.04077339 -0.8459875 0.5316415 -0.03933924 -0.889757 0.4547362 -0.04525929 -0.9332025 0.3564895 -0.04626661 -0.9685174 0.2446089 -0.02972716 -0.9995228 -0.008404791 -0.03365713 -0.9993569 -0.01237636 -0.03034871 -0.9993831 -0.01767545 -0.0327205 -0.9992734 -0.01955246 -0.03207212 -0.9992455 -0.02190542 -0.03052341 -0.999318 -0.0207867 -0.03275078 -0.9994475 -0.005673527 -0.02851909 -0.9994649 -0.01601952 0.05804783 -0.1337358 0.9893156 0.05554467 -0.1330631 0.98955 0.06332677 -0.2666439 0.9617124 0.02478176 -0.2930475 0.9557768 0.02966481 -0.2889877 0.9568732 0.02826058 -0.1490855 0.9884204 0.02426266 -0.3980607 0.9170383 0.02734512 -0.3955282 0.9180467 0.02893197 -0.02896249 0.9991617 0.03152596 -0.02740591 0.9991272 0.02652108 -0.5583165 0.829204 0.02472054 -0.4854997 0.8738873 0.0204479 -0.5624403 0.826585 0.03102582 -3.51284e-5 0.9995186 0.03044241 7.55472e-6 0.9995366 0.03043484 1.30126e-5 0.9995368 0.02464544 -0.009865939 0.9996476 0.02618527 -0.6880809 0.7251614 0.01782315 -0.745368 0.666415 0.02414071 -0.7449139 0.6667236 0.0165413 -0.6246022 0.780768 0.02230954 -0.6249117 0.7803766 0.03369277 -0.6857578 0.7270497 0.02792495 -0.7439642 0.6676359 0.03854525 -0.650265 0.758729 0.03763008 -0.621614 0.7824194 0.04028564 -0.5720871 0.819203 0.03836244 -0.6060476 0.7945029 0.04144513 -0.6005582 0.7985063 0.04577851 -0.5478772 0.8353053 0.05063098 -0.5296264 0.8467187 0.04730486 -0.5285028 0.8476126 0.04852539 -0.5440341 0.8376587 0.04599291 -0.4676506 0.8827161 0.04315447 -0.4748826 0.8789905 -0.2712557 -0.8065644 0.5252374 -0.284864 -0.8022826 0.5245905 -0.2868831 -0.8558578 0.4303552 0.05343866 -0.5074996 0.8599933 0.05868881 -0.4824512 0.8739545 0.05349999 -0.5119581 0.8573428 -0.1522008 -0.1833612 0.9711918 -0.3165761 -0.8893917 0.3297909 -0.3175848 -0.8475236 0.4252572 -0.2669529 -0.7429025 0.6138666 -0.2776336 -0.7366125 0.6167024 -0.2648155 -0.660589 0.702492 -0.2540414 -0.6698039 0.6977289 0.05038744 -0.2718358 0.9610237 0.0455349 -0.2750408 0.9603537 0.04776185 -0.3837127 0.9222165 -0.2373178 -0.5922263 0.7700315 -0.2450108 -0.5769107 0.7791942 -0.3112953 -0.9202437 0.2371642 -0.2844101 -0.8979107 0.3359573 0.06140506 -0.4141485 0.9081357 0.05948102 -0.3979644 0.9154706 0.08426338 -0.515652 0.8526446 0.05774295 -0.2678394 0.9617317 -0.2231549 -0.4782938 0.8493744 0.06262463 -0.3850866 0.9207532 -0.2206503 -0.5036808 0.8352361 0.0647006 -0.3157208 0.9466437 0.06631833 -0.3365663 0.9393216 -0.3135204 -0.7933383 0.5218423 0.05062419 -0.006870329 0.9986941 -0.378624 -0.8685523 0.3197825 -0.375783 -0.8981192 0.2284057 0.0483644 5.20533e-6 0.9988298 0.048146 1.1724e-4 0.9988404 -0.08701062 -0.01525962 0.9960905 -0.09228903 -0.07702958 0.9927483 -0.1081299 -0.07938075 0.9909626 0.04810309 1.38099e-5 0.9988424 0.04810309 2.2455e-5 0.9988424 0.04864674 -0.02594083 0.9984792 0.04614484 -0.0275892 0.9985538 0.05282771 -0.1306197 0.9900241 0.05551326 -0.2000492 0.978212 0.06006193 -0.2225161 0.9730772 0.06171 -0.2564231 0.9645928 0.06225985 -0.3000987 0.9518742 0.05118089 -0.04144519 0.9978291 0.06326699 -0.2593246 0.9637158 0.06619578 -0.3619252 0.9298539 0.04835152 1.6745e-5 0.9988304 0.06964534 -0.4041383 0.9120426 0.03232002 -0.7291085 0.6836346 0.03250306 -0.7324336 0.6800624 0.04092651 -0.5513939 0.8332406 0.03634846 -0.554566 0.8313455 0.02014237 -0.6889001 0.7245765 0.01330637 -0.6886364 0.7249848 0.01614439 -0.8902024 0.4552792 0.009643912 -0.9274982 0.3737033 0.0157783 -0.9283569 0.3713549 -0.01184123 -0.9995175 0.02871805 -0.007934927 -0.9995879 0.02758914 -0.0035097 -0.9908038 0.1352608 0.01156669 -0.7447267 0.6672693 0.01739579 -0.9234142 0.3834105 0.02240073 -0.8915442 0.4523794 0.008056938 -0.796297 0.6048524 0.01538169 -0.797224 0.6034877 0.002166807 -0.9616494 0.274273 -0.009521961 -0.9905337 0.13694 0.003387629 -0.888661 0.4585525 0.009796619 -0.8895415 0.4567495 0.01281809 -0.8446549 0.5351577 0.005493402 -0.8435759 0.5369819 0.02508687 -0.8401067 0.5418409 0.02411001 -0.8442184 0.535457 0.003082394 -0.9267151 0.3757522 -0.00350964 -0.9604257 0.2785143 -0.003021359 -0.9258225 0.3779465 0.01348954 -0.9627645 0.2700049 0.01757872 -0.9454062 0.3254202 0.006561517 -0.9913139 0.1313532 0.01342844 -0.9754252 0.2199215 0.002349913 -0.9955813 0.09387552 0.01059019 -0.9901692 0.1394733 -0.01146107 -0.9999344 8.37276e-7 0.001709043 -0.9997027 0.0243234 -0.007178604 -0.9999743 -5.13821e-5 -0.01161199 -0.9996973 -0.02169179 -0.001684725 -0.9997953 -0.02016448 -0.003495275 -0.9999423 -0.01016968 -0.01650977 -0.9997128 -0.01736956 -0.0202229 -0.9997346 -0.01104366 -0.02237725 -0.999739 -0.004627406 -0.03326058 -0.9994389 -0.003961443 -0.02562856 -0.9996213 0.01002585 -0.03200131 -0.9994315 0.01061475 -0.02355426 -0.9993668 0.02666693 -0.03112614 -0.9991232 0.02800405 -0.02447557 -0.9988509 0.04120665 -0.02519589 -0.9983767 0.05108076 -0.02739423 -0.9983258 0.05094426 -0.02131587 -0.9986587 0.04718625 -0.02825713 -0.9991323 0.03059858 -0.0290926 -0.9995008 -0.01232653 -0.02869522 -0.9995523 0.008488655 -0.02985554 -0.9970077 -0.0713042 -0.02948093 -0.9988182 -0.03864175 -0.003658175 -0.9929028 -0.1188735 -0.03014546 -0.9934318 -0.1103844 -0.003709912 -0.9866744 -0.1626648 -0.03038829 -0.9876605 -0.1536339 -0.03064495 -0.969833 -0.2418364 -0.03054785 -0.9796393 -0.198428 -0.02340817 -0.9569274 -0.2893824 -0.01974564 -0.9899691 -0.1398982 -0.1000875 -0.9949786 4.23284e-4 -0.09946084 -0.9950359 0.003357052 -0.09424287 -0.9954711 0.01248228 -0.09683781 -0.9952659 0.00827068 -0.1022072 -0.9947577 0.003296017 -0.108251 -0.9908309 0.08084487 -0.1126461 -0.9936351 5.98575e-4 -0.1145216 -0.9934195 0.00166428 -0.1178025 -0.9929894 0.009735465 -0.1170723 -0.9931006 0.006744742 -0.118413 -0.9928687 0.01379448 -0.1210401 -0.9926447 0.002411007 -0.1188707 -0.9927459 0.0180366 -0.1248034 -0.9921811 9.81495e-4 -0.125733 -0.9920632 0.001392841 -0.1290641 -0.9916177 0.006073236 -0.1282731 -0.9917286 0.004547357 -0.04754847 -0.9987316 0.01657176 -0.05966401 -0.9980835 0.01641905 -0.07287931 -0.9972081 0.01626658 -0.02990901 -0.9956968 0.08771282 -0.04605382 -0.9797965 0.1946225 -0.03863692 -0.995527 0.08621591 -0.1321474 -0.9911358 0.01367247 -0.1358387 -0.9907285 0.002227842 -0.05584931 -0.9798357 0.191841 -0.06839323 -0.9527443 0.2959739 -0.0630533 -0.9798904 0.1893126 -0.1351263 -0.9908242 0.002908766 -0.1367683 -0.9906028 7.43392e-4 -0.09952121 -0.9949074 0.01596122 -0.1054424 -0.8043835 0.5846788 -0.1171031 -0.7346033 0.6683151 -0.1387869 -0.9903166 0.003348231 -0.1404234 -0.9900342 0.01066142 -0.1425926 -0.9894943 0.02384537 -0.1258295 -0.991926 0.01580876 -0.1125544 -0.9935184 0.01590043 -0.1386805 -0.9902046 0.01620584 -0.1450889 -0.9894065 0.004913568 -0.1445671 -0.9894774 0.005920588 -0.1521058 -0.9882299 0.01629704 -0.1419758 -0.9898632 0.003723323 -0.147949 -0.9889922 0.00236535 -0.1538242 -0.9880933 0.003127396 -0.1650179 -0.9861702 0.01541221 -0.177163 -0.9841781 0.002594113 -0.1645271 -0.9863695 0.002471983 -0.1509176 -0.9885444 0.001950562 -0.1572647 -0.9875355 0.006439507 -0.1595247 -0.987088 0.01446616 -0.1597042 -0.9871266 0.008697807 -0.453572 -0.8899011 -0.048464 -0.4587923 -0.8885306 0.004791438 -0.5809852 -0.8126835 -0.04474043 -0.2839187 -0.9587255 -0.01535105 -0.2683523 -0.9631752 -0.0167548 -0.2454643 -0.9694057 -3.0519e-5 -0.1796957 -0.9837183 0.002807736 -0.1902252 -0.9817368 0.002716183 -0.1740806 -0.9847276 0.002777218 -0.1909259 -0.9814863 0.01522886 -0.1764522 -0.9843029 0.00353384 -0.1752715 -0.9845176 0.00225836 -0.1748122 -0.9846005 0.001648008 -0.1748418 -0.9845952 0.001678526 -0.1748561 -0.9845925 0.001727998 -0.2044791 -0.978753 0.01519858 -0.2033758 -0.9790973 0.002624571 -0.191325 -0.9814068 0.01535111 -0.3097381 -0.9508219 1.83114e-4 -0.346662 -0.9376263 -0.026124 -0.3701733 -0.9286837 -0.02276766 -0.3988875 -0.912436 0.09137481 -0.5020219 -0.8320641 0.2358883 -0.432853 -0.8955537 -0.1030631 -0.5063771 -0.8285393 0.2389665 -0.6172509 -0.775615 0.1319955 -0.5771827 -0.6777746 0.4555018 -0.5644202 -0.8184917 -0.1072441 -0.6037373 -0.7135771 0.3553999 -0.6963043 -0.7173629 0.02346956 -0.6945592 -0.6142017 0.3746249 -0.7205537 -0.6875016 0.09024465 -0.7147416 -0.633315 0.2967433 -0.7857528 -0.6152714 0.06351089 -0.7921826 -0.6040937 0.08670455 -0.8021039 -0.5650007 0.1933997 -0.779695 -0.528464 0.3358597 -0.2832494 -0.958977 0.01153624 -0.8121444 -0.5599039 0.1641013 -0.8480997 -0.5284105 0.03885096 -0.8634246 -0.49298 0.1070926 -0.8673338 -0.4847412 0.1129527 -0.893079 -0.4490268 0.02801644 -0.8936184 -0.4480757 0.02597141 -0.9073519 -0.411087 0.08786338 -0.9135186 -0.4066017 0.01260423 -0.9182964 -0.3957748 0.009705126 -0.5825253 -0.8127947 0.005401909 -0.3544201 -0.9350489 0.008362233 -0.1610171 -0.986947 0.003019452 -0.4630415 -0.8843934 0.05865842 -0.5847768 -0.8094281 0.05349999 -0.2311835 -0.9728022 0.01449662 -0.2474802 -0.9688016 0.01330631 -0.1603175 -0.9870532 0.004944086 -0.3695524 -0.918281 0.1420956 -0.4678649 -0.8736836 0.13334 -0.3608002 -0.9305362 0.06265628 -0.2913048 -0.9543626 0.06582969 -0.3025985 -0.9414584 0.1486288 -0.2562413 -0.964201 0.06824147 -0.2684185 -0.9510164 0.1533602 -0.2780305 -0.9292812 0.2431775 -0.3915644 -0.221388 0.8931208 -0.2816872 -0.2394798 0.9291403 -0.2444307 -0.1503086 0.9579463 -0.4383834 -0.6765583 0.5916833 -0.3367802 -0.6289412 0.7007225 -0.4154278 -0.6004049 0.6833257 -0.6918643 -0.3848743 0.6108976 -0.5991923 -0.4327991 0.6735382 -0.5719695 -0.3559206 0.7390342 -0.3185603 -0.3314089 0.8880808 -0.4249472 -0.3069911 0.8515729 -0.489229 -0.4787303 0.7290214 -0.4578747 -0.3936325 0.7971225 -0.3584198 -0.1386191 0.9232118 -0.5162926 -0.1996868 0.8328068 -0.326275 -0.06057953 0.9433317 -0.4891584 -0.1249448 0.8631992 -0.4401833 -0.01614481 0.8977628 -0.487796 -0.04678666 0.871703 -0.5232449 -0.1432247 0.8400605 -0.5381186 -0.2543489 0.8035765 -0.1771925 -0.002868771 0.9841721 -0.1920579 0.003235042 0.9813783 -0.2419236 -0.06018334 0.9684271 -0.3183167 0.01660251 0.9478391 -0.3729134 -0.1565327 0.9145672 -0.3019266 -0.002258419 0.9533286 -0.09525114 0.007874011 0.9954223 -0.06061005 0.005951106 0.9981439 -0.07275754 -0.02758926 0.9969681 -0.2079289 -0.06592196 0.9759201 -0.1845778 -0.01266527 0.9827364 -0.3061999 -0.01162779 0.9518963 -0.4633176 -0.05444687 0.8845183 -0.1299806 -0.0701633 0.989031 -0.1052281 -0.01342815 0.9943575 -0.08175981 0 0.9966521 -0.06613528 0.01977646 0.9976148 -0.06247287 0.003387629 0.9980409 -0.3539953 -0.4241291 0.8335478 -0.3867992 -0.5150406 0.7649311 -0.2790681 -0.4468631 0.8499615 -0.2440342 -0.3503643 0.9042634 -0.3104706 -0.5408592 0.7817157 -0.4548255 -0.7403923 0.4949275 -0.3568363 -0.7077212 0.609753 -0.2367386 -0.4642603 0.8534736 -0.5440632 -0.2772656 0.7919085 -0.2041738 -0.3655291 0.9081309 -0.1684945 -0.2658802 0.9491667 -0.2872223 -0.6475701 0.7058019 -0.3701758 -0.7743814 0.5131311 -0.3036063 -0.7264211 0.6165515 -0.1274467 -0.1744152 0.9763897 -0.3771238 -0.8278291 0.4153031 -0.2645077 -0.5595343 0.7854661 -0.1396846 -0.179481 0.9737941 -0.1713958 -0.9851598 0.00915575 -0.1713936 -0.9851474 0.01043742 -0.1728301 -0.9849455 0.003479182 -0.1767809 -0.9842425 0.003920793 -0.175418 -0.9844909 0.0024935 -0.175341 -0.9845048 0.002448081 -0.1001018 -0.9949759 0.001617491 -0.1000716 -0.9949784 0.001922667 -0.1079756 -0.9941512 0.002166807 -0.03073227 -0.9593203 -0.2806423 -0.005365073 -0.978239 -0.2074117 -0.02136343 -0.9672452 -0.2529432 -0.01529008 -0.992667 -0.1199098 -0.005156993 -0.9968795 -0.07877093 -0.008212149 -0.998966 -0.04471665 -0.01139652 -0.9997888 -0.01710444 -0.01424562 -0.9998869 0.004815697 -0.01684421 -0.9996207 0.0217874 -0.02822703 -0.9991326 0.03061467 -0.02646446 -0.9982298 0.05326336 -0.02958434 -0.9986883 0.04179066 -0.02893704 -0.9995812 2.71118e-4 -0.03336656 -0.9994432 1.20837e-4 -0.0339322 -0.9994242 9.09853e-5 -0.03364551 -0.9994339 1.34674e-4 -0.03330278 -0.9993211 -0.01576626 -0.034114 -0.9994068 -0.004731297 -0.02536088 -0.9996783 -4.69706e-4 -0.02536332 -0.9996784 -1.64481e-4 -0.01934057 -0.9997491 -0.01129806 -0.006959199 -0.9998261 -0.01730012 0.003258705 -0.9999948 -4.1269e-5 -0.006169974 -0.9999336 -0.009745717 -0.9073391 -0.4199762 0.01886093 -0.908582 -0.4176834 0.00439471 -0.8887175 -0.4567801 0.03915601 -0.8918598 -0.4519879 0.01712119 -0.1718205 -0.9849925 0.01635801 -0.1675497 -0.9858579 0.00338757 -0.171455 -0.9851191 0.01199388 -0.1714868 -0.9851565 0.007690787 -0.1716417 -0.9851395 0.006286978 -0.1720037 -0.9850847 0.004791438 -0.1718202 -0.9851127 0.005554378 -0.1723996 -0.985019 0.003997921 -0.2161639 -0.9763544 0.00225836 -0.1778219 -0.9840502 0.004965066 -0.1852328 -0.9826365 0.01070058 -0.113447 -0.9935438 8.89353e-4 -0.006854951 -0.9999765 -6.38961e-5 -0.007244646 -0.9999738 3.40574e-5 -0.007073044 -0.9999751 4.95105e-5 -0.009632289 -0.9999536 -1.8136e-5 -0.01396387 -0.9999026 -1.0086e-4 -0.01813721 -0.9998356 -1.19024e-4 -0.02179843 -0.9997625 -7.49387e-5 -0.02345257 -0.9997249 3.1078e-4 -0.09375476 -0.5186421 0.8498356 -0.09473079 -0.5532476 0.827613 -0.0919227 -0.5757073 0.8124724 -0.03086555 -0.9995235 1.74144e-4 -0.02646297 -0.9996498 2.77676e-4 -0.03223556 -0.9994803 1.75146e-4 -0.03140789 -0.9995067 -6.92145e-5 -0.03038305 -0.9995383 -8.0937e-6 -0.03301835 -0.9994548 -1.60524e-4 -0.03206455 -0.9994859 1.50263e-4 -0.03025496 -0.9995422 -6.47626e-5 -0.02792721 -0.99961 3.54675e-5 -0.02106189 -0.9997782 1.28938e-4 -0.0225085 -0.9997467 -1.30064e-4 -0.01928675 -0.999814 -1.80815e-4 0.002288877 -0.9998242 0.01861637 -0.002929806 -0.9982757 0.05862694 -0.006643414 -0.999978 -1.86667e-4 0.003882169 -0.9999925 -1.97926e-4 -0.9053964 -0.422331 0.04352098 -0.8846984 -0.4585856 0.0837149 -0.9036667 -0.4234507 0.06384569 -0.8794729 -0.4567204 0.1339184 -0.8994262 -0.4236651 0.107427 -0.6975017 -0.7080917 0.1099889 -0.7867766 -0.6153826 0.04782307 -0.6992854 -0.7132021 0.04840332 -0.2178142 -0.9758762 0.01492375 -0.2299913 -0.9731907 0.002014219 -0.16283 -0.9866524 0.001865565 -0.1721869 -0.9850543 0.004455685 -0.01101768 -0.9999393 -1.65437e-5 -0.008109092 -0.9999672 -2.04669e-4 -0.009371459 -0.9999562 -1.20858e-4 -0.01184248 -0.9999299 1.93844e-4 -0.01412731 -0.9999002 -4.02556e-5 -0.01653742 -0.9998633 2.46106e-4 -0.01994848 -0.999801 3.34017e-4 -0.02496367 -0.9996884 -3.11644e-5 -0.02794587 -0.9996094 -7.05917e-5 -0.02465945 -0.9994118 0.02383548 -0.02111899 -0.9974476 0.06820958 -0.02353012 -0.9904932 0.1355347 -0.02786284 -0.9996117 1.01058e-5 -0.02445173 -0.999701 7.31747e-5 -0.01771605 -0.9998431 4.65753e-5 -0.01558774 -0.9998786 -1.05238e-4 -0.0112887 -0.9999364 -5.59598e-5 -0.003894627 -0.9999924 9.60283e-5 -0.9016212 -0.4238776 0.08606338 -0.4704542 -0.8556376 0.215771 -0.5838391 -0.7871909 0.1986517 -0.5851725 -0.8016442 0.1222288 -0.1617389 -0.986831 0.002279162 -0.1717291 -0.9850237 0.01541197 -0.1271016 -0.991886 0.0026955 -0.03714191 -0.9991701 0.01672452 -0.02798587 -0.9994654 0.01690745 -0.01907408 -0.9996673 0.01736503 -0.01169151 -0.9999317 2.32048e-4 -0.0608865 -0.9451909 0.3207911 -0.0699203 -0.901212 0.4277011 -0.03359162 -0.9994357 -9.97755e-6 -0.01522344 -0.9998842 -1.6505e-5 3.9851e-4 -1 1.27915e-4 -0.8969305 -0.4225696 0.1301952 -0.8851649 -0.409317 0.2212302 -0.8645033 -0.4368752 0.2485443 -0.8814582 -0.4035871 0.245253 -0.8728373 -0.4499385 0.1889723 -0.8881365 -0.4143274 0.1988624 -0.6870171 -0.6806386 0.2544384 -0.7782037 -0.6070837 0.160774 -0.6934326 -0.6979494 0.1789355 -0.1600403 -0.9867016 0.02841293 -0.1782604 -0.9838656 0.01522886 -0.150473 -0.9886124 0.001891851 -0.0576505 -0.9947693 0.08432418 -0.04754847 -0.9952228 0.08526992 -0.03567665 -0.9990696 0.02423202 -0.03448617 -0.9990629 0.02615457 -0.04141426 -0.99202 0.1190851 -2.74672e-4 -0.9995928 0.02853536 0.002075254 -0.9910647 0.1333668 -0.004699826 -0.9996066 0.02764981 -0.001705348 -0.9999986 -2.07743e-4 -0.8915184 -0.4176513 0.1753922 -0.8942412 -0.4207368 0.1526872 -0.846692 -0.5301782 0.04498517 -0.8778862 -0.397086 0.2676538 -0.8541085 -0.4160063 0.3121497 -0.2399103 -0.9682783 0.06985813 -0.2264541 -0.9714026 0.0713849 -0.1466186 -0.9891882 0.00314188 -0.2130845 -0.9743233 0.07272708 -0.1603484 -0.9840645 0.07684761 -0.1473777 -0.9859874 0.07815992 -0.1998671 -0.9770264 0.07397735 -0.1342839 -0.9877805 0.07910543 -0.1866552 -0.9795433 0.07519918 -0.1212517 -0.9893936 0.07999014 -0.1734989 -0.9818789 0.07623577 -0.07809823 -0.9531102 0.2923726 -0.1219561 -0.9514775 0.2825195 -0.1213144 -0.9761003 0.1803083 -0.01214647 -0.9997685 0.01776194 -0.02325528 -0.995706 0.08960312 -0.02737516 -0.9951817 0.09414994 -0.02334707 -0.9954726 0.09213721 -0.01443541 -0.999736 0.01788401 -0.01092582 -0.9997749 0.01818937 -0.01886087 -0.9996594 0.0180369 -0.0230115 -0.9995372 0.01989853 -0.03296065 -0.9948637 0.09570807 -0.05038714 -0.9753319 0.214916 -0.02581906 -0.9994973 0.01840293 -0.02935951 -0.9993547 0.02069205 -0.03470003 -0.9991596 0.02182102 -0.04312312 -0.9926263 0.113286 -0.03747695 -0.9912779 0.1263474 -0.0320757 -0.9991089 0.02743679 -0.02939021 -0.9992064 0.02688759 -0.03225827 -0.9909438 0.1303455 -0.02771115 -0.990675 0.1333982 -0.02606344 -0.9992626 0.02819979 -0.01821988 -0.9995939 0.02191275 -0.01351982 -0.9966226 0.08099693 -0.01083415 -0.9779745 0.2084433 -0.0160833 -0.9994242 0.02987772 -0.8426659 -0.5306375 0.09131348 -0.865305 -0.3705311 0.3375706 -0.8414832 -0.3864377 0.3775871 -0.8606668 -0.3583543 0.3617113 -0.7834286 -0.6134365 0.09967577 -0.6640778 -0.6164976 0.4230028 -0.7613968 -0.5737333 0.3018364 -0.6774587 -0.6542338 0.3361963 -0.4698452 -0.8286611 0.3042473 -0.2520563 -0.9549087 0.1568981 -0.2384446 -0.9578682 0.1601024 -0.2249547 -0.9606124 0.1631539 -0.1466744 -0.9732517 0.1768272 -0.1594614 -0.9715703 0.1749956 -0.2116811 -0.9631551 0.1659023 -0.1356872 -0.867318 0.4789034 -0.1344653 -0.9147977 0.3808732 -0.1984976 -0.965509 0.1684971 -0.1339499 -0.9747613 0.1785999 -0.1853745 -0.9677076 0.1708168 -0.1723727 -0.9697186 0.1730136 -0.1458185 -0.914311 0.3778526 -0.1339483 -0.9505785 0.2801043 -0.03943043 -0.979475 0.1976712 -0.03930884 -0.9786326 0.2018243 -0.04513812 -0.9771994 0.2074706 -0.0529198 -0.971601 0.2306316 -0.05032634 -0.9698431 0.238478 -0.04413002 -0.9674735 0.2490937 -0.03833222 -0.9664251 0.2540734 -0.03390699 -0.9641373 0.2632295 -0.02713149 -0.9628188 0.2687823 -0.02221798 -0.9625172 0.2703093 -0.02041739 -0.9601693 0.2786722 -0.02169913 -0.9827495 0.1836646 -0.007934927 -0.9526491 0.3039687 0.008270621 -0.9622315 0.2721068 0.01632761 -0.9652838 0.2606928 0.01190239 -0.983505 0.1804893 -0.8742893 -0.3886646 0.2907888 -0.8372954 -0.5268537 0.1461566 -0.843977 -0.31685 0.4327923 -0.8268018 -0.3483488 0.4416466 -0.8382354 -0.3009175 0.4547639 -0.771034 -0.5944811 0.2282521 -0.5797132 -0.7645683 0.2817232 -0.4649891 -0.7908721 0.3978776 -0.2618243 -0.9327893 0.2476939 -0.2482123 -0.9354122 0.251783 -0.2348142 -0.9377921 0.2557504 -0.2217187 -0.939947 0.2595009 -0.1583343 -0.9482966 0.2750707 -0.1706916 -0.9469373 0.2723497 -0.208719 -0.9419367 0.2630428 -0.1460668 -0.9495258 0.2776063 -0.1959334 -0.9437458 0.2663717 -0.1832381 -0.9454281 0.2694247 -0.08304172 -0.9141916 0.3966838 -0.0971114 -0.8648166 0.492607 -0.07397741 -0.912663 0.4019623 -0.0875585 -0.8627065 0.4980674 -0.05896311 -0.9518637 0.3007974 -0.05459851 -0.9506368 0.3054648 -0.05676603 -0.9479623 0.3132814 -0.08194363 -0.7967306 0.5987535 -0.07736575 -0.8564862 0.5103393 -0.08325546 -0.7940399 0.6021372 -0.05737704 -0.9385114 0.3404473 -0.05252355 -0.937001 0.3453555 -0.0400713 -0.9315593 0.3613744 -0.0330528 -0.9295375 0.3672431 -0.02554458 -0.9278451 0.3720902 -0.01931864 -0.9272346 0.3739824 -0.01489323 -0.9178599 0.3966253 -0.004730463 -0.9131963 0.4074927 0.01782327 -0.9539436 0.299456 -0.8692134 -0.3805117 0.3157197 -0.8302577 -0.5176445 0.2066793 -0.8105573 -0.3027496 0.5013376 -0.5718407 -0.7317621 0.3708404 -0.2685406 -0.9011475 0.3403223 -0.2552621 -0.9034279 0.3444697 -0.2422301 -0.9054102 0.3486502 -0.2295647 -0.9070889 0.3528314 -0.168893 -0.9129503 0.3714793 -0.1806757 -0.9120768 0.3680658 -0.2170534 -0.9085907 0.3568624 -0.1572982 -0.913697 0.3747202 -0.2047505 -0.9099175 0.360732 -0.1926032 -0.9110736 0.3644844 -0.1232655 -0.9151374 0.3838352 -0.10468 -0.7590371 0.6425767 -0.1059016 -0.7299584 0.6752375 -0.08911544 -0.8017339 0.5910003 -0.06927883 -0.9108492 0.4068837 -0.07068312 -0.9043233 0.4209554 -0.06924784 -0.9078516 0.4135338 -0.08765035 -0.7564421 0.648161 -0.08649241 -0.7925931 0.6035854 -0.08716267 -0.7302317 0.6776167 -0.0777015 -0.8534348 0.5153753 -0.06631797 -0.898787 0.4333405 -0.06280875 -0.8976043 0.4363045 -0.05801665 -0.8966189 0.4389859 -0.05496472 -0.894329 0.4440211 -0.01687717 -0.6812843 0.7318244 -0.032045 -0.8876175 0.4594651 -0.02618563 -0.8453882 0.5335102 -0.03424203 -0.8465291 0.5312399 -0.01751804 -0.8875001 0.4604746 -0.02334737 -0.8879335 0.459379 -0.01413017 -0.8438462 0.5363993 -0.01022374 -0.8579137 0.5136923 -2.13634e-4 -0.8548426 0.5188874 0.02395731 -0.8882529 0.4587298 0.01513719 -0.9087218 0.4171282 -0.8503028 -0.3322044 0.4081978 -0.8552001 -0.3463588 0.3855755 -0.8211923 -0.5013464 0.272571 -0.646336 -0.5662841 0.5114411 -0.7486619 -0.5429638 0.380389 -0.5591785 -0.6868416 0.4642933 -0.2718069 -0.8592468 0.4333773 -0.2591981 -0.8615522 0.4365137 -0.2468436 -0.8634035 0.4400032 -0.234876 -0.8648234 0.4437496 -0.1890676 -0.8675138 0.4600799 -0.1781438 -0.8676768 0.464114 -0.2230966 -0.8658958 0.4477193 -0.1673362 -0.867719 0.4680409 -0.2115617 -0.8666647 0.451812 -0.2002357 -0.8671694 0.4559857 -0.1286994 -0.8074155 0.5757749 -0.1400505 -0.7383705 0.6596931 -0.1376111 -0.8083319 0.5724183 -0.1083728 -0.7329734 0.6715694 -0.0973556 -0.8021006 0.5892 -0.1020576 -0.7317081 0.6739344 -0.1059326 -0.7157395 0.6902864 -0.110663 -0.6854026 0.7197062 -0.08191329 -0.8607611 0.5023751 -0.07950228 -0.85774 0.5078993 -0.08212697 -0.8581063 0.5068617 -0.07342821 -0.8506811 0.5205286 -0.0696749 -0.8486116 0.5244082 -0.06595242 -0.8488669 0.5244761 -0.06171 -0.8478261 0.5266716 -0.05713158 -0.8472385 0.5281316 -0.05212658 -0.846722 0.5294759 -0.0441308 -0.7924018 0.6084012 -0.04999029 -0.7920322 0.6084291 -0.01049858 -0.684422 0.7290105 -6.71411e-4 -0.6251749 0.7804845 -0.00601232 -0.617774 0.7863328 -0.02456784 -0.7943502 0.6069632 -0.02063065 -0.843752 0.5363366 0.01934927 -0.845052 0.5343339 0.02621567 -0.8774773 0.4789014 0.01507633 -0.8585888 0.5124432 0.02530056 -0.8971781 0.440944 -0.8320194 -0.2822127 0.4775978 -0.8096258 -0.4760458 0.3433463 -0.7936483 -0.1720054 0.5835551 -0.7585144 -0.1445065 0.6354321 -0.785646 -0.1465514 0.6010682 -0.6244084 -0.5041596 0.5966047 -0.7326055 -0.5007231 0.4610486 -0.5410558 -0.6288004 0.5584521 -0.2598423 -0.809619 0.5263072 -0.2485746 -0.8119494 0.5281562 -0.2376244 -0.8135262 0.5307636 -0.1759756 -0.8123995 0.5559134 -0.1857712 -0.8133403 0.5513318 -0.2268205 -0.8144724 0.5340292 -0.1743873 -0.7459225 0.6427977 -0.1734716 -0.6682502 0.723429 -0.2162292 -0.8148041 0.5379025 -0.1662703 -0.8113611 0.5603992 -0.2058832 -0.8146519 0.5421756 -0.1957211 -0.8141365 0.5466947 -0.1470702 -0.8092986 0.5686881 -0.1090454 -0.5732132 0.8121182 -0.1156366 -0.5737883 0.8107991 -0.112218 -0.6134608 0.7817116 -0.1104474 -0.6548107 0.7476794 -0.0924139 -0.8001986 0.5925724 -0.09003275 -0.8311093 0.5487726 -0.08969658 -0.8078492 0.5825242 -0.08197432 -0.8300895 0.551572 -0.09167987 -0.4882473 0.8678765 -0.07370293 -0.7937333 0.6037842 -0.07898312 -0.794104 0.6026279 -0.07031601 -0.7923371 0.6060179 -0.0656476 -0.7919829 0.6070038 -0.06076353 -0.7918181 0.6077269 -0.05554479 -0.7918494 0.6081853 -0.01211601 -0.6143794 0.7889178 -0.04046839 -0.7344133 0.677495 -0.02096682 -0.7402482 0.6720068 -0.01117014 -0.7962248 0.6048977 -0.01754844 -0.7951425 0.6061688 -0.005432367 -0.7833048 0.6216143 0.004028499 -0.7820788 0.6231666 0.02194309 -0.7973065 0.6031758 0.02972561 -0.7972818 0.6028749 0.02942073 -0.8198139 0.5718738 -0.7932996 -0.2518489 0.5542995 -0.8181331 -0.242568 0.5213626 -0.8247579 -0.2630472 0.5005802 -0.7953933 -0.4406067 0.4161913 -0.7414884 -0.09079384 0.6647943 -0.7763469 -0.1182618 0.6191121 -0.5174192 -0.5584673 0.6483762 -0.2563303 -0.7464372 0.6141062 -0.2481533 -0.7502894 0.6127689 -0.2372899 -0.7526743 0.6141458 -0.2282267 -0.7540516 0.6158887 -0.1916937 -0.7502943 0.6327022 -0.218795 -0.7542005 0.6191207 -0.2095735 -0.7535125 0.6231356 -0.1830201 -0.7481335 0.6378087 -0.2005708 -0.7521099 0.6277755 -0.1485067 -0.7399697 0.6560418 -0.1181079 -0.5239171 0.8435411 -0.1200922 -0.4843059 0.8666174 -0.1034916 -0.64741 0.7550828 -0.09067261 -0.7115862 0.6967235 -0.09277856 -0.629582 0.7713745 -0.09332817 -0.67225 0.734418 -0.06915634 -0.7285221 0.6815227 -0.06378537 -0.7288933 0.6816495 -0.05801683 -0.72898 0.6820721 -0.05166804 -0.7308912 0.6805354 -0.04651075 -0.7328195 0.6788316 -0.02935922 -0.6742855 0.737887 -0.008362293 -0.7439128 0.6682245 -0.01422184 -0.7421011 0.6701372 0.007934987 -0.6915044 0.7223288 0.03091585 -0.7627644 0.6459372 0.03164845 -0.7807128 0.6240881 0.03119027 -0.8019449 0.5965833 -0.7758322 -0.1984673 0.5989116 -0.8026264 -0.1976733 0.5627754 -0.8098555 -0.220287 0.5436982 -0.7787386 -0.395168 0.4872457 -0.7133933 -0.4472327 0.5394932 -0.6460341 -0.2471764 0.7221799 -0.1310176 -0.1677013 0.9770931 -0.2066431 -0.2539168 0.9448942 -0.2396692 -0.6791188 0.6937986 -0.2202867 -0.6826509 0.6967507 -0.2266935 -0.6826443 0.6946992 -0.1959926 -0.6778562 0.7085887 -0.2107073 -0.6825098 0.699845 -0.1884576 -0.6747547 0.7135754 -0.203625 -0.6805201 0.7038674 -0.1810088 -0.6714507 0.7186027 -0.1691052 -0.4856473 0.8576422 -0.1671211 -0.576989 0.7994713 -0.1576313 -0.5758351 0.802226 -0.1657778 -0.665339 0.7279024 -0.1579996 -0.6628536 0.7318888 -0.1498175 -0.6609491 0.7353238 -0.1321471 -0.4827489 0.8657314 -0.1259523 -0.5721722 0.8104043 -0.1210378 -0.4839681 0.8666746 -0.1190858 -0.4643493 0.8776095 -0.118535 -0.4188094 0.9003045 -0.1179875 -0.6559509 0.745525 -0.1101137 -0.6556167 0.747022 -0.09302246 -0.5979012 0.7961539 -0.08920776 -0.3931185 0.9151502 -0.06927752 -0.6590524 0.7488996 -0.05453699 -0.586296 0.8082591 -0.06311446 -0.6604439 0.7482182 -0.05691868 -0.6621495 0.7472072 -0.0500819 -0.6647681 0.7453692 -0.0418415 -0.6679995 0.7429846 -0.03555488 -0.6710268 0.7405802 -0.00476098 -0.6873593 0.7263021 7.32456e-4 -0.6840831 0.7294037 0.01678568 -0.5604891 0.8279917 -0.7673742 -0.0895127 0.6349209 -0.7602033 -0.3412354 0.5528557 -0.09338927 -0.07385683 0.9928866 -0.16819 -0.1597058 0.9727313 -0.1225014 -0.01590013 0.9923411 -0.1185675 3.05193e-5 0.9929461 -0.2147369 -0.5998657 0.7707459 -0.2266363 -0.599338 0.7677435 -0.1873586 -0.586583 0.7879195 -0.1878125 -0.4938853 0.8490017 -0.1914188 -0.5913779 0.7833461 -0.2042663 -0.5976307 0.7753147 -0.1998067 -0.5938658 0.7793592 -0.1788747 -0.5844176 0.7914923 -0.1727356 -0.5807703 0.7955303 -0.1170402 -0.3566141 0.9268916 -0.1141405 -0.3182507 0.9411103 -0.1189623 -0.2929195 0.9487077 -0.1198182 -0.3910115 0.9125534 -0.1164591 -0.5727736 0.8113987 -0.09421336 -0.4295299 0.8981247 -0.09638035 -0.4720747 0.8762742 -0.08484339 -0.297196 0.9510396 -0.07574868 -0.5792853 0.8115977 -0.06842428 -0.5813013 0.8108064 -0.06134366 -0.58362 0.8097067 -0.04782325 -0.5900544 0.8059459 -0.03561633 -0.5954067 0.8026347 -0.04071277 -0.592197 0.8047641 -0.02951222 -0.5996752 0.7996992 0.008606374 -0.4909023 0.8711721 0.01242136 -0.3919911 0.9198852 0.004333734 -0.4793394 0.877619 -0.004211604 -0.5521785 0.8337153 0.001983702 -0.5571617 0.8304017 0.005188226 -0.5833446 0.8122083 0.01281791 -0.5778454 0.8160457 0.01940995 -0.4839985 0.8748535 0.02780312 -0.6235413 0.7812959 0.03210604 -0.6232298 0.7813796 0.03259444 -0.6254902 0.7795509 -0.7406454 -0.28203 0.6098391 -0.7077597 0.002868711 0.7064474 -0.7112107 -0.007385551 0.7029401 -0.73866 -0.04150629 0.6727992 -0.6690705 -0.3169104 0.6722444 -0.5600905 -0.005035638 0.8284162 -0.5545291 -0.01767045 0.8319768 -0.1245189 -0.08121198 0.9888881 -0.2147349 -0.507905 0.8342191 -0.2066776 -0.5060732 0.8373616 -0.1977363 -0.500643 0.8427674 -0.1797882 -0.4880316 0.8541086 -0.116643 -0.2652392 0.9571011 -0.1182937 -0.2292322 0.966157 -0.08481311 -0.2542868 0.9634028 -0.07745659 -0.1939772 0.9779434 -0.06659162 -0.4968738 0.8652642 -0.05841326 -0.5000532 0.8640224 -0.05075395 -0.5036941 0.8623899 -0.04355072 -0.5078683 0.8603333 -0.03686761 -0.5126371 0.8578135 -0.03061074 -0.5180332 0.8548128 -0.02481251 -0.5241149 0.8512861 -0.01934915 -0.5308513 0.847244 0.00238043 -0.4681584 0.8836414 0.02203494 -0.3987354 0.9168013 0.03155684 -0.557006 0.8299087 0.03796523 -0.5555322 0.8306279 0.03927838 -0.5148616 0.8563731 0.04147541 -0.5463525 0.8365278 -0.7464271 -0.02792459 0.6648811 -0.7472056 -0.02633816 0.6640709 -0.7149403 -0.005737543 0.699162 -0.721022 -0.2207471 0.656809 -0.06897264 -0.01474058 0.9975097 -0.1012318 0.001831114 0.9948612 -0.1058412 -0.01559537 0.9942608 -0.2058499 -0.4052603 0.8907244 -0.2027406 -0.4047793 0.8916559 -0.1898918 -0.396142 0.8983389 -0.1973674 -0.4011744 0.8944861 -0.180825 -0.3914366 0.9022637 -0.1713975 -0.3893678 0.9049948 -0.1166439 -0.1901034 0.9748102 -0.123601 -0.3893586 0.9127556 -0.1366659 -0.3872302 0.9117978 -0.0900017 -0.3679726 0.9254707 -0.08847439 -0.3180989 0.9439203 -0.05929952 -0.4045373 0.912597 -0.05014359 -0.4084432 0.9114055 -0.04184162 -0.4129231 0.9098042 -0.03427249 -0.4180455 0.9077795 -0.02740573 -0.4238741 0.9053065 -0.02130252 -0.4305064 0.9023361 -0.01577854 -0.4379541 0.8988589 -0.01095622 -0.4461244 0.894904 -0.006347894 -0.454733 0.8906053 0.00714153 -0.3775559 0.9259594 0.01809781 -0.477075 0.8786762 0.0315262 -0.1417612 0.9893988 0.03009194 -0.4840958 0.8744975 0.0345171 -0.4809812 0.8760512 0.03881967 -0.4778304 0.877594 0.05179059 -0.4678248 0.8823025 0.05905413 -0.5305107 0.8456188 -0.7012174 -0.1189347 0.702957 -0.6499038 -3.05191e-4 0.7600166 -0.7017613 -0.1591582 0.6944062 -0.6305544 -0.1839384 0.7540345 -0.6601355 -0.03521943 0.7503204 -0.6233793 -0.1780168 0.7613859 -0.1942847 -0.2985685 0.9344038 -0.1969097 -0.2987523 0.9337953 -0.191109 -0.2936218 0.9366236 -0.1955955 -0.2965825 0.9347627 -0.1831435 -0.2906919 0.9391255 -0.172802 -0.2891427 0.9415605 -0.1603487 -0.2894762 0.9436588 -0.08804798 -0.04123145 0.9952626 -0.09464049 -0.01358109 0.9954189 -0.1469824 -0.2902719 0.9455889 -0.1321163 -0.2915166 0.9473983 -0.1104187 -0.1777137 0.977868 -0.1041919 -0.1122184 0.9882061 -0.1200927 -0.292129 0.948809 -0.07709062 -0.153815 0.9850878 -0.08575952 -0.2085695 0.9742403 -0.04983741 -0.3074175 0.9502688 -0.039797 -0.3119367 0.9492691 -0.03079319 -0.3171488 0.9478757 -0.02288937 -0.3230766 0.946096 -0.01602268 -0.329824 0.9439065 -0.01013237 -0.3374828 0.9412772 -0.005188167 -0.3459595 0.9382351 -7.93498e-4 -0.3550902 0.9348317 0.00225836 -0.3645181 0.9311937 0.01309281 -0.3987054 0.9169857 0.03161835 -0.3911092 0.9198011 0.03387641 -0.3872598 0.9213481 0.03897273 -0.3856382 0.9218267 0.04251295 -0.3843868 0.9221928 0.0661959 -0.5360376 0.8415949 0.06378442 -0.4737749 0.8783331 0.06119006 -0.4853702 0.8721649 -0.7576677 -0.05835253 0.6500267 -0.7260256 -0.03894269 0.6865641 -0.6831521 -0.09836483 0.7236212 -0.6016282 -0.111182 0.7910008 -0.06866747 -0.01409971 0.9975401 -0.1808853 -0.1904683 0.9648847 -0.1888225 -0.1912029 0.9632173 -0.1907469 -0.1883053 0.963409 -0.1921162 -0.1904377 0.9627175 -0.1845484 -0.1868984 0.9648891 -0.1748418 -0.1857064 0.9669249 -0.1626374 -0.1854048 0.96911 -0.1271733 -0.1891271 0.9736827 -0.1050781 -0.08228009 0.9910544 -0.1191772 -0.1894627 0.9746285 -0.07629674 -0.09772086 0.992285 -0.05090546 -0.1992881 0.9786179 -0.03848403 -0.2034071 0.9783377 -0.02743691 -0.2081119 0.9777202 -0.01779234 -0.2135083 0.9767792 -0.009521901 -0.2196148 0.9755402 -0.002563536 -0.2264811 0.9740122 0.003082394 -0.234174 0.9721899 0.00790435 -0.2417093 0.9703165 0.01184123 -0.2533967 0.9672901 0.02728378 -0.1255847 0.9917078 0.01504594 -0.3064428 0.9517702 0.02487325 -0.1977044 0.9799462 0.02322518 -0.3129453 0.9494872 0.02984768 -0.01031541 0.9995012 0.02911549 -0.07614582 0.9966716 0.0355547 -0.2825149 0.9586037 0.04117035 -0.2770227 0.959981 0.06323516 -0.5222089 0.8504701 0.1028797 -0.684664 0.7215615 -0.7531225 -0.06274747 0.6548811 -0.6637688 -0.03436493 0.747148 -0.5809356 -0.04828155 0.8125163 -0.4475568 -0.01013219 0.8941981 -0.05450278 -1.30066e-5 0.9985136 -0.1712751 -0.08337914 0.9816887 -0.1794854 -0.08508843 0.980074 -0.1873893 -0.08530175 0.978575 -0.1877231 -0.0843243 0.9785957 -0.1805226 -0.08432525 0.9799494 -0.1779265 -0.0164498 0.9839063 -0.183788 -0.01709085 0.9828173 -0.1699283 -0.08459794 0.9818185 -0.1565308 -0.08490324 0.9840171 -0.1513749 -0.01690757 0.9883319 -0.1607763 -0.01693826 0.9868455 -0.1260428 -0.08456766 0.9884137 -0.1157272 -0.08505582 0.9896327 -0.0591458 0.002471983 0.9982464 -0.03109914 -0.09564751 0.9949294 -0.01803648 -0.09854471 0.9949692 -0.006653189 -0.1018128 0.9947814 0.003082334 -0.105442 0.9944207 0.01123082 -0.109165 0.9939602 0.0178231 -0.1130732 0.9934269 0.02292001 -0.1178658 0.992765 0.02926772 -0.02520871 0.9992538 0.03183144 -0.02893209 0.9990745 0.03097677 -0.146308 0.988754 0.03527975 -0.1420041 0.9892372 0.0408042 -0.1360547 0.9898607 0.04571813 -0.1335226 0.9899907 0.06180173 -0.320362 0.9452771 0.0496546 -0.1315069 0.9900709 0.06470072 -0.4051119 0.9119749 0.0717805 -0.4158511 0.9065956 -0.568454 -0.007568776 0.8226804 -0.1603472 -0.01629716 0.9869261 -0.1807619 -0.01565605 0.9834024 -0.185679 -0.01629728 0.9824754 -0.1733811 -0.01684671 0.9847107 -0.1661128 -0.01672416 0.985965 -0.143897 -0.01644968 0.9894559 -0.01663261 -0.01965397 0.9996685 -0.0112003 -0.02035593 0.9997301 -0.003051817 -0.02035588 0.9997882 0.001617491 -0.02108871 0.9997764 0.008636832 -0.0210886 0.9997404 0.01266539 -0.02182108 0.9996817 0.01855552 -0.02188211 0.9995884 0.02206528 -0.02261465 0.9995008 0.02810823 -0.02368295 0.9993243 0.033876 -0.0243541 0.9991293 0.03817909 -0.0255748 0.9989436 0.04037708 -0.02514791 0.998868 0.04089546 -0.02710086 0.9987959 0.03027504 -0.02945101 0.9991077 0.03235012 -0.02743655 0.9991 0.03460824 -0.02932852 0.9989706 0.03695887 -0.02673494 0.9989591 0.03903377 -0.02871835 0.9988251 0.04138374 -0.02636837 0.9987953 0.04321503 -0.02789443 0.9986764 0.04837048 3.96368e-6 0.9988296 0.04836142 9.41059e-6 0.9988299 -0.09055113 0.00488311 0.9958799 -0.07028436 0.0153203 0.9974094 0.03370821 -4.05114e-5 0.9994318 -0.1738969 -0.01409971 0.9846629 -0.1415797 0.01727396 0.9897763 -0.06924915 4.81156e-4 0.9975993 -0.02346891 0.07434368 0.9969566 -0.01620572 0.07233077 0.9972491 -0.02188211 0.06076341 0.9979123 0.02998054 1.37665e-4 0.9995506 0.0292533 1.27475e-4 0.999572 0.03054791 -7.50334e-5 0.9995334 0.03032773 1.005e-4 0.9995401 -0.6407718 0.001586973 0.7677298 -0.4049609 -0.03894263 0.9135043 -0.05505293 1.55179e-4 0.9984835 -0.186208 -6.74385e-5 0.9825104 -0.1859545 1.08067e-4 0.9825583 -0.1807311 7.82133e-4 0.9835323 -0.1801164 1.75061e-4 0.9836453 -0.164652 -0.007233083 0.9863253 -0.1585761 3.05189e-5 0.9873468 -0.1510076 0.006988823 0.9885079 -0.1177724 0.04086476 0.9921994 -0.07043313 2.41641e-4 0.9975166 -0.07001459 7.01517e-5 0.997546 0.02378571 -4.59195e-6 0.9997172 0.04455739 -3.51097e-5 0.9990069 -0.6110631 -0.06619697 0.7888091 -0.02328592 0.2583431 0.9657726 0.006225824 0.1929714 0.9811847 0.01010179 0.144447 0.989461 0.01397758 0.1070906 0.9941511 0.01773124 0.07757824 0.9968287 0.02127146 0.05377388 0.9983266 0.02850848 -1.53777e-4 0.9995936 0.02378731 -4.82503e-6 0.9997171 0.02797311 -5.25256e-6 0.9996088 0.03472065 -1.73387e-4 0.9993971 0.03168225 2.22114e-4 0.9994981 0.03488856 -2.4462e-4 0.9993912 0.03981822 -1.07983e-4 0.999207 0.03770089 1.55871e-4 0.9992892 0.03998613 -1.78349e-4 0.9992003 0.04308176 -4.59198e-5 0.9990717 0.04187715 9.39943e-5 0.9991228 0.04324424 -1.14223e-4 0.9990645 0.04422479 3.775e-5 0.9990217 0.04441869 -1.10585e-4 0.999013 0.04290568 2.349e-4 0.9990792 0.04193931 -9.7138e-5 0.9991202 0.04008698 -1.45224e-4 0.9991962 0.03851288 1.15566e-4 0.9992581 0.03824597 2.33776e-4 0.9992684 0.03503578 7.64706e-5 0.9993861 -0.3888825 -0.3644667 0.8461291 -0.198302 -0.01318126 0.9800524 -0.1865543 2.41858e-4 0.9824447 -0.1917806 -0.03305405 0.9808811 -0.1868377 -0.02116119 0.9821629 -0.1811614 -0.03401541 0.982865 -0.1801913 -0.03754067 0.982915 -0.1778654 -0.03454762 0.9834483 -0.1669071 -0.02066117 0.9857561 -0.1708556 -0.02316844 0.9850237 -0.1478634 0.01831126 0.9888383 -0.1347435 0.03900384 0.9901127 -0.03344917 0.1126773 0.9930685 -0.02527004 0.1373373 0.990202 -0.01593083 0.1471008 0.9889933 -0.008819937 0.1403262 0.9900661 0.02982449 -3.44841e-5 0.9995552 0.02863025 5.6912e-5 0.9995901 0.02872693 -5.38148e-5 0.9995874 0.03243362 -2.8433e-4 0.9994739 0.03465652 8.16429e-5 0.9993993 0.03446936 1.50535e-4 0.9994058 0.03687465 2.53119e-4 0.9993199 0.03715592 5.94801e-5 0.9993095 0.03900814 -2.34723e-4 0.9992389 0.04095995 2.04256e-4 0.9991608 0.04092282 2.30084e-4 0.9991623 0.04315263 -2.96862e-4 0.9990685 0.04480153 5.5704e-4 0.9989958 0.04619771 -2.94986e-4 0.9989324 -0.1319638 -3.05189e-4 0.9912546 -0.145667 0 0.9893338 -0.1578131 6.10378e-5 0.987469 -0.1675803 1.22076e-4 0.9858585 -0.1815865 -3.05187e-5 0.983375 -0.08261424 0.2353606 0.9683906 0.02600246 0.4318484 0.9015714 0.0223093 0.3288105 0.9441324 0.02020364 0.2482123 0.9684951 0.01913547 0.1839691 0.9827457 0.01883035 0.1319044 0.9910836 0.01907444 0.08911579 0.9958387 0.03220206 0.1309399 0.9908672 0.009693026 0.06942558 0.9975401 0.0326851 0.08840531 0.9955483 0.01201808 0.03700101 0.999243 0.03335177 0.05320215 0.9980267 0.01446723 0.0101003 0.9998444 0.03407889 0.02393001 0.9991327 0.01701647 -0.01222866 0.9997805 0.03486764 -4.39918e-4 0.9993919 0.01966792 -0.03062331 0.9993375 0.03562772 -0.02067875 0.9991512 0.02235233 -0.0456165 0.998709 0.03635156 -0.03732675 0.9986417 0.03700417 -0.05086034 0.99802 0.03753709 -0.06157279 0.9973965 0.03797811 -0.0729655 0.9966111 0.03787451 -0.07957428 0.9961093 0.03738659 -0.07643878 0.9963732 0.03620254 -0.06860613 0.9969868 0.03524774 -0.05990535 0.9975816 0.02399927 -0.007117927 0.9996867 0.02856969 -0.01074892 0.9995341 0.03127855 -0.007911264 0.9994794 0.03834897 0.003253877 0.9992591 0.0409162 0.001148641 0.9991619 0.04174721 0.003800928 0.9991211 0.04486674 1.51547e-4 0.998993 -0.10181 0.01849424 0.994632 -0.1249434 -0.0389418 0.9913994 -0.1826462 2.35814e-4 0.9831787 0.02512335 -0.05759233 0.9980241 0.0284692 -0.06651937 0.997379 0.03381645 -0.07432407 0.9966607 0.03997391 -0.07699346 0.99623 0.04589247 -0.07024574 0.9964736 0.04950428 -0.06214332 0.9968388 0.05287206 -0.05132675 0.9972814 0.05328243 -0.1418879 0.9884477 0.100789 -0.05826044 0.9932006 0.05810898 -0.08241021 0.994903 0.03083419 -0.1303869 0.9909836 0.06298804 -0.01354187 0.9979224 0.03180342 -0.06974107 0.997058 0.03298032 -6.49266e-6 0.999456 0.02775007 -0.008096039 0.9995821 0.0306304 -0.007506072 0.9995027 0.0333634 -0.002781867 0.9994395 0.03559035 -0.003496706 0.9993603 -0.05731487 0.01693171 0.9982126 -0.1132242 0.003021299 0.9935649 -0.1238278 -0.002681374 0.9923001 -0.1850911 -1.81691e-4 0.9827214 -0.1863365 1.26338e-4 0.982486 -0.2853863 -0.9580631 0.02588039 -0.2218143 -0.9750006 0.01312327 -0.3345484 -0.9421495 0.02078336 -0.6628491 -0.7443357 0.08121192 -0.5460529 -0.8350411 0.06732577 -0.5420539 -0.8394038 0.03973615 -0.6118026 -0.7071469 0.3544585 -0.6016276 -0.6708149 0.4336492 -0.5244419 -0.7376796 0.4251935 -0.6247715 -0.7392209 0.2514224 -0.661346 -0.6602473 0.3559427 -0.5844106 -0.645571 0.4916325 -0.5252989 -0.7031046 0.4792757 -0.592993 -0.6363001 0.4934385 -0.5883215 -0.7949985 0.1478357 -0.6711571 -0.716265 0.1910833 -0.6554338 -0.7536146 0.04971599 -0.7359399 -0.6762443 0.03296071 -0.3912876 -0.919332 0.04150617 -0.1508243 -0.98811 0.02984744 -0.1390161 -0.987976 0.06766164 -0.04998987 -0.9984246 0.02548325 0.2691473 -0.9561612 0.1153925 0.5211168 -0.8522205 0.04645031 0.3417519 -0.9372085 0.06961387 0.1138377 -0.9904801 0.07739746 0.3681249 -0.9166194 0.1558625 0.5964246 -0.8026692 3.05186e-5 0.4217767 -0.9064231 0.02240115 0.1349242 -0.9740121 0.1819234 0.2043251 -0.9517371 0.2290151 -0.4464704 -0.887722 0.1123119 -0.2971343 -0.952136 0.07175046 -0.4658104 -0.8615189 0.2020048 -0.7834345 -0.5900022 0.1952635 -0.7100324 -0.6979162 0.09363329 -0.2921005 -0.9454582 0.1441733 -0.1171916 -0.9897809 0.08124065 -0.4821799 -0.8198798 0.3087062 -0.6892833 -0.6656002 0.2861205 0.2059739 -0.9784752 0.01269596 -0.2912465 -0.9251038 0.2436363 -0.1770081 -0.9318868 0.3166309 -0.06961512 -0.9843175 0.1620895 -0.3598202 -0.8518492 0.3806343 0.00665307 -0.9700438 0.242839 -0.3477029 -0.8292317 0.4375814 0.04577833 -0.953166 0.2989631 -0.1587318 -0.9125327 0.3769462 0.4100903 -0.9120444 9.76624e-4 0.419969 -0.9075371 -0.001617491 0.4859226 -0.8740015 9.46087e-4 0.322072 -0.9467142 -0.001342833 0.05734437 -0.998354 -9.46076e-4 0.1403872 -0.9900963 -9.76607e-4 0.1312619 -0.9913465 0.001586973 0.2334408 -0.9723702 0.001342833 -0.9797909 -0.2000233 -7.32463e-4 -0.9763296 -0.2162873 5.79859e-4 -0.9812821 -0.1925758 0 -0.926981 -0.3751078 6.10378e-4 -0.9464035 -0.3229857 8.5454e-4 -0.9338783 -0.3575899 -9.46086e-4 -0.9220737 -0.3870128 -0.001037597 -0.9166309 -0.3997347 4.57781e-4 -0.953813 -0.3003994 -0.00100708 -0.9632951 -0.2684433 9.76601e-4 -0.9717661 -0.2359449 -9.1558e-4 -0.5451982 0.8383063 0.00125128 -0.3290899 0.9442986 3.66232e-4 -0.365131 0.9309558 -8.85055e-4 -0.608317 0.7936932 -0.00125128 -0.1445995 0.9894904 -3.05191e-5 -0.1220136 0.992528 -8.85041e-4 7.32466e-4 0.9999997 6.10389e-4 -0.01413035 0.9998993 -0.001403868 0.06363219 0.9979729 0.001098632 -0.7587348 0.6513992 9.15572e-4 -0.7830584 0.6219482 -3.66229e-4 -0.8909087 0.4541828 0 -0.9013599 0.4330703 8.54543e-4 -0.9492067 0.3146525 -6.40902e-4 -0.9445421 0.3283877 0.00137335 -0.9671602 0.2541657 -0.001098692 -0.4540001 -0.8910017 0 -0.8909934 0.4540164 0 -0.8910133 0.4539775 0 -0.4539516 -0.8910263 0 -0.8910033 0.4539969 0 -0.4539641 -0.89102 0 -0.4539617 -0.8910213 0 0.7756732 -0.6311348 3.3571e-4 0.89241 -0.4512254 -3.6623e-4 0.9026212 -0.4304358 5.18818e-4 0.7714684 -0.6362677 1.83116e-4 0.6181635 -0.7860488 0.001037597 0.6488665 -0.7609022 -3.3571e-4 0.5120247 -0.8589697 -0.00137335 0.4638596 -0.8859081 0.001098632 0.4349637 -0.9004469 -0.001434385 0.4023632 -0.91548 5.18824e-4 0.9851226 -0.1718524 -5.49342e-4 0.9892618 -0.1461538 5.49336e-4 0.9920675 0.125706 -5.18816e-4 0.9909182 0.1344662 -1.52595e-4 0.9320629 0.362296 -6.40908e-4 0.9420405 0.3354991 3.96751e-4 0.9052012 0.4249807 0.001525938 0.8842881 0.4669407 -0.00100708 -0.2867317 0.9580105 9.46108e-4 -0.2785805 0.960413 0 -0.3052839 0.9522612 -7.32462e-4 -0.4804933 0.8769979 -9.76612e-4 -0.53112 0.8472955 0.001403868 -0.4602036 0.8878125 0.001281797 -0.4228669 0.9061913 -0.001068115 -0.6066052 0.795002 0.001464903 -0.5890206 0.8081179 -5.49346e-4 -0.6401719 0.7682307 -0.001281797 -0.6690046 0.7432571 0.001281738 -0.801433 0.5980839 9.76613e-4 -0.7605364 0.6492942 0.00125128 -0.7870141 0.6169338 -0.001312255 -0.7360898 0.6768828 -0.00125128 -0.8344275 0.5511171 -8.2402e-4 -0.8760248 0.4822653 -9.15578e-4 -0.9018025 0.4321474 9.46085e-4 -0.8716814 0.4900729 4.27265e-4 -0.9288545 0.3704431 0.00125128 -0.9113706 0.4115847 -0.001281797 -0.9378757 0.3469691 -0.001281738 -0.9629172 0.2697914 -0.001831114 -0.9551483 0.2961243 0.001464903 -0.9748712 0.2227588 -0.002166807 -0.9745652 0.2241014 0.001068115 -0.9809448 0.1942845 0.00100708 -0.8385099 0.5448865 9.1557e-5 -0.7176022 0.6964523 0.001098692 -0.6887459 0.7250021 -0.001068115 -0.5365259 0.8438838 -4.27267e-4 -0.397088 0.9177796 0.001312315 -0.3633044 0.9316697 -0.00125128 -0.3260619 0.9453477 0.001190185 0 -1 -3.78722e-6 0 -1 -3.76841e-6 0 -1 1.60548e-7 0 -1 -1.60537e-7 -0.2083201 -0.9780607 1.83112e-4 -0.2191854 -0.9756833 -1.22075e-4 -0.1299184 -0.9915248 -2.4415e-4 -0.3687371 -0.9295337 -9.15586e-5 -0.4949257 -0.8689354 9.15568e-5 -0.5057939 -0.8626544 -1.83115e-4 -0.3608006 -0.932643 6.10388e-5 -0.6327158 -0.7743841 1.83113e-4 -0.8274013 -0.5616111 9.15571e-5 -0.832468 -0.5540733 -9.15571e-5 -0.7465887 -0.6652859 -9.15573e-5 -0.7406067 -0.6719388 9.15573e-5 -0.8723635 -0.488858 0 -0.8681154 -0.4963625 1.83115e-4 -0.642484 -0.7662992 -9.15567e-5 -0.1169174 -0.9931417 1.83113e-4 -0.9000107 -0.4358655 0.00148344 -0.9005126 -0.4348298 -2.43574e-5 -0.9001557 -0.4355686 -6.9563e-6 -0.9002022 -0.435472 -3.82099e-4 -0.9001185 -0.4356448 -5.89578e-4 -0.9001729 -0.4355327 1.70312e-4 -0.9000993 -0.4356837 -9.30512e-4 -0.9001184 -0.4356417 0.001820981 -0.9002035 -0.435468 -0.001134693 -0.9000016 -0.435885 0.001185715 -0.9003221 -0.4352211 -0.00164479 -0.9003353 -0.4351963 -8.56412e-4 -0.9000962 -0.4356913 1.93914e-4 -0.9001659 -0.4355473 1.74578e-4 -0.9001584 -0.435563 -6.23026e-5 -0.9001996 -0.4354762 0.001106917 -0.9000675 -0.4357491 0.001201808 -0.9001267 -0.4356284 -1.22884e-4 -0.9001504 -0.4355794 -2.29973e-4 -0.9001427 -0.4355953 4.74004e-5 -0.9001842 -0.435509 -6.15467e-4 -0.900072 -0.435741 5.4754e-4 -0.9001371 -0.435607 9.18924e-5 -0.9002049 -0.4354665 -3.87099e-4 -0.9001019 -0.4356794 2.75096e-4 -0.900141 -0.4355988 4.94673e-5 -0.9001331 -0.435615 2.8038e-4 -0.9004825 -0.4348857 -0.002406001 -0.9002215 -0.4354323 -3.06196e-4 -0.8999776 -0.4359348 0.001161754 -0.9004814 -0.4348921 -0.001458585 -0.9001324 -0.4356165 8.58914e-5 -0.8997867 -0.436327 0.001723825 -0.900163 -0.4355534 5.15051e-6 -0.9004536 -0.4349504 -0.001242101 -0.9001315 -0.4356183 -2.16152e-4 -0.8994698 -0.4369831 -3.0869e-4 -0.9002862 -0.4352976 9.05895e-4 -0.9004905 -0.4348758 6.16705e-5 -0.8999536 -0.4359858 -8.94391e-5 -0.8999462 -0.4360011 -9.29116e-5 -0.9001514 -0.4355773 -2.51948e-4 -0.9009783 -0.4338641 3.4572e-5 -0.900003 -0.4358839 -1.88474e-6 -0.8992564 -0.4374222 1.38306e-4 -0.900153 -0.435574 -2.78249e-4 -0.9001448 -0.435591 -6.81199e-5 -0.8998286 -0.436244 2.55113e-5 -0.9000875 -0.4357093 -8.45315e-5 -0.9006713 -0.4344998 0.00119841 -0.9005143 -0.4348261 6.76549e-4 -0.9005569 -0.4347376 8.92896e-4 -0.8999112 -0.436073 -4.05212e-4 -0.899623 -0.4366662 -0.00102967 -0.9001489 -0.4355822 -2.86902e-4 -0.9006538 -0.4345368 8.55517e-4 -0.8997748 -0.436354 -7.64563e-4 -0.9001703 -0.4355384 0 -0.8996756 -0.4365586 -7.28591e-4 -0.9001651 -0.4355489 -4.31743e-5 -0.899985 -0.4359203 8.25607e-4 -0.9000462 -0.4357945 3.75131e-4 -0.8996484 -0.4366074 0.002615571 -0.9000819 -0.4357203 5.88596e-4 -0.9006249 -0.4345872 -0.002971053 -0.9002867 -0.4352955 -0.001341283 -0.8999655 -0.4359589 0.0014292 -0.9000545 -0.4357756 0.001341044 -0.9001059 -0.435671 5.7822e-4 -0.9001233 -0.4356353 -5.27435e-5 -0.9001511 -0.4355757 -0.001423656 -0.9001714 -0.4355353 8.18773e-4 0.1906219 -0.3939399 0.8991522 0.1806135 -0.3734348 0.909904 0.2139071 -0.4423106 0.8709794 0.2194041 -0.4533965 0.8638828 0.2456188 -0.5079318 0.8256372 0.2403403 -0.4966118 0.8340344 0.2591971 -0.5357289 0.8036239 0.2772035 -0.5732981 0.7710302 0.2772357 -0.5727829 0.7714014 0.294905 -0.6095252 0.7358738 0.3118734 -0.6450797 0.6975724 0.3119108 -0.6444835 0.6981065 0.3284125 -0.6787681 0.6568251 0.3444973 -0.7124637 0.6113241 0.344807 -0.7124118 0.6112099 0.3589349 -0.7418577 0.5664036 0.3724576 -0.7702767 0.517638 0.368952 -0.7624419 0.5315608 0.3766734 -0.7784034 0.5022006 0.3835963 -0.7929813 0.4733229 0.3958323 -0.8185213 0.416341 0.3905206 -0.8070739 0.4428606 0.3967854 -0.8198482 0.4128082 0.4082241 -0.8437933 0.348376 0.402979 -0.8329676 0.3791738 0.4141798 -0.8564985 0.3080025 0.4138327 -0.8551322 0.3122362 0.418508 -0.865002 0.276808 0.4268452 -0.8826534 0.1967895 0.4228167 -0.8738639 0.2399746 0.4266834 -0.8816578 0.2015462 0.4322679 -0.8934065 0.1223497 0.429711 -0.8881712 0.1627897 0.4336469 -0.8965922 0.08984839 0.4341608 -0.8971619 0.08127158 0.4352099 -0.899383 0.0412625 0.4351133 -0.8995252 0.03912568 0.4354459 -0.899946 0.02200424 0.1460648 -0.3020485 0.942036 0.1555874 -0.3214903 0.9340431 0.1192091 -0.2462311 0.9618521 0.110265 -0.2281598 0.9673597 0.070957 -0.147377 0.9865319 0.06961393 -0.1430733 0.9872609 0.0245068 -0.05154663 0.9983699 0.0139473 -0.02807778 0.9995085 -0.02237057 0.04556518 0.9987109 -0.02899283 0.06042724 0.9977515 -0.0621972 0.1280567 0.9898146 -0.06411975 0.1326953 0.9890807 -0.09885203 0.2040216 0.9739628 -0.09073275 0.1876304 0.9780401 -0.1229631 0.254136 0.9593201 -0.1344978 0.2777547 0.9511902 -0.1710917 0.3531399 0.9197934 -0.1554048 0.3211253 0.9341992 -0.1780466 0.3681176 0.9125728 -0.214242 0.4420344 0.8710373 -0.1978277 0.4085958 0.8910183 -0.2167513 0.4482743 0.8672191 -0.2367084 0.4890428 0.8395275 -0.2564862 0.5293004 0.8087373 -0.2564228 0.5301806 0.8081806 -0.2759585 0.5702898 0.7737032 -0.2965524 0.611813 0.7333088 -0.2951539 0.610237 0.7351838 -0.3137078 0.6483213 0.693734 -0.3375756 0.6963927 0.6333089 -0.3314663 0.6855777 0.6481615 -0.3458424 0.715093 0.6074827 -0.3554313 0.734027 0.5786822 -0.3723106 0.7683657 0.5205757 -0.3632972 0.7505213 0.5520263 -0.3709561 0.7669987 0.5235502 -0.3860703 0.7976242 0.4634064 -0.3784988 0.782359 0.4946242 -0.3928676 0.8121033 0.4314433 -0.3966644 0.8189043 0.4147931 -0.3998017 0.8264909 0.3963226 -0.4146944 0.8561846 0.3081825 -0.4058198 0.8385884 0.3634279 -0.4116778 0.8509757 0.3261315 -0.4170778 0.862142 0.2876757 -0.4218053 0.8715966 0.2497993 -0.4273903 0.8824309 0.1966044 -0.4256173 0.8798918 0.2112827 -0.4291977 0.8871449 0.1695976 -0.4320032 0.8927252 0.1281207 -0.4340674 0.8963951 0.08978599 -0.4338563 0.8968886 0.08578854 -0.4354504 0.8993448 0.03952258 -0.4351169 0.8993495 0.04294097 -0.4354531 0.8999608 0.0212416 0.201454 -0.979498 -3.96743e-4 0.3546293 -0.9350069 5.4934e-4 0.1845815 -0.9828171 6.40908e-4 0.05761992 -0.9983386 -3.66228e-4 0.9053009 -0.4247708 -3.66234e-4 0.9728167 -0.2315765 2.74669e-4 0.8493142 -0.5278877 4.27266e-4 0.7355203 -0.6775027 -3.96754e-4 0.9841379 -0.1774054 -3.05187e-5 0.9971201 0.07583993 0 0.9961379 0.08780294 1.22076e-4 0.9241837 0.3819484 -1.52596e-4 0.9141448 0.4053879 1.22077e-4 0.8445012 0.5355538 -1.22077e-4 0.832871 0.5534671 1.22077e-4 0.6412704 -0.767315 4.27269e-4 0.4870571 -0.8733701 -4.2727e-4 -0.1563188 -0.1424937 0.9773741 -0.1408749 -0.1272025 0.9818217 -0.2201962 -0.1994126 0.9548552 -0.206552 -0.1879355 0.9602169 -0.2547155 -0.2318564 0.9388092 -0.2969236 -0.2691204 0.9161935 -0.2966414 -0.2700291 0.9160177 -0.3345543 -0.3043705 0.89187 -0.3705318 -0.3360758 0.8658865 -0.379199 -0.3452314 0.8585007 -0.4269319 -0.3883863 0.8166306 -0.4427083 -0.4013551 0.8018252 -0.4693548 -0.4271162 0.7728376 -0.5184569 -0.4699012 0.7144196 -0.5038688 -0.4588227 0.7318457 -0.5287154 -0.4814105 0.6990737 -0.5495298 -0.4994172 0.6697757 -0.5830065 -0.5290183 0.6166386 -0.5683532 -0.5165016 0.6404693 -0.588135 -0.5351232 0.606416 -0.6255307 -0.5682148 0.5346432 -0.6071853 -0.5521586 0.5713554 -0.6442814 -0.5853497 0.4922065 -0.6242459 -0.567327 0.5370821 -0.6577501 -0.5972 0.4590395 -0.6418556 -0.5824952 0.4987192 -0.6618837 -0.6009355 0.4480922 -0.6712919 -0.6098269 0.4212817 -0.6768352 -0.6143308 0.4055761 -0.6851341 -0.6223554 0.3785039 -0.7000276 -0.636852 0.3230803 -0.6906396 -0.6272826 0.3599078 -0.7080715 -0.6437374 0.2902358 -0.7142217 -0.6513511 0.2561822 -0.7217184 -0.6581164 0.214489 -0.7221694 -0.6596972 0.208017 -0.7362414 -0.6709307 0.0883221 -0.7384022 -0.6723901 0.05151569 -0.7358431 -0.6726688 0.07779288 -0.7303004 -0.66624 0.1509492 -0.7306672 -0.6672782 0.1444487 -0.7386605 -0.6724029 0.04748815 -0.0928089 -0.08490443 0.9920574 -0.05960428 -0.05340886 0.9967924 -0.0240184 -0.02215677 0.9994661 0.02752828 0.02569717 0.9992907 0.05029594 0.04590111 0.997679 0.1233586 0.1117919 0.9860454 0.1265931 0.115942 0.9851557 0.1802772 0.1638579 0.9698716 0.2303314 0.2092424 0.95035 0.2220572 0.2027386 0.9537231 0.3041553 0.2772068 0.9113979 0.2776633 0.2521798 0.926989 0.321885 0.2926782 0.9004052 0.3597923 0.3269841 0.8738598 0.3793194 0.3454129 0.8583745 0.4002305 0.3640041 0.8410212 0.4463476 0.4057261 0.7975965 0.4462563 0.4062452 0.7973833 0.4861178 0.4418032 0.7539892 0.5099722 0.4643462 0.7240933 0.5152323 0.4683541 0.7177605 0.5362553 0.4880652 0.6886383 0.5791291 0.5274909 0.6215811 0.5562168 0.5057376 0.6594335 0.5760754 0.5233386 0.6278965 0.5946038 0.540524 0.5952143 0.6121286 0.557102 0.5611916 0.6448373 0.5873394 0.4890985 0.6299226 0.5727902 0.5245083 0.6461241 0.5870388 0.4877594 0.6605652 0.6005638 0.4505296 0.6752975 0.6141676 0.4083769 0.6912344 0.6294021 0.3550325 0.6884557 0.6258605 0.366507 0.7100427 0.6456765 0.2809651 0.6994402 0.6360212 0.3259761 0.7194401 0.6538534 0.2342689 0.7214497 0.6567485 0.2195265 0.7269639 0.6608291 0.186624 0.7351183 0.6678233 0.1166753 0.7384205 0.6702703 0.07397937 0.7364265 0.6699254 0.09421253 0.7392209 0.6721716 0.04168832 -1.15324e-5 0 1 1.58967e-5 0 1 1.79083e-5 0 1 -1.74837e-5 0 1 -2.40362e-5 0 1 1.44738e-5 0 1 -3.60464e-5 0 1 2.05395e-5 0 1 1.41856e-5 0 1 0 0 1 0.7033009 0.7108923 0 0 0 1 0 0 1 1.25511e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 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.21313e-7 0 1 0 0 1 1 -1.20533e-5 0 1 -8.71605e-5 0 1 -9.89231e-5 0 1 2.02406e-5 0 1 1.49348e-5 0 1 -1.17756e-4 0 1 3.96059e-5 0 1 8.08211e-5 0 1 7.96103e-5 0 1 -1.51726e-5 0 1 -3.60345e-5 0 1 -4.46808e-5 0 1 1.2899e-5 0 1 5.97803e-5 0 1 1.00146e-5 0 1 -8.02464e-5 0 1 -2.96761e-5 0 1 -1.99112e-5 0 1 -5.91847e-5 0 1 3.18443e-5 0 1 1.15433e-4 0 1 1.26743e-5 0 1 1.05759e-4 0 1 -5.50189e-5 0 1 -3.89006e-5 0 1 5.16786e-5 0 1 -9.0601e-5 0 1 1.14606e-5 0 1 1.32921e-5 0 1 -9.71164e-5 0 1 1.1573e-5 0 1 1.28683e-4 0 1 9.1567e-6 0 1 9.64525e-5 0 1 5.49383e-6 0 1 -9.20843e-5 0 1 2.77187e-5 0 1 1.18535e-5 0 1 1.28158e-4 0 1 1.39223e-5 0 1 -6.12887e-6 0 1 -2.53656e-4 0 1 1.32559e-4 0 1 2.16497e-4 0 1 -1.47904e-4 0 1 -1.4939e-4 0 1 3.31707e-4 0 1 -2.57271e-4 0 1 1.26215e-4 0 1 4.99205e-5 0 1 -1.61463e-5 0 1 -6.56113e-5 0 1 -9.24405e-6 0 1 5.29626e-6 0 1 -3.5402e-5 0 1 2.67626e-5 0 1 4.27061e-5 0 1 5.82339e-6 0 1 -9.59049e-5 0 1 -8.44095e-5 0 1 1.33815e-4 0 1 1.00995e-4 0 1 -7.5805e-5 0 1 -1.10744e-5 0 1 5.4913e-5 0 1 4.19916e-5 0 1 -2.92537e-6 0 1 7.25926e-5 0 1 2.99581e-4 0 1 -1.50972e-4 0 1 -8.89996e-5 0 1 -6.55951e-5 0 1 -7.84099e-5 0 1 -2.86314e-6 0 1 -2.30358e-5 0 1 5.70534e-6 0 1 -1.42095e-5 0 1 2.30417e-5 0 1 5.87285e-6 0 1 -2.37942e-5 0 1 4.21727e-5 0 1 -2.40618e-5 0 1 1.54953e-5 0 1 -1.82163e-5 0 1 1.24565e-5 0 1 1.9846e-5 0 1 -1.28017e-5 0 1 -6.56669e-6 0 1 4.91964e-6 0 1 4.28354e-5 0 1 -9.78389e-6 0 1 2.45935e-6 0 1 1.56878e-6 0 1 -9.47987e-6 0 1 -5.42611e-6 0 1 9.67136e-6 0 1 4.8339e-6 0 1 -8.73296e-5 0 1 -2.26034e-5 0 1 -1.11643e-5 0 1 -1.4015e-4 0 1 -9.21776e-5 0 1 2.39916e-5 0 1 9.44131e-5 0 1 1.02656e-5 0 1 6.2613e-5 0 1 5.04699e-5 0 1 -1.07135e-5 0 1 -5.34133e-6 0 1 -1.27752e-5 0 1 -3.81479e-5 0 1 8.93665e-6 0 1 -3.35971e-5 0 1 4.138e-6 0 1 -7.06493e-6 0 0.4864922 -0.2992923 0.8208225 0.4982571 -0.3066573 0.8109878 0.4923143 -0.3030002 0.8159765 0.473931 -0.2917625 0.8308213 0.4958423 -0.3052511 0.8129959 0.5036613 -0.3099548 0.806383 0.5051842 -0.310899 0.8050657 0.4837951 -0.2976262 0.8230194 0.4760627 -0.2928279 0.8292263 0.4735109 -0.2912786 0.8312306 0.4703109 -0.2893168 0.8337286 0.4688402 -0.2884396 0.8348603 0.463497 -0.2852031 0.8389458 0.4572958 -0.2814457 0.8436047 0.4344441 -0.2674723 0.860068 0.447775 -0.2754647 0.8506566 0.437651 -0.2691828 0.8579058 0.4329788 -0.2663124 0.8611661 0.4291949 -0.2640237 0.8637612 0.4238854 -0.2608315 0.8673455 0.4208959 -0.2589894 0.869351 0.3990383 -0.2456794 0.8834083 0.4097145 -0.2521156 0.8766822 0.4022479 -0.2475167 0.8814375 0.4006913 -0.2465675 0.8824121 0.3943698 -0.2427501 0.8863097 0.3881665 -0.2390524 0.8900455 0.360834 -0.2222442 0.9057628 0.3846457 -0.2368205 0.8921681 0.3710802 -0.2283124 0.9000961 0.3819211 -0.2350917 0.8937943 0.3624485 -0.2230052 0.9049308 0.3576894 -0.2201072 0.9075303 0.353523 -0.217602 0.9097642 0.3476701 -0.2140893 0.9128478 0.3525882 -0.217022 0.9102655 0.3170664 -0.1953549 0.9280654 0.3390693 -0.2088434 0.9172877 0.3320412 -0.2044058 0.9208513 0.33058 -0.2034996 0.9215773 0.3244534 -0.1996589 0.9245899 0.3181371 -0.1957532 0.927615 0.3125202 -0.1923342 0.9302359 0.3093664 -0.1904166 0.9316835 0.3049203 -0.1877326 0.9336917 0.3034794 -0.1868669 0.9343346 0.2969251 -0.1828733 0.9372261 0.2791866 -0.1719738 0.9447115 0.28886 -0.1778327 0.9407101 0.2815388 -0.1732875 0.9437729 0.271006 -0.1668762 0.9480022 0.2388154 -0.1472262 0.9598395 0.2646639 -0.1630039 0.9504646 0.2610882 -0.1607407 0.951838 0.2598383 -0.1599497 0.9523131 0.2548075 -0.1568093 0.9541929 0.2500751 -0.1538478 0.9559255 0.239485 -0.1473777 0.9596493 0.2284074 -0.1406946 0.9633458 0.2251092 -0.13874 0.9644051 0.2198618 -0.1355977 0.9660611 0.1923002 -0.1186578 0.974136 0.2127522 -0.1311428 0.9682655 0.2030101 -0.1250044 0.9711648 0.197888 -0.1218335 0.9726237 0.1920863 -0.118261 0.9742265 0.1861642 -0.1146588 0.9758055 0.1785904 -0.1100708 0.9777474 0.1754249 -0.1080994 0.9785402 0.152258 -0.09396725 0.9838637 0.1620869 -0.09988898 0.9817078 0.1565813 -0.09648853 0.9829406 0.1538167 -0.0947926 0.983542 0.1409976 -0.08688747 0.9861899 0.1102652 -0.06814897 0.9915631 0.1309593 -0.08066314 0.9881008 0.126655 -0.0779376 0.9888803 0.1259825 -0.07751828 0.9889992 0.1268671 -0.07806736 0.988843 0.1168897 -0.07187342 0.9905409 0.1070289 -0.06588977 0.9920703 0.1023522 -0.06308132 0.9927461 0.1012313 -0.06241124 0.9929034 0.09528118 -0.05887168 0.993708 0.06283813 -0.03897249 0.9972625 0.08743649 -0.05407941 0.9947012 0.08041465 -0.04963642 0.9955249 0.07437521 -0.04583978 0.9961763 0.0794419 -0.04901409 0.9956339 0.06912618 -0.0425744 0.9966992 0.06375509 -0.0392785 0.9971924 0.05523997 -0.0340901 0.997891 0.04666441 -0.02894234 0.9984914 0.0429396 -0.02673423 0.99872 0.0461449 -0.02862691 0.9985245 0.03717207 -0.02322494 0.999039 0.02578878 -0.01608365 0.9995381 0.0298478 -0.01849466 0.9993835 0.02489233 -0.01542818 0.9995711 0.02343857 -0.01452702 0.9996197 0.01626682 -0.01013243 0.9998164 0.01077312 -0.00677514 0.9999191 0.01348948 -0.008484363 0.9998731 0.004303157 -0.002685666 0.9999871 -0.00169456 0.001045048 0.999998 0.07599246 -0.4721301 0.8782474 0.2217212 -0.4105429 0.884474 0.09848421 -0.3440997 0.9337539 0.111671 -0.2234642 0.9682942 0.2016114 -0.2402185 0.9495515 0.177955 -0.2237638 0.9582597 0.04242187 -0.2469319 0.9681039 0.03100699 -0.3345463 0.9418691 0.05594086 -0.1647403 0.9847494 0.05441516 -0.163215 0.9850888 0.04120117 -0.1017517 0.9939563 0.121495 -0.1507014 0.9810852 0.0368365 -0.09747791 0.9945558 0.01116997 -0.03521901 0.9993173 0.1539717 -0.638624 0.7539578 0.2769027 -0.5771832 0.7682347 0.190532 -0.5289606 0.8269816 0.0511806 -0.5937502 0.8030201 0.3038854 -0.6072214 0.7341226 0.2789428 -0.6256986 0.7284863 0.1876295 -0.680508 0.7083107 0.1074891 -0.7309076 0.6739585 0.2043225 -0.6622553 0.7208817 -0.01443564 -0.6238779 0.7813886 0.02478152 -0.7041069 0.7096614 -0.003143489 -0.7881917 0.6154219 0.05975735 -0.7708335 0.6342278 0.1282741 -0.7589323 0.6384102 0.09085547 -0.7756134 0.6246352 -0.04773169 -0.8161086 0.575924 -0.02325528 -0.8266007 0.5623083 -0.0528289 -0.7968899 0.6018104 -0.0587185 -0.819648 0.5698503 -0.07349044 -0.8280496 0.5558175 -0.07709228 -0.8652589 0.4953624 0.00915569 -0.8204445 0.571653 0.03241139 -0.7992683 0.6000998 -0.03647041 -0.7492161 0.6613208 0.05377507 -0.7665241 0.6399604 0.1572048 -0.7244055 0.6712104 -0.02630788 -0.6937101 0.7197738 0.2104907 -0.6540564 0.7265699 -0.001678526 -0.5407692 0.8411693 0.3506734 -0.5239043 0.7762426 0.3268309 -0.468715 0.8206632 0.01522892 -0.4392583 0.8982318 0.240855 -0.2990241 0.9233491 0.2655831 -0.2309737 0.9360111 0.4073783 -0.4087517 0.8166794 0.3590834 -0.3672013 0.858034 0.3224951 -0.3166354 0.8920421 0.3022909 -0.2943559 0.9066284 0.3907105 -0.3098033 0.8668145 0.4349914 -0.3415413 0.833146 0.4596813 -0.3402289 0.8203276 0.4295663 -0.391325 0.8138412 0.4199424 -0.3662593 0.8303629 0.4881885 -0.3232005 0.810687 0.3216107 -0.5839838 0.7453385 0.3955347 -0.4353629 0.8087098 0.1733816 -0.6914511 0.7013089 0.2342951 -0.638246 0.733313 0.3668084 -0.500024 0.784492 0.4226698 -0.3763101 0.8244641 0.1824759 -0.4319115 0.8832639 0.3365701 -0.5510312 0.7636002 0.3832254 -0.4686477 0.7959321 1 3.44327e-6 0 1 -1.64587e-6 0 -0.07530575 -0.9971605 0 -0.07530558 -0.9971605 0 1 1.2874e-6 0 -0.09757095 -0.8452082 0.5254549 -0.09753996 -0.8447767 0.5261543 -0.09448778 -0.8202065 0.5642105 -0.09579819 -0.828247 0.5521138 -0.080356 -0.697843 0.711729 -0.07608294 -0.6571575 0.7499037 -0.08365213 -0.7227166 0.6860634 -0.08786481 -0.7638047 0.6394389 -0.07199412 -0.6252414 0.7771037 -0.06909525 -0.5974424 0.7989296 -0.02560573 -0.2245919 0.9741165 -0.03109896 -0.2675915 0.9630305 -0.04019355 -0.3502978 0.9357756 -0.04171985 -0.3609212 0.9316626 -0.02020376 -0.1730447 0.9847068 -0.01223826 -0.1079776 0.994078 -0.00939995 -0.08023536 0.9967316 -0.006103754 -0.05462884 0.9984881 -0.004150569 -0.03515779 0.9993732 -0.05212682 -0.4511046 0.8909475 -0.05279761 -0.45821 0.8872746 -0.0616492 -0.5332965 0.843679 -0.06293082 -0.5461129 0.8353446 -0.09009283 -0.7759215 0.624363 -0.09558755 -0.8301044 0.549354 -0.09528219 -0.8216183 0.5620185 -0.09778386 -0.8451102 0.525573 -0.09146618 -0.7942634 0.6006494 -0.09161972 -0.7928066 0.6025477 -0.09747898 -0.8441364 0.5271923 -0.1472858 -0.5722053 0.8067762 -0.1318438 -0.5343949 0.8348889 -0.1403579 -0.4793655 0.8663189 -0.152352 -0.6756351 0.7213224 -0.1377342 -0.6277542 0.7661293 -0.1567466 -0.522336 0.8382098 -0.1423401 -0.7708771 0.6208766 -0.1503708 -0.7753847 0.6133248 -0.15043 -0.8030567 0.5766028 -0.1632482 -0.6346203 0.7553855 -0.1734415 -0.5928385 0.7864227 -0.1652012 -0.5091848 0.8446534 -0.1721293 -0.6623319 0.7291694 -0.1729234 -0.5312222 0.8293976 -0.185617 -0.6977273 0.6918982 -0.1789646 -0.6250333 0.759806 -0.176918 -0.7050782 0.6867058 -0.1895265 -0.6469844 0.7385736 -0.1865645 -0.6178939 0.7638068 -0.1701454 -0.6381599 0.7508679 -0.1706303 -0.6391238 0.7499374 -0.1739276 -0.6389449 0.7493321 -0.1169186 -0.4963013 0.8602413 -0.12403 -0.4359058 0.8914049 -0.1071846 -0.3912301 0.9140299 -0.1015692 -0.4569698 0.8836642 -0.09146553 -0.3470013 0.9333939 -0.0858494 -0.4161849 0.9052183 -0.07431405 -0.2993316 0.9512508 -0.07998985 -0.5015466 0.8614248 -0.05676537 -0.4317833 0.9001894 -0.07693821 -0.551294 0.8307559 -0.0964111 -0.5298187 0.8426132 -0.06998002 -0.3740713 0.924756 -0.05700981 -0.2505625 0.9664205 -0.08884179 -0.6677936 0.7390257 -0.09256452 -0.622865 0.776834 -0.07123309 -0.5602512 0.8252542 -0.1106944 -0.8217691 0.5589653 -0.09143608 -0.7711338 0.6300731 -0.1070313 -0.8284474 0.5497448 -0.08542382 -0.6792096 0.7289562 -0.1018135 -0.7317698 0.6739044 -0.08215731 -0.4950499 0.8649716 -0.04187238 -0.2977458 0.9537265 -0.06183212 -0.422357 0.9043182 -0.06320565 -0.3679419 0.9276983 -0.05441582 -0.3308899 0.9420992 -0.04916548 -0.1836916 0.9817537 -0.04025429 -0.2012716 0.978708 -0.03186154 -0.1320546 0.9907303 -0.0272234 -0.1623333 0.9863604 -0.04492402 -0.2845901 0.9575961 -0.04351967 -0.2256248 0.9732418 -0.02688723 -0.1416693 0.9895489 -0.01895242 -0.08978748 0.9957806 -0.02212625 -0.07861697 0.9966593 -0.006714046 -0.03326529 0.9994241 -0.1739606 -0.7414383 0.6480795 -0.1781721 -0.7310609 0.6586385 -0.1639497 -0.7000216 0.695047 -0.1681308 -0.7691779 0.6165204 -0.1556454 -0.4809444 0.8628251 -0.167367 -0.7563561 0.6323873 -0.1505514 -0.4683485 0.8706228 -0.1603466 -0.7923032 0.5886805 -0.1539995 -0.7377083 0.6573209 -0.1390478 -0.4352719 0.8894966 -0.1339774 -0.4227767 0.8962756 -0.1407237 -0.7180234 0.6816446 -0.121496 -0.3889338 0.9132192 -0.1278745 -0.7479898 0.6512752 -0.1310794 -0.7744827 0.6188659 -0.1227785 -0.7659692 0.6310442 -0.1334292 -0.7816231 0.6093127 -0.1292178 -0.688694 0.7134449 -0.1238183 -0.5957443 0.7935729 -0.1166445 -0.3758747 0.9193 -0.1183834 -0.6644915 0.7378594 -0.1037662 -0.3415738 0.9341092 -0.1153923 -0.7314795 0.6720286 -0.1183841 -0.7651479 0.6328775 -0.1102966 -0.5632938 0.8188619 -0.09882175 -0.3272594 0.9397529 -0.1063906 -0.6382216 0.762466 -0.0940895 -0.6110481 0.7859819 -0.08435589 -0.2862425 0.9544367 -0.1105102 -0.7618824 0.6382185 -0.1067875 -0.7627416 0.6378257 -0.104864 -0.7190632 0.6869875 -0.0673564 -0.2357323 0.969481 -0.1059631 -0.7668897 0.6329709 -0.09824198 -0.7831285 0.6140508 -0.09894287 -0.7691116 0.6314094 -0.09543323 -0.7021836 0.7055712 -0.08951121 -0.7834446 0.6149816 -0.09384638 -0.7979538 0.5953677 -0.08194315 -0.5841922 0.8074682 -0.06818073 -0.459442 0.8855872 -0.1004393 -0.7707366 0.6291877 -0.08038753 -0.8062257 0.5861213 -0.1029409 -0.2954859 0.9497849 -0.1015679 -0.2913059 0.9512229 -0.1127704 -0.3227767 0.939733 -0.08365327 -0.2412546 0.9668498 -0.08432483 -0.2423539 0.9665164 -0.06488364 -0.1873264 0.9801526 -0.04681551 -0.1362655 0.9895656 -0.06323558 -0.1830536 0.9810672 -0.02792459 -0.08221745 0.9962232 -0.04187262 -0.1218335 0.991667 -0.01046812 -0.03146553 0.9994501 -0.02063071 -0.06030523 0.9979668 -0.008179187 -0.02469015 0.9996618 -0.002502501 -0.007232844 0.9999708 -0.118385 -0.3389796 0.9333156 -0.1221078 -0.3491715 0.929069 -0.1312331 -0.3750826 0.9176552 -0.1279652 -0.366042 0.9217582 -0.1398693 -0.3995875 0.9059616 -0.1369099 -0.3915024 0.9099349 -0.145547 -0.41601 0.8976368 -0.1483221 -0.4237252 0.8935645 -0.1565053 -0.4471755 0.8806476 -0.1539668 -0.44011 0.8846453 -0.164408 -0.4699073 0.86727 -0.1623005 -0.4640733 0.8708012 -0.1702685 -0.487092 0.8565921 -0.1719471 -0.4917309 0.8536012 -0.1794213 -0.5134522 0.8391513 -0.1781716 -0.5100688 0.8414777 -0.1862598 -0.5335093 0.8250305 -0.1855573 -0.5316765 0.8263708 -0.1869603 -0.5355805 0.8235287 -0.191813 -0.5500777 0.8127868 0.03982776 0.001770079 0.9992051 -0.1207938 0.006225824 0.9926581 -0.0397973 -0.001770079 0.9992063 -0.2769587 0.01040691 0.9608255 -0.1982514 0.002471983 0.9801481 -0.3525532 0.006744623 0.9357676 -0.4192453 0.01370316 0.9077696 -0.4918748 0.01187187 0.870585 -0.5158658 0.0142219 0.8565514 -0.602086 0.01632785 0.7982645 -0.6066921 0.01568686 0.7947822 -0.7094302 0.020204 0.7044861 -0.7180609 0.01901358 0.6957206 -0.8001317 0.02160781 0.599435 -0.795644 0.0222792 0.6053548 -0.8603009 0.02291977 0.5092711 -0.8552358 0.0237438 0.5176949 -0.913653 0.02505624 0.4057221 -0.9112083 0.02554446 0.4111531 -0.9495355 0.02569693 0.3126054 -0.9564517 0.02734547 0.290607 -0.9769757 0.02514767 0.2118632 -0.9868511 0.02920633 0.1589716 -0.9957789 0.02984768 0.08679646 -0.9950145 0.02563601 0.09637933 -0.9989099 0.0256052 0.03903347 0.1208239 -0.006225824 0.9926545 0.1982514 -0.002471983 0.9801481 0.2769869 -0.01040679 0.9608173 0.3525531 -0.00677514 0.9357674 0.4192453 -0.01370316 0.9077696 0.4918748 -0.01187187 0.870585 0.5158658 -0.0142219 0.8565514 0.5969559 -0.01641929 0.802106 0.5982896 -0.01614439 0.8011173 0.6935737 -0.02047818 0.7200946 0.6782913 -0.01815897 0.7345688 0.7687129 -0.01898282 0.6393122 0.7990176 -0.0247814 0.6007968 0.8557738 -0.02096629 0.5169251 0.8946847 -0.02707004 0.4458774 0.9139494 -0.02417093 0.4051078 0.9548822 -0.02792495 0.2956692 0.9495264 -0.02569669 0.3126329 0.9769757 -0.02514767 0.2118632 0.9868455 -0.02920705 0.1590062 0.9950175 -0.02563607 0.09634912 0.9957762 -0.02984762 0.08682674 0.9989123 -0.02560526 0.03897255 -0.1591588 -0.9818714 0.1029421 -0.09680509 -0.9942973 0.04474031 -0.1744805 -0.9814186 0.07983922 -0.08820033 -0.994558 0.05545324 -0.09476268 -0.9940167 0.0543245 -0.4153941 -0.857004 0.3049458 -0.3600954 -0.8582594 0.3656804 -0.2921562 -0.9335693 0.2075887 -0.1033988 -0.9937337 0.04245209 -0.4543998 -0.7562648 0.4707275 -0.3710538 -0.7582523 0.5360717 -0.1856144 -0.9811133 0.0544452 -0.1033664 -0.9941122 0.03250223 -0.3225567 -0.9328173 0.1606527 -0.3454789 -0.9319691 0.1099001 -0.4603561 -0.8556447 0.2365261 -0.1092293 -0.9935936 0.02899354 -0.1928812 -0.9808562 0.0267958 -0.1023011 -0.9947497 0.002746701 -0.1803044 -0.9835562 0.01037633 -0.1074894 -0.994018 0.01934927 -0.1129217 -0.9934973 0.01455771 -0.08319377 -0.9965247 0.004181027 -0.08713126 -0.9961956 0.001586973 -0.1404774 -0.9823654 0.1233869 -0.493229 -0.8548265 0.1612356 -0.07815939 -0.9948313 0.06482255 -0.08466041 -0.9942872 0.06500601 -0.2780288 -0.7608406 0.586363 -0.2952436 -0.8601863 0.4158254 -0.094397 -0.9835845 0.153788 -0.06680572 -0.9951277 0.07251274 -0.1187196 -0.9829314 0.1405408 -0.386612 -0.3327769 0.8601109 -0.3609211 -0.4923066 0.7920671 -0.4865392 -0.4891028 0.7239186 0.1984657 -0.5076547 0.8383902 0.1698993 -0.6499329 0.7407574 0.0453518 -0.6465532 0.7615197 -0.08060139 -0.6430413 0.7615782 0.0576812 -0.5037493 0.8619222 -0.06814861 -0.9842947 0.1628487 -0.04080402 -0.9850655 0.1672753 -0.04083406 -0.9958577 0.08124095 -0.05356043 -0.940039 0.3368356 0.04880023 -0.07202535 0.9962084 0.07736653 -0.1670629 0.9829062 -0.08554393 -0.1633361 0.9828549 -0.01309251 -0.9858185 0.167304 0.002197325 -0.9415711 0.3368073 0.05725282 -0.943085 0.3275864 0.01428306 -0.9865724 0.1626993 0.2210208 -0.3496901 0.9104212 0.06805807 -0.3454483 0.9359667 0.1756992 -0.8731552 0.4546755 0.2360036 -0.7750001 0.5862399 0.3290005 -0.7775461 0.5358924 0.1811922 -0.06430381 0.9813432 0.2381746 -0.1721608 0.9558419 0.3150451 -0.06140369 0.9470884 0.3916491 -0.1744766 0.9034207 0.1100224 -0.9444839 0.3095888 0.04043805 -0.9873 0.1536343 0.06485372 -0.9879441 0.1405724 0.1590337 -0.9458703 0.2829096 0.4121341 -0.7800456 0.4708229 0.2476898 -0.875185 0.4155732 0.3123311 -0.8769626 0.3652205 0.4838862 -0.7818478 0.3931518 0.5041133 -0.3574999 0.7861702 0.6268053 -0.3601887 0.6909263 0.4593148 -0.5145851 0.7240388 0.8038167 -0.5244126 0.2808384 0.7046841 -0.6647347 0.248089 0.6541436 -0.6632078 0.363664 0.2031662 -0.947041 0.2486703 0.08728414 -0.9885392 0.1231744 0.5417767 -0.7833361 0.3047341 0.3679658 -0.878424 0.3049138 0.7473531 -0.08209651 0.6593358 0.7729611 -0.1838174 0.6072416 0.66292 -0.1830271 0.7259739 0.9939404 -0.06677538 0.0873146 0.995003 -0.09045755 0.04226845 0.9805753 -0.1841821 0.06744694 0.8391761 -0.5256562 0.139532 0.7362676 -0.6654028 0.1230825 0.9283334 -0.1890054 0.320116 0.8628122 -0.1866257 0.4698147 0.9122216 -0.0748943 0.4027936 0.9174335 -0.367541 0.1524121 0.9138193 -0.3982814 0.0794121 0.8617977 -0.1062674 0.495996 0.8228091 -0.07715356 0.5630565 0.968262 -0.1913878 0.1607462 0.828099 -0.5559318 0.07205504 0.108618 -0.9903191 0.08643049 0.05002039 -0.9979057 0.04101729 0.05206608 -0.9974054 0.04971611 0.6002234 -0.0736736 0.7964321 0.6943684 -0.09268617 0.7136259 0.6106954 -0.7852059 0.1024845 0.7171137 -0.6939495 0.0646705 0.4664769 -0.8810111 0.07886004 0.5519993 -0.8320732 0.05432403 0.1304704 -0.9898968 0.05551475 0.04458862 -0.9984372 0.03369325 0.0549041 -0.9980706 0.02899324 0.04794585 -0.9983181 0.03259462 0.3533462 -0.9347898 0.03625625 0.3073279 -0.9500917 0.05362212 0.4458813 -0.8804401 0.1612924 0.1384664 -0.9900185 0.02627718 0.05313271 -0.9983524 0.02166813 0.05890166 -0.998155 0.01474064 0.05307257 -0.9983991 0.01956266 0.1393492 -0.9901548 0.01324516 0.03509676 -0.9993737 0.004547297 0.04953235 -0.9987652 0.003845393 0.03906476 -0.9992352 0.001770079 0.9447277 -0.109473 0.3090393 0.97024 -0.08160865 0.2279794 0.04501497 -0.9975935 0.05273616 0.7464394 -0.5228555 0.4116435 0.8165324 -0.3652803 0.4470404 0.8783124 -0.3681532 0.305009 0.4126179 -0.879743 0.2362177 0.2475719 -0.9438068 0.2189449 0.668279 -0.5207797 0.5312173 0.7315183 -0.3633024 0.5769683 0.4022079 -0.09802651 0.9102855 0.4846427 -0.0669893 0.8721433 0.5720889 -0.5174894 0.6363326 0.5343291 -0.1808869 0.8256952 0.5849722 -0.6614853 0.4693024 0.4996262 -0.6590268 0.5621901 0.3335444 -0.5113493 0.7920039 0.367571 -0.3540511 0.8599648 0.4004478 -0.6559579 0.6398131 -0.02722281 -0.9962275 0.08240091 0.28935 -0.6529831 0.6999213 -0.4007189 -0.1529629 0.903342 -0.488368 -0.04068207 0.871689 -0.4067263 -0.07675516 0.9103199 -0.08517861 -0.4998409 0.8619188 -0.0868268 -0.341234 0.9359597 -0.6723288 -0.1451168 0.7258893 -0.6696567 -0.06772249 0.7395766 -0.60267 -0.03747802 0.7971101 -0.2469313 -0.1592189 0.9558632 -0.1834203 -0.05386632 0.9815577 -0.05420184 -0.9954712 0.07809829 -0.1086176 -0.938555 0.3275924 -0.2258417 -0.4960278 0.8384222 -0.2398212 -0.3369034 0.9104845 -0.3169368 -0.04470986 0.9473923 -0.5436693 -0.1508259 0.8256363 -0.1613845 -0.9371471 0.3093711 -0.2051538 -0.6396942 0.7407451 -0.324448 -0.6365054 0.6997103 -0.4353826 -0.6336639 0.6394625 -0.5349138 -0.6307142 0.5621982 -0.5992494 -0.4853814 0.6366358 -0.774007 -0.4812327 0.4114954 -0.6958353 -0.483514 0.5310627 -0.6893902 -0.6264908 0.3636626 -0.9372166 -0.1392289 0.3197505 -0.9371114 -0.05157679 0.3451985 -0.9070501 -0.03634792 0.4194508 -0.8976316 -0.3181325 0.3050397 -0.8722661 -0.1395027 0.4687122 -0.7830626 -0.1421891 0.6054711 -0.7386728 -0.03006082 0.6733935 -0.9727241 -0.03112912 0.2298672 -0.8484998 -0.03296089 0.5281683 -0.9361793 -0.3174922 0.1508874 -0.9776602 -0.138833 0.1578161 -0.9696928 -0.2292922 0.08438611 -0.9952655 -0.07001131 0.06741714 -0.9963928 -0.007751882 0.08450782 -0.9985638 -0.02469015 0.04754918 0.5842895 -0.7844647 0.2078965 0.2940488 -0.9492877 0.1113021 0.2841348 -0.9456102 0.1583952 0.02389633 -0.9976047 0.06491386 0.03103739 -0.9982335 0.0506609 0.01229912 -0.9972983 0.07242143 0.03338766 -0.9976928 0.05911505 0.03305208 -0.9981858 0.05032587 -2.13633e-4 -0.9969648 0.07785397 0.0227977 -0.9973917 0.0684846 0.03027468 -0.9974176 0.06512725 -0.05798649 -0.07403963 0.995568 -0.01348942 -0.9966032 0.08124196 0.09815049 -0.8709639 0.4814442 0.01058995 -0.997043 0.0761134 0.01837229 -0.9971088 0.07373327 0.1361763 -0.772256 0.6205455 0.01730442 -0.8687942 0.4948711 -0.00262463 -0.9966385 0.08188325 0.005127191 -0.9967825 0.07999038 0.03189283 -0.7695189 0.6378273 -0.06463879 -0.8665814 0.4948318 -0.01681584 -0.9962239 0.08517783 -0.00866729 -0.9964035 0.08429247 -0.07382601 -0.7666125 0.637852 -0.1455149 -0.8644524 0.481194 -0.03125113 -0.9958259 0.08575761 -0.02313327 -0.9960132 0.08615469 -0.1779571 -0.7637109 0.6205457 -0.2230614 -0.8622763 0.4546681 -0.04580909 -0.9953798 0.08438521 -0.03763014 -0.9956575 0.08514845 -0.05972564 -0.9949802 0.08029544 -0.05182141 -0.9952889 0.08194375 -0.8061234 -0.05807721 0.5888907 -0.5228592 -0.3293048 0.7862421 -0.2104288 -0.9358058 0.2828201 -0.07278841 -0.9946227 0.07367348 -0.06518948 -0.994933 0.07654267 -0.6451613 -0.3260752 0.6909718 -0.2544062 -0.9346134 0.2485466 -0.07712209 -0.9946521 0.06869876 -0.620554 -0.6279092 0.4697264 -0.7501336 -0.3235045 0.5767535 -0.5260534 -0.7539986 0.3933879 -0.08768105 -0.9944003 0.05899316 -0.6532672 -0.7501052 0.1028808 -0.685773 -0.7256009 0.05673569 -0.7709347 -0.6249024 0.1231127 -0.8350328 -0.3206946 0.4470741 -0.5839279 -0.7523645 0.3049194 -0.09653139 -0.9941849 0.04773157 -0.831406 -0.4795798 0.2806552 -0.7398824 -0.625404 0.2478787 -0.6262004 -0.7514833 0.2077161 -0.1034895 -0.9940004 0.03540188 -0.8668733 -0.4787274 0.1391074 -0.5129984 -0.8547227 0.0792585 -0.3585964 -0.9318929 0.05462872 -0.1075507 -0.9939588 0.02188247 -0.9047718 -0.4183875 0.07962453 -0.7993858 -0.5970444 0.0672335 -0.5503286 -0.8336722 0.04614555 -0.3726663 -0.9275 0.02938967 -0.02729833 -0.9996274 2.15009e-5 -0.02729463 -0.9996275 0 -0.02729833 -0.9996274 -3.7477e-5 -0.02729868 -0.9996274 -7.56331e-5 -0.02728974 -0.9996276 6.09022e-5 -0.02731537 -0.9996269 -6.39137e-5 -0.02729928 -0.9996274 0 -0.02728474 -0.9996277 6.68532e-5 -0.02729821 -0.9996274 -8.73465e-7 -0.02729636 -0.9996274 6.19649e-6 -0.02729612 -0.9996274 7.38557e-5 -0.02729612 -0.9996275 1.88493e-5 -0.02729851 -0.9996273 -3.18866e-4 -0.02729684 -0.9996274 -1.09791e-4 -0.02729791 -0.9996274 1.13651e-4 -0.02729558 -0.9996275 1.76196e-4 -0.02730059 -0.9996273 3.66338e-5 -0.02729862 -0.9996274 1.89747e-5 -0.02729809 -0.9996274 7.6234e-5 -0.02729856 -0.9996274 0 -0.02729737 -0.9996275 1.02052e-4 -0.02729898 -0.9996274 0 -0.02729946 -0.9996274 -1.07103e-4 -0.02729874 -0.9996274 -9.04718e-5 -0.02729892 -0.9996274 -1.90916e-5 -0.0272997 -0.9996274 0 -0.02729904 -0.9996274 -1.10857e-5 -0.0272997 -0.9996274 5.66989e-5 -0.02730011 -0.9996274 1.14179e-4 -0.02729994 -0.9996274 0 -0.02729904 -0.9996274 6.54707e-5 -0.02729803 -0.9996274 8.05745e-5 -0.02730011 -0.9996273 5.28263e-5 -0.02729862 -0.9996274 -7.75657e-7 -0.02729713 -0.9996274 -9.91721e-5 -0.02731335 -0.9996269 2.66553e-5 -0.02727329 -0.9996281 -2.58797e-5 -0.02737563 -0.9996253 -5.8294e-5 -0.02733218 -0.9996265 -8.30991e-5 -0.02803671 -0.9996066 -8.46863e-4 -0.02745467 -0.9996231 9.25063e-5 -0.02717661 -0.9996306 -3.07749e-4 -0.02727383 -0.9996281 -6.57311e-6 -0.02730333 -0.9996273 5.05143e-5 -0.02747744 -0.9996224 3.86586e-4 -0.02732527 -0.9996267 8.64505e-5 -0.02722191 -0.9996294 -1.58617e-4 -0.02725112 -0.9996287 -1.22239e-4 -0.02734369 -0.9996262 7.67556e-5 -0.02729803 -0.9996274 0 -0.02724903 -0.9996287 -1.05714e-4 -0.02728164 -0.9996279 0 -0.02729868 -0.9996274 1.15501e-4 -0.02734875 -0.999626 -2.32336e-4 -0.02702265 -0.9996348 2.1999e-4 -0.02730363 -0.9996273 -6.31177e-5 -0.02729189 -0.9996275 6.91138e-5 -0.02726519 -0.9996283 1.616e-4 -0.02728557 -0.9996277 5.81246e-5 -0.02729737 -0.9996274 -4.81006e-5 -0.02732414 -0.9996267 -1.01614e-4 -0.02729707 -0.9996275 -4.39841e-5 -0.02727746 -0.999628 1.36807e-4 -0.02729487 -0.9996275 0 -0.02729588 -0.9996275 4.24043e-5 -0.02730756 -0.9996272 -1.17693e-4 -0.02730035 -0.9996274 -4.01271e-5 -0.02730149 -0.9996274 -3.819e-5 -0.02729958 -0.9996274 0 -0.02729862 -0.9996274 -1.47282e-4 -0.02729314 -0.9996275 1.88947e-4 -0.02735912 -0.9996256 -4.10355e-4 -0.02694177 -0.999637 4.93567e-4 -0.02701085 -0.9996351 4.26102e-4 -0.02866309 -0.9995889 -8.48067e-4 -0.0271998 -0.9996301 0 -0.02738165 -0.999625 -3.16337e-4 -0.02862161 -0.9995899 -0.001035273 -0.02613013 -0.9996581 0.001004457 -0.02719163 -0.9996303 -1.63842e-5 -0.02757626 -0.9996197 -3.48455e-4 -0.02711433 -0.9996324 1.34323e-4 -0.02759462 -0.9996193 -2.52429e-4 -0.02726072 -0.9996284 5.92604e-5 -0.02696233 -0.9996364 4.3698e-4 -0.02721697 -0.9996296 1.0501e-4 -0.0274865 -0.9996222 -1.77726e-4 -0.02732151 -0.9996267 -1.33356e-4 -0.02697616 -0.999636 5.70003e-4 -0.02760243 -0.999619 -5.15267e-4 -0.02720063 -0.99963 1.25141e-4 -0.02726513 -0.9996283 0 -0.02733492 -0.9996263 -1.19316e-4 -0.02732002 -0.9996268 1.01506e-4 -0.02724695 -0.9996289 7.36082e-5 -0.0273087 -0.9996271 5.45651e-6 -0.0272578 -0.9996285 7.99524e-5 -0.02729576 -0.9996275 -4.0514e-6 -0.02733874 -0.9996262 4.19119e-5 -0.0272938 -0.9996275 0 -0.02730822 -0.9996272 8.32493e-6 -0.02732926 -0.9996266 1.50227e-5 -0.02726554 -0.9996283 -1.83833e-5 -0.02729851 -0.9996274 0 -0.02727609 -0.999628 -1.33761e-5 -0.0272926 -0.9996275 -2.23662e-6 -0.02732264 -0.9996268 3.35341e-6 -0.02728956 -0.9996277 -5.58836e-7 -0.02731698 -0.9996269 2.23649e-6 -0.02729034 -0.9996276 1.66848e-6 -0.0271793 -0.9996306 -2.51477e-6 -0.02728295 -0.9996278 2.21867e-6 -0.02731478 -0.999627 1.38874e-6 -0.02729904 -0.9996274 0 -0.02728694 -0.9996277 5.54265e-6 -0.0272904 -0.9996276 1.04735e-4 -0.02728015 -0.9996278 4.2841e-4 -0.02727442 -0.999628 2.57902e-4 -0.02729582 -0.9996275 -4.82785e-5 -0.02727895 -0.9996279 0 -0.02730047 -0.9996274 -1.08977e-4 -0.02728885 -0.9996276 1.03214e-4 0.0862779 -0.8557596 0.5101292 0.08838361 -0.8284136 0.5530998 0.09085595 -0.7944481 0.6004979 0.09479212 -0.7931596 0.6015915 0.098028 -0.7944481 0.5993687 0.100041 -0.7561065 0.6467572 0.09485518 -0.8332792 0.5446544 0.09171003 -0.883987 0.458428 0.08530128 -0.8847225 0.4582465 0.07916647 -0.9146264 0.3964734 0.08838319 -0.8841681 0.4587322 0.0770291 -0.9378696 0.3383301 0.09094756 -0.8682445 0.4877294 0.07681643 -0.9474643 0.3105009 0.0822798 -0.9465233 0.3119675 0.08917623 -0.9031459 0.4199706 0.08618623 -0.9291266 0.3595772 0.06796622 -0.9778041 0.1981915 0.07278698 -0.9617342 0.2641389 0.06665438 -0.9831832 0.1700237 0.07343006 -0.9717736 0.2241967 0.07046926 -0.982572 0.1720073 0.07773226 -0.9536624 0.2906644 0.05829131 -0.9967207 0.05612444 0.06106877 -0.9906515 0.121985 0.05572742 -0.9971739 0.05038666 0.05911493 -0.9951579 0.07852494 0.0594502 -0.9965847 0.05731391 0.06619602 -0.9863182 0.1509783 0.05298131 -0.9984964 0.01406931 0.09998106 -0.721414 0.6852487 0.0970804 -0.6722993 0.7338863 0.1000401 -0.6820922 0.7243911 0.10227 -0.6289714 0.7706724 0.09442603 -0.7877589 0.6087034 0.09299319 -0.6809227 0.7264274 0.09125298 -0.7514486 0.6534509 0.09320557 -0.7160106 0.6918393 0.1000428 -0.5891482 0.8018079 0.09808754 -0.5508345 0.8288307 0.1004095 -0.4830642 0.8698086 0.09534204 -0.5311872 0.8418729 0.09210711 -0.6229287 0.7768374 0.09158819 -0.5478814 0.8315272 0.09616667 -0.4394185 0.8931201 0.09369289 -0.5818727 0.8078649 0.09094554 -0.4850937 0.8697201 0.08734637 -0.4035269 0.9107891 0.09274792 -0.4088966 0.9078555 0.08993911 -0.3735817 0.9232268 0.08783429 -0.31212 0.9459737 0.09113043 -0.4293751 0.8985168 0.08508622 -0.2717694 0.9585937 0.08649128 -0.3613163 0.9284233 0.08072292 -0.2647834 0.9609233 0.08301311 -0.2988473 0.9506835 0.07999086 -0.1892801 0.9786596 0.08316528 -0.2417744 0.966762 0.07611477 -0.1524737 0.9853723 0.0745275 -0.1357792 0.9879321 0.06891107 -0.0697351 0.9951826 0.07355195 -0.1466461 0.9864508 0.0798676 -0.2272427 0.9705576 0.07529145 -0.1634621 0.9836724 0.06341773 -0.01538139 0.9978686 0.06787341 -0.05853468 0.9959754 0.07049798 -0.1060827 0.9918552 0.06585919 -0.0509966 0.9965249 0.06662243 0.09576785 0.9931718 0.06720334 0.05740666 0.9960865 0.07467913 0.1525017 0.9854778 0.06261342 7.1452e-5 0.9980379 0.08233988 0.3651887 0.927285 0.08414059 0.4041007 0.9108364 0.07876938 0.3008252 0.9504208 0.07199382 0.1774973 0.9814845 0.07535141 0.2302963 0.9701989 0.07715213 0.2646307 0.9612587 0.09750729 0.722256 0.684718 0.09705281 0.6822692 0.7246306 0.09616529 0.7658128 0.6358325 0.09421265 0.7945663 0.5998236 0.08871895 0.6807892 0.7270867 0.08826267 0.6392636 0.7639057 0.09170901 0.690244 0.7177415 0.0867663 0.7304179 0.6774669 0.08737605 0.7649604 0.6381232 0.08575862 0.7946255 0.6010124 0.08212739 0.8395248 0.5370786 0.07986915 0.8852444 0.4582176 0.08804661 0.88422 0.4586969 0.09085673 0.8506107 0.5178865 0.08771312 0.8072721 0.583625 0.07840245 0.947025 0.311443 0.07867759 0.9406214 0.3302139 0.08377557 0.9160686 0.3921735 0.07657337 0.962676 0.2595987 0.07672595 0.9031327 0.4224508 0.0726363 0.9287992 0.3633953 0.07126235 0.9479576 0.3103194 0.07257401 0.975721 0.2066437 0.07236045 0.9536568 0.2920665 0.06671398 0.9827653 0.1724005 0.06457835 0.986285 0.1518934 0.05920767 0.9944143 0.08737707 0.06055033 0.9835464 0.1702063 0.06622695 0.9751848 0.2112549 0.05887049 0.9903309 0.1256148 0.05264496 0.996684 0.06204473 0.0571323 0.9965804 0.05969589 0.05212604 0.9970485 0.05636817 0.04878008 0.9987725 -0.008612334 0.05157685 0.9984554 0.02066123 0.04898315 0.9987993 9.15574e-4 0.04702931 0.9988476 -0.009582877 0.04794478 0.9987841 0.01147496 0.04605275 0.9989389 6.10374e-4 0.08539128 0.8857743 0.4561933 0.08249318 0.8677502 0.4901066 0.09189355 0.8136135 0.5740982 0.08789533 0.5476065 0.8321067 0.08728641 0.5989496 0.7960154 0.08438622 0.4922479 0.8663551 0.09115964 0.5513831 0.8292568 0.09549552 0.5502057 0.8295508 0.09610426 0.6159951 0.7818658 0.0944572 0.6693492 0.7369189 0.0835312 0.4358454 0.8961369 0.09317499 0.5588058 0.8240478 0.09482485 0.5047662 0.8580324 0.09039705 0.4088318 0.9081217 0.09283775 0.4525308 0.8869031 0.0876525 0.3727064 0.9238004 0.08270668 0.2714977 0.9588789 0.07086491 0.145209 0.9868599 0.08481347 0.3094061 0.9471402 0.0797761 0.242136 0.9669571 0.06497579 0.05163878 0.9965499 0.06900435 0.1186289 0.990538 0.0659219 0.05334788 0.9963977 0.07544231 0.1729801 0.9820318 0.06222844 0.02572757 0.9977303 0.0633884 -0.009033679 0.9979481 0.05285888 -0.9985674 -0.008318662 0.0550571 -0.9984441 0.008850634 0.09598302 -0.6659604 0.7397865 0.09500759 -0.5338801 0.8402057 0.06261318 7.16554e-5 0.9980379 0.06323516 0.00778228 0.9979684 0.04826211 0.9988147 -0.006341516 0.04691296 0.9988461 -0.0102775 0 0 1 1.63698e-7 0 1 -3.83456e-7 0 1 3.16793e-7 0 1 -8.56904e-7 0 1 2.28867e-7 0 1 3.87731e-7 0 1 -1.37265e-7 0 1 -1.28572e-7 0 1 0 0 1 0 0 1 -1.20696e-7 0 1 5.57983e-7 0 1 -5.61899e-7 0 1 0 0 1 0 0 1 -1.21242e-7 0 1 3.11523e-7 0 1 1.42538e-7 0 1 -0.06446099 -0.9979202 0 -0.06446099 -0.9979202 0 1 -1.37287e-5 0 0.5339047 0.5993992 0.5963777 0.3000927 0.6761166 0.6729121 0.4228771 0.640084 0.6414573 0.1655367 0.6966032 0.6980986 0.298692 0.674079 0.6755744 0.533726 0.5973289 0.5986106 0.6325452 0.5477318 0.5476098 0.8403055 0.3829503 0.3837133 0.9060811 0.2983241 0.3000331 0.910836 0.293439 0.2902956 0.7529701 0.4671881 0.4634343 0.7815325 0.4402377 0.4420383 0.9639302 0.1875122 0.1888856 0.9834646 0.1286362 0.1274765 0.9945859 0.0716893 0.07522946 0.9973315 0.0516687 0.05157715 0.7159268 0.4927375 0.4946298 0.1715794 0.6986168 0.6946188 0.09146636 0.7028598 0.7054234 -6.29406e-6 0 1 2.91185e-6 0 1 1 -2.4174e-5 0 1 4.34107e-4 0 1 2.57178e-4 0 1 9.44209e-5 0 1 -1.02673e-4 0 1 5.20651e-6 0 1 -9.44362e-5 0 1 -1.60921e-4 0 1 -1.47955e-4 0 1 -6.21738e-6 0 1 8.11506e-5 0 1 -9.93606e-5 0 1 1.99905e-5 0 1 -1.03642e-4 0 1 8.09199e-6 0 0.06555533 -0.9918762 0.1090148 0.05945104 -0.9980638 0.01828086 0.05859678 -0.9981296 0.01742643 0.06286841 0.03903335 0.9972583 0.06357079 0.04767048 0.9968382 0.06509768 0.07004177 0.9954177 0.05993938 0.009582936 0.9981561 0.05902427 0.001342833 0.9982556 0.06576842 0.08160781 0.9944922 0.06622648 0.09204566 0.9935501 0.0555309 -1.43095e-4 0.998457 0.08020353 0.4765824 0.8754638 0.08670449 0.527918 0.8448581 0.08283054 0.4699736 0.8787856 0.06644093 0.09876108 0.9928907 0.05374211 0.01618289 0.9984237 0.06470012 0.06283843 0.9959243 0.0651887 0.0709263 0.9953492 0.06415116 0.05508697 0.9964187 0.06100785 0.01947122 0.9979473 0.06198441 0.02948153 0.9976417 0.06198489 0.00149542 0.998076 0.06213736 0.01040709 0.9980134 0.06479197 0.01471018 0.9977905 0.06628775 0.03137373 0.9973072 0.06457394 0.00122255 0.9979122 0.06358575 0.03329426 0.9974209 0.06357169 0.007324576 0.9979504 0.06018322 -9.66252e-5 0.9981874 0.07663297 -0.2244055 0.9714781 0.06879061 -0.09934049 0.9926729 0.06766015 -0.1092572 0.9917082 0.06094723 -0.01928824 0.9979546 0.06195294 -0.01886051 0.9979009 0.08316469 -0.4916635 0.8668049 0.07989805 -0.3806298 0.9212694 0.07818889 -0.3943628 0.9156225 0.0934199 -0.4992974 0.8613797 0.08945143 -0.4026689 0.9109644 0.09366303 -0.5197094 0.8491935 0.0956788 -0.6098724 0.7867028 0.09598332 -0.6329712 0.7682024 0.07611346 -0.3603947 0.9296895 0.07989966 -0.441249 0.8938208 0.07913726 -0.4055442 0.9106433 0.08078432 -0.9348645 0.3456911 0.08536249 -0.8794751 0.4682273 0.08063173 -0.9305306 0.3572273 0.08841419 -0.5885634 0.8036019 0.09244269 -0.6243621 0.7756457 0.08527088 -0.5921352 0.8013144 0.0921055 -0.9403737 0.3274354 0.08441489 -0.9501104 0.3002741 0.09457832 -0.9318056 0.3504189 0.08881121 -0.9586427 0.2704012 0.08923828 -0.9535434 0.2877355 0.07525986 -0.9903721 0.1161858 0.06671488 -0.990927 0.1166748 0.07956218 -0.9759263 0.2030712 0.1131653 -0.9602263 0.2552627 0.05951154 -0.9981558 0.01198327 0.0950362 -0.9859167 0.1376102 0.09570902 -0.9829708 0.15687 0.09796619 -0.9788991 0.17933 0.05770832 -0.9983285 -0.003158926 0.09552389 -0.9875586 0.1249135 0.08963358 -0.990944 0.09997946 0.06997907 -0.9955461 0.06317341 0.06109976 -0.9979223 0.02044796 0.0575515 -0.9983415 -0.001500368 0.05579465 -0.9982793 -0.01804423 0.05477243 -0.9984855 -0.005178034 0.09686839 -0.9890713 0.1111515 0.05415356 -0.9983795 -0.0174933 0.1018723 -0.9737989 0.2033172 0.08807927 -0.9669189 0.239395 0.08902376 -0.9630559 0.2541618 0.06048417 -0.9981692 -4.98456e-5 0.09054923 -0.9466013 0.30943 0.09915506 -0.91736 0.3855115 0.05659002 -0.9983935 -0.002849936 0.08902448 -0.9234496 0.3732497 0.08462959 -0.9223499 0.3769726 0.08862888 -0.9167171 0.3895826 0.08923786 -0.908249 0.4088037 0.0892952 -0.9075874 0.4102579 0.09161943 -0.8885742 0.4494906 0.09030485 -0.8985015 0.4295814 0.09299063 -0.8793065 0.4670896 0.09470218 -0.8680981 0.4872752 0.0894519 -0.8699206 0.4850119 0.08963412 -0.8563618 0.5085373 0.08545279 -0.8721377 0.4817403 0.09076428 -0.8374793 0.5388787 0.1004081 -0.7859298 0.6101088 0.09348058 -0.7754954 0.6243944 0.0995838 -0.7535165 0.6498431 0.09991914 -0.7722524 0.6274093 0.07403981 -0.9681031 0.2393629 0.05676537 -0.9983077 0.01263487 0.05578839 -0.998362 0.01269578 0.06256461 -0.9940761 0.08887231 0.09204655 -0.6922414 0.7157719 0.08905333 -0.7430979 0.6632307 0.0972954 -0.6171912 0.7807745 0.06408929 -0.9930789 0.09842282 0.07346004 -0.9712479 0.2264536 0.08005023 -0.9429939 0.3230392 0.07156765 -0.9763725 0.2038992 0.09341865 -0.7442671 0.6613165 0.08032637 -0.9271715 0.3659245 0.08746886 -0.8914442 0.4446082 0.0817908 -0.9328429 0.3508766 0.0845685 -0.9133462 0.3983052 0.05777168 -0.9982028 0.01593071 0.08624744 -0.5616156 0.8228909 0.0850268 -0.5221246 0.8486203 0.08649051 -0.889046 0.4495739 0.09311437 -0.8212438 0.5629284 0.09082502 -0.8208737 0.5638415 0.08627808 -0.883565 0.4602924 0.08734655 -0.8886339 0.4502224 0.07382547 -0.9708709 0.2279465 0.08359169 -0.4838188 0.871167 0.09595179 -0.733891 0.6724562 0.09164756 -0.8219597 0.5621237 0.08765083 -0.8179727 0.5685402 0.08624696 -0.8157145 0.5719889 0.08441597 -0.8751979 0.476343 0.08911764 -0.7450784 0.6609965 0.0871632 -0.7469912 0.6590955 0.07254409 -0.2821498 0.9566237 0.08060026 -0.9388822 0.3346698 0.08920621 -0.6612187 0.7448705 0.08713221 -0.6678205 0.7392048 0.08185267 -0.475887 0.8756894 0.08124244 -0.4580952 0.8851828 0.08237111 -0.4755797 0.8758077 0.09470087 -0.731666 0.675053 0.08920699 -0.8194347 0.5661882 0.09436631 -0.6922739 0.7154383 0.09680813 -0.6525397 0.7515453 0.06540209 -0.1317808 0.989119 0.06338828 -0.1266545 0.9899195 0.05563604 -0.02438461 0.9981534 0.08868712 -0.566151 0.8195167 0.08679699 -0.5794401 0.8103799 0.08490359 -0.4758204 0.875435 0.09103876 -0.74241 0.6637315 0.07120138 -0.2782134 0.9578768 0.07306218 -0.268444 0.9605206 0.064884 -0.1219552 0.9904127 0.05486387 -2.79822e-4 0.9984938 0.09125399 -0.6533359 0.7515484 0.05515551 -3.13651e-5 0.9984778 0.05519431 -1.39705e-4 0.9984756 0.09222894 -0.5365881 0.838789 0.09048837 -0.5515368 0.8292279 0.0932669 -0.6449335 0.7585263 0.05386555 -0.02576148 0.9982159 0.08563631 -0.3146815 0.9453264 0.08362209 -0.2952104 0.9517659 0.0891171 -0.3749328 0.9227588 0.05082458 -0.01558715 0.998586 0.08777379 -0.4370075 0.895165 0.08642935 -0.4571723 0.8851687 0.08243274 -0.3428848 0.9357537 0.08328634 -0.3204801 0.9435868 0.06341904 -0.01944077 0.9977976 0.07571804 -0.2416814 0.967397 0.05957388 -0.02041745 0.9980152 0.09164983 0.804553 0.5867664 0.09146678 0.7842587 0.6136549 0.09219855 0.7399385 0.6663261 0.05105602 9.39613e-5 0.9986958 0.0540595 0.01531302 0.9984203 0.05552405 -2.3404e-4 0.9984574 0.05554312 -1.34904e-4 0.9984564 0.05554693 -1.2784e-4 0.9984561 0.05389302 0.01501142 0.9984339 0.05550241 -1.63549e-4 0.9984586 0.05538129 0.00321424 0.9984602 0.05621606 0.0167244 0.9982785 0.06463932 0.1160638 0.9911362 0.06717228 0.1106008 0.9915924 0.07294017 0.2136018 0.974194 0.07614398 0.2678316 0.9604521 0.05641222 -4.51972e-6 0.9984076 0.05071157 2.02375e-5 0.9987134 0.05176019 0.02282816 0.9983986 0.06042844 0.106055 0.9925225 0.05337816 0.01455765 0.9984683 0.080509 0.3872858 0.9184379 0.0731852 0.2626184 0.9621204 0.07431375 0.2536739 0.9644309 0.05612426 0.01727366 0.9982744 0.05746704 0.01648014 0.9982115 0.06396782 0.1086476 0.9920201 0.07519918 0.3190472 0.9447509 0.07745623 0.3648806 0.927827 0.07059037 0.2451894 0.966902 0.08163845 0.3759949 0.9230186 0.08566659 0.4929111 0.8658522 0.08252388 0.5447676 0.8345167 0.09180194 0.6632144 0.7427781 0.09302216 0.7374936 0.6689172 0.09048801 0.6667429 0.7397742 0.09149605 0.736882 0.6698012 0.08655095 0.4835381 0.8710339 0.08914744 0.5869816 0.8046772 0.08676666 0.7437886 0.6627596 0.08685731 0.7186025 0.6899756 0.08053952 0.657348 0.7492711 0.08859568 0.6793459 0.7284504 0.09430599 0.6794003 0.7276825 0.09018355 0.5907558 0.8017946 0.08490526 0.6485093 0.7564569 0.07925766 0.713014 0.6966558 0.08469074 0.7999079 0.594117 0.09094673 0.8614 0.4997188 0.09161728 0.8686247 0.4869267 0.07635867 0.7580021 0.6477672 0.08246189 0.8504685 0.5195223 0.07541316 0.8025048 0.5918606 0.08984845 0.8524617 0.5150112 0.07666414 0.7833355 0.6168534 0.08853572 0.9322955 0.3506942 0.08566784 0.9119186 0.4013296 0.08664363 0.9522869 0.2926475 0.07523095 0.9020394 0.4250474 0.07120168 0.8572894 0.5098873 0.07263559 0.834119 0.5467812 0.08395761 0.9145305 0.3957086 0.0782808 0.9686984 0.2355749 0.07422316 0.9739959 0.214063 0.07120138 0.9785992 0.1930646 0.0894525 0.9034978 0.4191541 0.07431453 0.68348 0.7261766 0.08166813 0.6105579 0.7877497 0.0855754 0.5711334 0.8163844 0.07272595 0.7187143 0.6914917 0.0752601 0.7305359 0.6787145 0.09912699 0.6184757 0.7795265 0.09012472 0.6197642 0.779596 0.09561669 0.6897038 0.7177509 0.08615589 0.6044038 0.7920058 0.09647208 0.625863 0.7739436 0.0913133 0.6578102 0.7476281 0.09509783 0.7070994 0.7006903 0.09750813 0.7140222 0.6932997 0.09812003 0.7390896 0.6664227 0.07873964 0.3985815 0.9137466 0.08456814 0.591916 0.8015509 0.06525069 0.1525059 0.9861462 0.06250381 0.1118233 0.9917605 0.05969446 0.07931792 0.9950605 0.08893251 0.4979185 0.8626518 0.0889008 0.4665693 0.8800055 0.08346921 0.3924121 0.9159945 0.08520877 0.382341 0.9200842 0.0564177 2.25433e-5 0.9984073 0.0547958 -2.14306e-4 0.9984976 0.05551677 1.98528e-4 0.9984578 0.05419135 0 0.9985306 0.06381821 -0.9979159 0.009551703 0.06263166 -0.9980368 -6.60865e-5 0.05828005 -0.9983 -7.91906e-4 0.06793451 -0.9965254 0.04818892 0.05758553 -0.9983397 -0.001387417 0.05558514 -0.998379 -0.01224058 0.05603426 -0.9984269 -0.00202924 0.0583533 -0.9982956 -9.03731e-4 0.06210935 -0.9980691 -7.26018e-4 0.06586068 -0.9973103 0.03216731 0.05556887 -0.9984468 -0.00404793 0.05456036 -0.9984917 -0.006145358 0.05367726 -0.9985216 -0.008574247 0.06357169 -0.9978894 0.01324534 0.06222814 -0.998062 0 0.1069695 -0.9675781 0.2288018 0.05447643 -0.9984909 0.006958305 0.05871909 -0.9969127 0.05212694 0.05337941 -0.9985215 -0.01028221 0.09201508 -0.7121632 0.6959575 0.07321608 -0.9736001 0.2161996 0.06326639 -0.9923945 0.1055966 0.06766051 -0.9849075 0.1593089 0.09235215 -0.7293868 0.6778393 0.09582996 -0.5570956 0.8249007 0.07831287 -0.9527255 0.2935665 0.1003769 -0.7295565 0.6765145 0.09674566 -0.5978396 0.7957563 0.0947926 -0.7361841 0.67011 0.09250479 -0.8210373 0.5633301 0.09531152 -0.6358069 0.7659409 0.08838462 -0.8624216 0.4984148 0.08105748 -0.5005973 0.861877 0.08911579 -0.4167385 0.9046477 0.09293055 -0.7393549 0.6668721 0.09323608 -0.7799178 0.6188986 0.08469253 -0.5914134 0.8019087 0.06799679 -0.1923627 0.9789654 0.07712274 -0.1901059 0.9787297 0.08231097 -0.2624673 0.9614239 0.09476083 -0.5646283 0.8198875 0.07284867 -0.2750673 0.9586611 0.05525559 0.01960325 0.9982799 0.09140557 -0.436702 0.8949506 0.06939935 -0.08499437 0.9939616 0.07730573 -0.2041141 0.97589 0.08130252 -0.3632367 0.9281429 0.06299102 -0.1041305 0.992567 0.05673491 -0.02157694 0.9981561 0.05905377 -0.02145463 0.9980243 0.05505603 -1.01867e-4 0.9984833 0.07449638 -0.256297 0.9637231 0.06634849 -0.116644 0.9909551 0.078983 -0.2068878 0.9751714 0.05503147 -1.42745e-4 0.9984847 0.074252 -0.1234481 0.9895692 0.05512768 1.66457e-4 0.9984794 0.05722308 -0.02313339 0.9980934 0.05850404 -0.02182072 0.9980487 0.06494504 -0.01559531 0.997767 0.06909549 -0.05780339 0.995934 0.06525003 -0.0197764 0.997673 0.05504238 -1.15576e-4 0.998484 0.05341297 -1.60729e-4 0.9985725 0.05413627 2.88179e-4 0.9985335 0.05628556 -5.34334e-5 0.9984148 0.06257432 -3.34617e-5 0.9980403 0.06350845 -7.74553e-5 0.9979813 0.05328536 -1.85969e-5 0.9985793 0.05092036 -0.01918804 0.9985184 0.05486786 -2.6689e-4 0.9984937 0.05570244 7.07212e-5 0.9984474 0.05732667 -6.87915e-5 0.9983555 0.058752 -1.01925e-4 0.9982726 0.05519068 -1.2327e-4 0.9984759 0.05250006 -0.03345125 0.9980605 0.06434869 0 0.9979275 0.05861473 0.01257884 0.9982015 0.05627757 -0.004862248 0.9984034 0.05786323 8.68822e-5 0.9983245 0.05485183 1.33023e-4 0.9984945 0.05561661 1.18295e-4 0.9984523 0.05955904 1.47603e-4 0.9982249 0.05874335 -1.10362e-4 0.9982731 0.06124579 -1.00847e-4 0.9981228 0.06266582 -1.79671e-4 0.9980346 0.06191271 2.03737e-4 0.9980816 0.06395202 0 0.9979531 0.05641496 4.23945e-6 0.9984074 0.06346231 -1.40562e-4 0.9979842 0.05572402 -0.008485972 0.9984102 0.05903935 0.014355 0.9981524 0.05719274 4.50738e-6 0.9983631 0.06110978 1.25226e-5 0.998131 0.06033283 1.16311e-5 0.9981784 0.05554604 -1.28252e-4 0.9984562 0.05547279 -1.13708e-4 0.9984602 0.05395507 6.72061e-4 0.9985432 0.05620056 -0.0162009 0.9982881 0.0581147 -0.004008412 0.9983019 0.05982959 0.00685966 0.9981851 0.0592522 0.008426368 0.9982075 0.06253874 0.03222107 0.9975224 0.05348038 -2.17682e-4 0.9985689 0.05547749 -1.27624e-4 0.99846 0.05163699 -0.008081197 0.9986333 0.06293684 0.03638809 0.997354 0.0580483 1.44476e-5 0.9983139 0.06189846 2.41663e-5 0.9980825 0.0617839 0.009268283 0.9980466 0.064511 0.03907793 0.9971516 0.06082499 0.02862709 0.9977379 0.07971531 0.2983526 0.951121 0.04948836 -0.004295825 0.9987655 0.06503665 0.04184198 0.9970053 0.06268543 0.03250241 0.9975041 0.07130569 0.06222146 0.995512 0.09351056 0.5304528 0.8425412 0.06976634 0.2359727 0.9692521 0.095555 0.6421202 0.7606255 0.09195387 0.825754 0.5564844 0.08191341 0.6848805 0.7240366 0.07974714 0.7334418 0.6750583 0.08194279 0.7074854 0.7019615 0.07901471 0.7533103 0.6529015 0 0 1 -4.48504e-7 0 1 2.13895e-5 0 1 6.25939e-5 0 1 -1.30698e-5 0 1 1.30949e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 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 8.58898e-6 0 1 -6.18871e-6 0 8.15225e-6 0 1 0 0 1 -1.00664e-6 0 1 -1.20034e-5 0 1 7.55812e-7 0 1 -7.2448e-6 0 1 2.21676e-7 0 1 0 0 -1 0 0 -1 1 0 3.51922e-6 1 0 0 1 0 -3.60397e-6 1 -7.74654e-6 0 -0.7165347 0.6975516 1.22078e-4 -0.6966076 0.7174524 -3.05195e-5 -0.7200932 0.6938774 0 -0.5772067 0.8165981 1.22076e-4 -0.5230737 0.8522875 -1.83117e-4 -0.5853591 0.8107743 -1.52596e-4 -0.637271 0.7706398 1.52596e-4 -0.4311747 0.9022685 9.15575e-5 -0.3904284 0.9206333 2.44151e-4 -0.4013615 0.9159197 -1.83117e-4 -0.3137575 0.9495031 -2.11231e-4 -0.345421 0.9384477 3.66235e-4 -0.3071125 0.9516733 2.13633e-4 -0.3309757 0.9436393 -3.05187e-4 -0.2998473 0.9539873 -1.52594e-4 -0.2763814 0.961048 1.83115e-4 -0.2713739 0.9624741 -1.22076e-4 -0.2106643 0.9775584 -1.80055e-4 -0.1846036 0.9828131 3.37518e-5 -0.145654 0.9893356 -1.67842e-4 -0.1404778 0.9900838 1.25634e-4 -0.08862334 0.9960652 -4.06769e-5 -0.06964206 0.9975721 -5.05321e-5 -0.05455917 0.9985105 5.23876e-5 0.01042312 0.9999457 -9.78215e-5 0.02568066 0.9996702 -6.11752e-5 0.0804916 0.9967554 -1.20908e-4 0.1012182 0.9948642 2.56037e-4 0.1094071 0.993997 -2.71782e-4 0.1265653 0.9919583 -1.54529e-4 0.1420609 0.9898579 5.16334e-5 0.1518359 0.9884058 1.1216e-4 0.1546938 0.9879625 -3.03023e-4 0.1615595 0.986863 2.4639e-4 0.1686135 0.9856823 -2.64608e-4 0.1769434 0.9842211 3.43332e-4 0.1800281 0.9836615 -3.98351e-4 0.1861784 0.982516 2.48514e-4 0.1917281 0.9814481 1.01961e-4 0.1927511 0.9812477 -2.1923e-4 0.1955549 0.9806928 2.97914e-4 0.1973657 0.98033 -2.77566e-4 0.1985479 0.9800912 2.12574e-4 0.1994516 0.9799077 -1.9935e-4 0.2128131 0.9770929 2.88833e-5 0.2133641 0.9769728 1.35046e-5 0.2153362 0.97654 -7.9512e-5 0.2152864 0.9765511 -7.4215e-5 0.2143612 0.9767544 5.25383e-5 0.214818 0.9766542 -2.39783e-5 0.2133833 0.9769686 1.19288e-5 0.2143331 0.9767607 5.38484e-5 0.209631 0.9777806 -4.73592e-5 0.2001579 0.9797637 -1.70835e-4 0.214356 0.9767556 2.68694e-5 0.2478443 0.9687998 5.39917e-4 0.2141527 0.9768002 3.97016e-5 0.2131878 0.9770113 1.57084e-5 0.2142868 0.9767708 3.71658e-5 0.2154687 0.9765107 1.2142e-4 0.2154668 0.9765112 -9.0795e-5 0.2148656 0.9766438 8.39712e-5 0.2147422 0.9766708 -3.82015e-5 0.2131606 0.9770172 1.21441e-6 0.2150172 0.9766104 5.57147e-5 0.2142487 0.9767792 -7.81393e-6 0.2124446 0.9771732 8.75879e-7 0.2144101 0.9767438 -1.5969e-5 0.2145586 0.9767111 2.89768e-5 0.2092397 0.9778644 -4.28045e-5 0.2124389 0.9771744 3.26693e-5 0.211158 0.977452 2.63722e-5 0.2038397 0.9790044 -1.22078e-4 0.205146 0.9787314 6.10372e-5 0.2083847 0.978047 -1.52596e-4 0.2094595 0.9778174 -8.48163e-6 0.2083174 0.9780613 -5.55527e-5 0.2068893 0.9783645 -1.55986e-4 0.2098616 0.9777311 2.25558e-4 0.2070767 0.9783248 -1.38321e-4 0.2068006 0.9783831 3.69434e-4 0.2008666 0.9796187 2.49891e-4 0.2105721 0.9775782 3.70829e-4 0.1777761 0.984071 -2.74676e-4 0.1918122 0.9814316 -2.13633e-4 0.1986802 0.9800644 -1.83115e-4 0.2058197 0.9785899 2.13633e-4 0.1585165 0.9873563 -4.88307e-4 0.1740813 0.9847313 -4.57787e-4 0.1612308 0.9869167 -3.05188e-4 0.1690739 0.9856034 3.05188e-5 0.1713927 0.9852029 0 0.1874991 0.9822648 -1.36896e-4 0.1687478 0.9856593 -2.97264e-4 0.1409384 0.9900184 -1.30115e-4 0.1282402 0.9917432 1.09541e-4 0.1138018 0.9935035 2.14529e-4 0.09404212 0.9955682 -2.85726e-4 0.08449077 0.9964243 3.11714e-4 0.06906747 0.997612 -8.4394e-5 0.06545007 0.9978559 2.84272e-4 0.05603581 0.9984288 -2.69868e-4 0.04686939 0.9989011 3.43188e-4 0.03956824 0.9992169 -2.53735e-4 0.02826499 0.9996005 1.75987e-4 0.01211541 0.9999267 7.37422e-5 -0.002719223 0.9999964 1.37234e-4 -0.006141185 0.9999812 -1.18519e-4 -0.01569992 0.9998769 1.3006e-4 -0.01907676 0.999818 -1.26627e-4 -0.03408956 0.9994189 1.1809e-4 -0.03524047 0.9993789 -2.64883e-5 -0.05392497 0.998545 -2.14375e-5 -0.07071411 0.9974967 6.19951e-5 -0.08836656 0.9960881 -7.18439e-5 -0.1052328 0.9944477 1.30083e-4 -0.108941 0.9940482 -2.50272e-4 -0.1247038 0.992194 1.96648e-4 -0.1296674 0.9915575 -1.73428e-4 -0.1593511 0.987222 2.12506e-4 -0.1634064 0.9865589 -1.37125e-4 -0.1843379 0.982863 3.18606e-6 -0.1961161 0.9805808 3.05192e-5 -0.1974599 0.980311 -6.10386e-5 -0.2179644 0.9759568 9.1556e-5 -0.2283803 0.9735721 1.87257e-4 -0.2448543 0.9695599 -1.22076e-4 -0.245041 0.9695127 1.83117e-4 -0.2218137 0.9750891 -1.52596e-4 -0.3667767 0.930309 -3.35708e-4 -0.4368193 0.8995493 -9.15572e-5 -0.4670013 0.8842567 9.15569e-5 -0.4733881 0.880854 -1.52598e-4 -0.515595 0.8568325 9.15582e-5 -0.6441593 0.7648915 -9.15562e-5 -0.6916667 0.7222169 1.22079e-4 -0.02206242 -0.9997566 -2.129e-5 -0.02173328 -0.9997638 1.08682e-4 -0.02093386 -0.9997809 -5.58929e-5 -0.02078694 -0.9997839 -4.50227e-5 -0.02058732 -0.9997881 1.55283e-5 -0.02048343 -0.9997902 7.0123e-5 -0.02038866 -0.9997922 4.66064e-5 -0.0203464 -0.999793 2.67958e-6 -0.02032548 -0.9997935 -1.60013e-5 -0.02034324 -0.9997931 -3.36024e-6 -0.0204454 -0.999791 2.00477e-5 -0.02054727 -0.9997889 1.58803e-5 -0.02094513 -0.9997807 1.83414e-5 -0.0210303 -0.9997789 2.32307e-5 -0.02111518 -0.9997771 1.24227e-5 -0.02121937 -0.9997749 -1.62564e-5 -0.02136731 -0.9997718 -4.98322e-6 -0.02127981 -0.9997736 -4.49654e-5 -0.02151215 -0.9997686 2.68727e-5 -0.02163594 -0.9997659 2.98424e-5 -0.02172142 -0.9997641 1.30879e-5 -0.02168893 -0.9997648 2.61244e-5 -0.02157998 -0.9997671 8.39131e-5 -0.02158421 -0.9997671 8.66239e-5 -0.02143222 -0.9997704 6.48844e-6 -0.02130758 -0.999773 -4.16249e-5 -0.02114295 -0.9997766 -7.80038e-5 -0.02107203 -0.999778 -8.58622e-5 -0.02069211 -0.999786 -8.67916e-5 -0.01964998 -0.999807 7.30698e-5 -0.01935011 -0.9998129 1.62747e-4 -0.01838481 -0.9998311 4.24518e-6 -0.01646614 -0.9998645 -7.1415e-5 -0.01360774 -0.9999074 1.80425e-4 -0.01207947 -0.9999271 -2.61929e-5 -0.01468145 -0.9998922 3.29398e-5 -0.02141696 -0.9997707 7.30249e-5 -0.008541107 -0.9999635 -1.4207e-4 -0.004715144 -0.9999889 7.53228e-5 -0.003557324 -0.9999938 2.36261e-4 0.002490222 -0.9999969 8.88627e-5 7.45541e-5 -1 -6.59696e-5 0.004496216 -0.9999899 -1.11908e-4 0.007857561 -0.9999691 6.97567e-5 0.007087051 -0.999975 -3.09914e-5 0.006164908 -0.9999811 4.97409e-5 0.001750409 -0.9999985 1.30892e-5 0.002646803 -0.9999966 7.32036e-5 0.00748831 -0.9999721 -1.60837e-4 -0.01382523 -0.9999045 -9.1558e-5 -0.007202386 -0.9999741 -6.10373e-5 6.1037e-5 -1 -9.15555e-5 -0.02676492 -0.9996418 0 -0.03399765 -0.999422 -3.05186e-5 -0.0391258 -0.9992343 9.15581e-5 -0.05017352 -0.9987406 3.05192e-5 -0.04455763 -0.9990069 -9.15568e-5 -0.05069476 -0.9987143 1.45154e-4 -0.05044752 -0.9987268 1.22075e-4 -0.03540194 -0.9993732 -2.13633e-4 -0.02116268 -0.9997761 -2.46702e-5 -0.02074915 -0.9997847 -5.67306e-5 -0.02085 -0.9997827 -7.12372e-6 -0.0207448 -0.9997849 -5.36822e-5 -0.0206604 -0.9997866 -1.43514e-5 -0.02036511 -0.9997926 5.92991e-6 -0.02043455 -0.9997913 1.04822e-4 -0.02159959 -0.9997667 1.92767e-4 -0.02254933 -0.9997457 -9.36649e-5 -0.02305692 -0.9997342 -4.41126e-5 -0.02380234 -0.9997167 2.43208e-4 -0.02371019 -0.9997189 1.78675e-4 -0.02462357 -0.9996969 -6.37098e-5 -0.02543193 -0.9996767 -7.18826e-5 -0.02619904 -0.9996567 1.26428e-4 -0.02645432 -0.9996501 3.31455e-5 -0.02764225 -0.9996179 -6.54377e-5 -0.02870827 -0.9995879 1.71915e-4 -0.0292623 -0.9995718 -4.02969e-5 -0.03111523 -0.9995158 -1.33898e-4 -0.0322411 -0.9994801 2.02707e-4 -0.03345602 -0.9994402 -1.01544e-4 -0.03583955 -0.9993576 1.34165e-4 -0.03602647 -0.9993509 5.20337e-5 -0.03982007 -0.9992069 -2.01492e-4 -0.04157418 -0.9991354 4.86829e-4 -0.04444515 -0.9990119 -3.73307e-4 -0.04940855 -0.9987787 1.73828e-4 -0.04939502 -0.9987794 1.67876e-4 -0.05412989 -0.9985339 -1.45194e-4 -0.05585873 -0.9984387 2.6762e-4 -0.05946797 -0.9982302 -2.775e-4 -0.06376934 -0.9979646 3.77611e-4 -0.06517493 -0.9978739 -4.15309e-5 -0.071065 -0.9974717 -2.68892e-4 -0.07453685 -0.9972182 4.1212e-4 -0.07746988 -0.9969947 -1.76871e-4 -0.08523637 -0.9963608 1.52333e-4 -0.08495134 -0.9963852 2.34969e-4 -0.09109526 -0.9958422 -2.39158e-4 -0.09648001 -0.995335 1.18805e-4 -0.09703946 -0.9952805 2.45178e-4 -0.103523 -0.9946271 -2.58343e-4 -0.1093485 -0.9940035 2.07973e-4 -0.1100331 -0.9939279 8.81842e-5 -0.1175019 -0.9930728 -2.05865e-4 -0.1239438 -0.9922893 3.27713e-4 -0.1250214 -0.9921541 1.42965e-4 -0.1356137 -0.9907618 -2.69562e-4 -0.141995 -0.9898673 3.37074e-4 -0.1441735 -0.9895525 9.81121e-5 -0.1511487 -0.988511 -6.14181e-5 -0.1574406 -0.9875284 3.05912e-4 -0.1599627 -0.9871231 -9.92533e-6 -0.1710976 -0.9852541 -1.91193e-4 -0.1772746 -0.9841614 3.69466e-4 -0.1815581 -0.9833802 -6.86484e-5 -0.1924074 -0.9813152 -1.36676e-4 -0.1973051 -0.9803422 3.06772e-4 -0.2054052 -0.978677 -2.40164e-4 -0.2139726 -0.9768397 -3.05196e-5 -0.2107378 -0.9775426 3.05196e-4 -0.228529 -0.9735372 -3.05194e-5 -0.2443663 -0.9696829 3.96748e-4 -0.2429305 -0.9700437 -1.83113e-4 -0.2587376 -0.9659477 1.22075e-4 -0.2915477 -0.9565562 4.88304e-4 -0.2756763 -0.9612506 -3.05188e-5 -0.2950271 -0.9554889 -3.0519e-4 -0.3139471 -0.9494405 6.10376e-5 -0.3391246 -0.9407414 3.96744e-4 -0.3284153 -0.9445335 3.0519e-5 -0.341721 -0.9398014 -1.52595e-4 -0.3537442 -0.9353422 3.05189e-5 -0.3651679 -0.9309418 0 -0.3735839 -0.9275964 2.74672e-4 -0.3774918 -0.9260131 -3.05192e-5 -0.3896091 -0.9209803 -6.10386e-5 -0.3875282 -0.9218578 2.78224e-4 -0.4219262 -0.9066302 3.05191e-4 -0.4074349 -0.9132342 -3.35714e-4 -0.4326646 -0.901555 -1.83113e-4 -0.4625535 -0.8865914 -9.15585e-5 -0.5283766 -0.8490099 6.409e-4 -0.502901 -0.864344 -4.27274e-4 -0.5484872 -0.8361591 -2.44152e-4 -0.6009128 -0.7993147 1.83112e-4 -0.6894965 -0.7242887 8.24026e-4 -0.653286 -0.7571111 -3.05188e-4 -0.7061753 -0.7080369 -4.57782e-4 -0.7580014 -0.6522529 3.66228e-4 -0.7993953 -0.6008055 1.52597e-4 -0.823435 -0.5674105 5.49343e-4 -0.8398542 -0.5428121 0 -0.8679932 -0.496576 2.74672e-4 -0.9113037 -0.4117347 5.18827e-4 -0.8963659 -0.4433152 -3.05187e-5 -0.9151831 -0.4030383 -6.10387e-5 -0.9493587 -0.3141945 3.96749e-4 -0.9360882 -0.3517655 3.05193e-4 -0.9636604 -0.2671307 -6.10375e-5 -0.9796915 -0.20051 5.79862e-4 -0.9723934 -0.2333475 -2.7467e-4 -0.9824551 -0.1864992 -3.05186e-4 -0.9863518 -0.1646513 -2.44154e-4 -0.9922097 -0.1245794 0 -0.9985165 -0.05444562 7.32453e-4 -0.9948133 -0.1017183 1.83111e-4 -0.9984374 0.05588072 3.35712e-4 -0.998233 -0.05941969 3.66223e-4 -0.9994364 -0.03357088 1.22076e-4 -0.9994116 -0.03430354 1.52596e-4 -0.9975419 -0.07007145 3.35708e-4 -0.9923506 0.1234487 -8.85046e-4 -0.9930404 0.1177744 -3.66233e-4 -0.9929644 0.1184135 2.74671e-4 -0.9583038 0.2857515 9.15577e-5 -0.9687297 0.2481184 -2.7467e-4 -0.8787317 0.4773162 -2.7467e-4 -0.8892038 0.4575114 1.52595e-4 -0.8120515 0.5835857 3.05191e-4 -0.7888376 0.6146018 -2.13637e-4 -0.7704879 0.6374547 2.74673e-4 -0.7576343 0.6526795 -6.1038e-5 2.57846e-7 0 1 0 0 1 -1.55802e-7 0 1 6.19398e-7 0 1 0 0 1 0 0 1 4.59034e-6 0 1 -1.71813e-6 0 1 -2.64382e-5 0 1 1.7597e-5 0 1 -1.06273e-6 0 1 7.44384e-7 0 1 4.11549e-6 0 1 -8.3918e-6 0 1 -5.4362e-6 0 1 -3.96234e-6 0 1 0 0 1 1.88727e-5 0 1 5.40928e-7 0 1 -7.62363e-7 0 1 1.15911e-6 0 1 -5.94743e-7 0 1 -3.67649e-7 0 1 -5.04073e-7 0 1 1.79376e-6 0 1 -2.59657e-6 0 1 4.34159e-7 0 1 0 0 1 -1.89094e-6 0 1 -2.53235e-7 0 1 -3.94677e-6 0 1 1.19486e-6 0 1 1.66223e-6 0 1 -4.23129e-7 0 1 7.25268e-7 0 1 -6.90878e-7 0 1 5.92834e-7 0 1 -2.06008e-7 0 1 9.77838e-7 0 1 6.76576e-6 0 1 -2.51217e-7 0 1 -2.83525e-7 0 1 -1.31214e-6 0 1 1.40923e-6 0 1 -1.84464e-7 0 1 3.23544e-7 0 1 5.33921e-7 0 1 -9.95218e-7 0 1 1.1495e-6 0 1 8.67173e-7 0 1 2.22491e-6 0 1 3.30873e-7 0 1 -1.06015e-6 0 1 -3.31107e-6 0 1 1.73856e-6 0 1 -3.64768e-7 0 1 -1.26378e-6 0 1 6.59106e-6 0 1 -8.36388e-7 0 1 -3.01338e-7 0 1 -1.75252e-7 0 1 -7.81563e-7 0 1 -2.29264e-7 0 1 0 0 1 -2.7824e-7 0 1 -6.53757e-7 0 1 2.29476e-7 0 1 5.68826e-7 0 1 2.04579e-7 0 1 2.31442e-6 0 1 0 0 1 2.1812e-7 0 1 -1.25265e-6 0 1 -3.28743e-7 0 1 -2.2141e-7 0 1 -4.42631e-6 0 1 6.42971e-6 0 1 -2.36389e-6 0 1 7.381e-7 0 1 1.96513e-6 0 1 2.95516e-6 0 1 2.49553e-6 0 1 -4.37761e-7 0 1 6.80492e-7 0 1 -5.66183e-7 0 1 -1.18019e-6 0 1 -1.23203e-7 0 1 -2.31229e-7 0 1 -3.72268e-7 0 1 2.80511e-7 0 1 0 0 1 1.45986e-7 0 1 0 0 1 6.34893e-7 0 1 -1.81185e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.75907e-7 0 1 0 0 1 3.05894e-7 0 1 0 0 1 -1.98173e-7 0 1 1.41535e-7 0 1 3.02685e-7 0 1 0 0 1 0 0 1 -1.68427e-7 0 1 -7.30853e-7 0 1 2.01817e-7 0 1 0 0 1 1.37678e-7 0 1 -1.00483e-6 0 1 8.2942e-7 0 1 -2.74045e-7 0 1 3.722e-7 0 1 0 0 1 2.35534e-7 0 1 4.04035e-7 0 1 -1.20024e-7 0 1 -8.7708e-7 0 1 7.80167e-7 0 1 -1.44204e-6 0 1 3.27453e-6 0 1 -1.04091e-6 0 1 -1.83631e-6 0 1 1.21351e-6 0 1 7.92724e-7 0 1 -1.27699e-7 0 1 2.28974e-6 0 1 -2.16327e-6 0 1 -2.76466e-7 0 1 0 0 1 7.17401e-7 0 1 -2.92288e-7 0 1 -2.7518e-7 0 1 1.08308e-6 0 1 -6.25063e-7 0 1 6.19683e-7 0 1 0 0 1 -1.39613e-7 0 1 -4.81093e-6 0 1 -2.59651e-7 0 1 2.0743e-7 0 1 1.26928e-7 0 1 1.23961e-6 0 1 -1.37409e-7 0 1 5.99972e-7 0 1 -1.59653e-7 0 1 1.29721e-7 0 1 0 0 1 0 0 1 1.77285e-6 0 1 0 0 1 0 0 1 -9.73317e-6 0 1 1.5975e-5 0 1 9.14539e-6 0 1 -2.09192e-5 0 1 2.51671e-7 0 1 -1.2913e-6 0 1 -2.27903e-6 0 1 1.96174e-7 0 1 0 0 1 -1.9169e-7 0 1 0 0 1 0 0 1 -4.32195e-7 0 1 1.78462e-7 0 1 3.75017e-7 0 1 -4.02475e-7 0 1 5.89406e-7 0 1 -1.83141e-6 0 1 0 0 1 -1 0 0 -1 -2.07001e-6 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.01023083 0.9999477 1.66903e-6 0.01025104 0.9999475 0 -1 -3.94834e-4 0 -1.74027e-6 0 1 -0.5992226 0.8005825 -2.41694e-5 -0.5992057 0.8005951 0 -0.5991904 0.8006067 -9.43158e-7 -0.5991678 0.8006235 -3.1813e-5 -0.599277 0.8005419 1.8036e-4 -0.5991894 0.8006075 -3.13396e-5 -0.5990734 0.8006941 4.26318e-4 -0.5994384 0.8004205 -8.42169e-4 -0.5990456 0.8007149 5.08395e-4 -0.5990605 0.8007037 4.13305e-4 -0.5990623 0.8007023 4.34746e-4 -0.5995156 0.8003626 -9.49032e-4 -0.5991 0.8006743 2.38336e-4 -0.5989785 0.800765 5.43402e-4 -0.599276 0.8005425 -2.03657e-4 -0.5993671 0.8004742 -3.7165e-4 -0.5989725 0.8007695 4.92011e-4 -0.5996062 0.800295 -7.33121e-4 -0.59917 0.8006218 1.35033e-5 -0.5990934 0.8006792 1.17703e-4 -0.5991176 0.800661 8.90525e-5 -0.599337 0.8004969 -2.33939e-4 -0.5994673 0.8003992 -3.50009e-4 -0.5987444 0.80094 5.98434e-4 -0.5987874 0.8009081 4.32314e-4 -0.5994692 0.8003978 -3.46675e-4 -0.5986238 0.8010301 5.44637e-4 -0.5997608 0.8001793 -5.86126e-4 -0.5984197 0.8011826 6.5625e-4 -0.5998013 0.8001489 -6.07377e-4 -0.5999205 0.8000595 -4.9735e-4 -0.5991327 0.8006497 5.20234e-5 -0.5995945 0.800304 -2.21219e-4 -0.5988328 0.8008741 1.77881e-4 -0.5993836 0.800462 -8.74683e-5 -0.5990115 0.8007405 4.23328e-5 -0.5992588 0.8005554 4.87469e-6 -0.5986528 0.8010087 9.3631e-5 -0.5997537 0.8001848 6.01506e-5 -0.5990298 0.8007268 1.37251e-5 -0.5993548 0.8004837 7.11185e-5 -0.5987613 0.8009275 -1.29154e-4 -0.5990671 0.8006988 -9.40775e-5 -0.599227 0.8005792 4.50533e-6 -0.5990799 0.8006893 -1.1069e-4 -0.5992316 0.8005758 4.22158e-5 -0.5993269 0.8005045 1.42696e-4 -0.599487 0.8003844 3.97379e-4 -0.5991656 0.8006252 -1.8779e-4 -0.5991709 0.8006212 -1.23386e-4 -0.5990899 0.8006817 -4.91003e-4 -0.5992286 0.8005781 3.47576e-5 -0.5992702 0.8005468 3.17045e-4 -0.5992299 0.8005771 2.02193e-4 -0.5991636 0.8006266 -3.91138e-4 -0.599152 0.8006351 -4.96409e-4 -0.5992177 0.8005861 -1.19636e-4 -0.5992309 0.8005757 0.001056313 -0.5992399 0.8005694 -5.46191e-4 -0.5992379 0.8005708 -5.8479e-4 -0.5992704 0.8005466 -4.05044e-4 -0.5990834 0.8006862 8.9978e-4 -0.5991803 0.8006142 6.69058e-5 -0.5991973 0.8006015 -5.31129e-5 -0.5991724 0.8006201 1.02815e-4 -0.599147 0.8006391 2.58429e-4 -0.5993587 0.8004804 -5.62485e-4 -0.5993 0.8005247 -2.74653e-4 -0.5991046 0.8006708 2.9099e-4 -0.599049 0.8007123 3.98316e-4 -0.599355 0.8004834 -4.28883e-4 -0.5987369 0.8009452 9.92549e-4 -0.599339 0.8004953 -3.20878e-4 -0.5992115 0.8005908 -2.03032e-6 -0.5989364 0.8007966 -7.40249e-7 0 -0.9999997 -8.7604e-4 0 -1 4.41501e-4 5.95214e-5 -1 0 0 -1 -2.14846e-4 0 -1 1.60321e-4 0 -1 -2.55395e-4 0 -1 -1.37893e-4 0 -1 3.18945e-4 7.41385e-5 -1 3.3484e-4 -0.1622232 -3.80147e-4 0.986754 -0.1698886 4.81922e-4 0.9854632 -0.1360229 0 0.9907058 -0.1355654 9.1557e-5 0.9907685 -0.1428269 1.22074e-4 0.9897477 -0.1466548 3.81352e-4 0.9891877 -0.1323316 -6.10386e-5 0.9912055 -0.1323916 0 0.9911975 -0.1435915 -1.52595e-4 0.9896371 -0.147314 -3.80778e-4 0.9890898 -0.1547597 -3.81538e-4 0.9879521 -0.1541026 3.80693e-4 0.9880548 -0.1615662 3.81716e-4 0.9868619 -0.1704222 -3.37408e-4 0.9853711 0 -1 0 0 -1 4.19553e-7 0 -1 -2.3644e-7 0 -1 -1.22784e-5 0 -1 3.97043e-6 0 -1 1.15548e-5 0 -1 -1.36085e-5 0 -1 3.16643e-6 0 -1 5.13784e-5 0 -1 2.33492e-5 0 -1 -4.69484e-5 0 -1 2.37905e-5 0 -1 -6.42013e-5 0 -1 -4.1632e-5 0 -1 1.39931e-5 0 -1 1.32991e-5 0 -1 1.88182e-5 0 -1 -1.73106e-5 0 -1 4.18525e-6 0 -1 1.16303e-5 0 -1 -9.91831e-6 0 -1 6.17479e-7 0 -1 -3.74205e-6 0 -1 1.60133e-5 0 -1 -1.32506e-5 0 -1 1.09818e-6 0 -1 3.66693e-6 0 -1 -3.30782e-7 0 -1 0 0 -1 0 0 -1 0 -0.6341573 0.001556456 0.7732025 -0.6860954 0.001709043 0.7275096 -0.6450195 -7.32457e-4 0.7641658 -0.7055482 -0.001007139 0.7086613 -0.7293293 0.001892209 0.6841602 -0.7572384 -0.00100708 0.6531379 -0.7686459 0.001098632 0.6396735 -0.8071137 3.96751e-4 0.5903961 -0.8028401 -7.01943e-4 0.5961941 -0.8249021 -2.44153e-4 0.5652757 -0.8250123 -2.74668e-4 0.5651149 -0.5885273 -3.66227e-4 0.8084773 -0.5772611 0.001586914 0.8165581 -0.5332349 -3.96752e-4 0.8459672 -0.5218234 0.001586973 0.8530521 -0.4806728 -2.13632e-4 0.8769 -0.469233 0.001281797 0.8830736 -0.4372488 -6.10384e-4 0.8993403 -0.4243634 7.93488e-4 0.9054917 -0.3812777 5.18828e-4 0.9244604 -0.3954067 -9.46095e-4 0.9185057 -0.3709642 -0.001220762 0.9286464 -0.3603142 2.74676e-4 0.9328311 -0.9144127 -0.07196396 0.398335 -0.9111399 -0.03784334 0.4103563 -0.9102937 -0.05380517 0.4104516 -0.9155781 -0.06161838 0.3973914 -0.9204764 -0.1038248 0.3767541 -0.9210895 -0.09079355 0.3786169 -0.9279501 -0.1611995 0.3360409 -0.9301007 -0.1466749 0.336748 -0.9279446 -0.1735947 0.329824 -0.9178219 -0.1474972 0.3685753 -0.9189839 -0.131933 0.3715671 -0.9136287 -0.09851658 0.3944327 -0.9106301 -0.1453931 0.3867996 -0.9152938 -0.1647107 0.3675702 -0.9120444 -0.1145702 0.3937624 -0.9090556 -0.06625795 0.4113731 -0.9084739 -0.08307403 0.4096022 -0.929748 -0.1387419 0.3410561 -0.9267602 -0.1157572 0.3573735 -0.914754 -0.04803729 0.4011453 -0.922175 -0.07028621 0.3803331 -0.915299 -0.0322892 0.401479 -0.9202818 -0.07718354 0.3835678 -0.9149999 -0.08722418 0.3939129 -0.9261987 -0.1021479 0.3629351 -0.9274525 -0.0886892 0.3632718 -0.9135173 -0.2427155 0.3264589 -0.9165102 -0.2149439 0.3373548 -0.9153276 -0.2206223 0.3368998 -0.9078003 0.02777266 0.4184823 -0.9044606 0.06289958 0.4218944 -0.9073539 0.0444048 0.4180157 -0.9102613 -0.02325546 0.4133806 -0.9083127 -0.01113951 0.4181436 -0.9221726 -0.05676597 0.3825905 -0.9264183 -0.07965576 0.3679732 -0.9073446 0.02050906 0.4198872 -0.9077981 -0.04022449 0.4174742 -0.9078889 -0.017457 0.4188472 -0.9053419 0.06207531 0.4201226 -0.9082559 0.0418725 0.4163145 -0.9066596 0.004944026 0.4218341 -0.9086797 -0.01867777 0.4170759 -0.9090401 -0.101842 0.4040721 -0.9086351 -0.05938947 0.4133461 -0.9101513 -0.1269609 0.394342 -0.9212578 -0.02774208 0.3879622 -0.9212124 -0.03988814 0.3870099 -0.9181281 -0.015473 0.3959817 -0.9166136 -0.01919656 0.3993132 -0.9077048 0.02023428 0.4191214 -0.90871 0.02877962 0.4164348 -0.9145003 -0.01559513 0.4042845 -0.9078422 -0.003479123 0.4192975 -0.9078617 0.01318436 0.4190624 -0.9088063 0.01391679 0.4169864 -0.9078584 0.005279839 0.4192439 -0.9243736 -0.1479889 0.3516148 -0.924664 -0.1305297 0.3577129 -0.9107158 -0.3123003 0.2703063 -0.9093782 -0.3099521 0.2774187 -0.9056676 -0.3441994 0.2475745 -0.9265867 -0.2291975 0.2981704 -0.9261213 -0.2423186 0.2891039 -0.9256089 -0.2318218 0.2991771 -0.9301729 -0.2021611 0.3064462 -0.9270517 -0.2180903 0.3049785 -0.9226081 -0.1582137 0.3517996 -0.9191247 -0.1992006 0.3398954 -0.9206941 -0.1847919 0.3437649 -0.9198467 -0.1174376 0.3742867 -0.9136238 -0.1927595 0.3579601 -0.9235397 -0.206584 0.3231061 -0.9256278 -0.1881836 0.3283295 -0.9228318 -0.2750673 0.2696654 -0.9276608 -0.2559338 0.2719258 -0.9223794 -0.284072 0.2617625 -0.9207102 -0.289019 0.2622229 -0.9211043 -0.2983266 0.2501365 -0.9195072 -0.2353015 0.3148646 -0.9144957 -0.2634382 0.3070801 -0.9235038 -0.2436023 0.2963086 -0.9211521 -0.2605704 0.2891055 -0.9218924 -0.2248346 0.3155376 -0.9125915 -0.2731487 0.304248 -0.9221958 -0.1711511 0.3467886 -0.9147681 -0.3391659 0.2194674 -0.9128757 -0.3539679 0.2033835 -0.9122852 -0.346639 0.218122 -0.9065393 -0.3499014 0.2361263 -0.9152193 -0.3323881 0.2277976 -0.9223768 -0.3090662 0.231731 -0.8930169 -0.4112743 0.1826868 -0.8841331 -0.4439282 0.1457278 -0.8845353 -0.4430153 0.1460644 -0.8971084 -0.3970533 0.1937656 -0.9002785 -0.3770616 0.2175391 -0.8964376 -0.4109702 0.1658408 -0.909756 -0.3538432 0.2171158 -0.9067771 -0.3659214 0.2094206 -0.8742246 -0.4719805 0.1138674 -0.8703317 -0.4822731 0.09967744 -0.902646 -0.3918404 0.1780205 -0.9139001 -0.3615009 0.1846722 -0.9027665 -0.395258 0.1696578 -0.9005553 -0.4092296 0.1467354 -0.8986869 -0.4063272 0.1651067 -0.8519791 -0.5224003 0.03506672 -0.850059 -0.5252707 0.03860712 -0.8298316 -0.5501285 0.0934785 -0.8575807 -0.5079563 0.08084452 -0.8311643 -0.5556965 0.01916611 -0.9076095 -0.4005335 0.1257694 -0.8842668 -0.4537918 0.1102052 -0.882705 -0.4550403 0.1173461 -0.9015236 -0.4131016 0.1288501 -0.877547 -0.4690485 0.09952288 -0.883645 -0.4617208 0.07736545 -0.8561919 -0.5148321 0.04339861 -0.882317 -0.4663676 0.06338888 -0.8968909 -0.4386488 0.05633795 -0.8513945 -0.5242895 0.0157479 -0.8596971 -0.5108009 0.001831114 -0.8540133 -0.518701 0.04013246 -0.8278329 -0.5608511 0.01178038 -0.9134131 -0.1715186 0.3691313 -0.9134565 -0.004944026 0.4069064 -0.9082076 0.003692746 0.4185037 -0.9073265 1.4786e-4 0.4204267 -0.9215198 -0.05414062 0.3845388 -0.9233077 -0.06753975 0.378076 -0.9302766 -0.1950461 0.3107128 -0.9271363 -0.1282408 0.3520975 -0.9184535 -0.298389 0.2596293 -0.9279294 -0.1861962 0.3229212 -0.92591 -0.1159409 0.3595115 -0.9155834 -0.3132516 0.2521517 -0.9180424 -0.2492182 0.3083641 -0.9284886 -0.2492206 0.2753146 -0.9271036 -0.1747818 0.3315575 -0.9144465 -0.2992407 0.2724753 -0.9175588 -0.2797997 0.2824854 -0.923907 -0.302445 0.2343567 -0.9118306 -0.3308007 0.2431792 -0.8742972 -0.4741231 0.1039805 -0.91692 -0.3535959 0.1850076 -0.902754 -0.3803896 0.200846 -0.8900792 -0.4301617 0.1507321 -0.8926562 -0.4212871 0.1602563 -0.8502767 -0.5244492 0.04452812 0 0 1 0 0 1 0 0 1 -0.8258812 -0.5634462 0.02118033 -0.8377408 -0.5453708 0.02758896 -0.7510235 -0.6581832 0.05252403 -0.6031717 -0.7974842 0.01425218 -0.6113976 -0.7913101 -0.00463891 -0.7147793 -0.6993368 -0.004333615 -0.7272883 -0.68502 0.0424208 -0.6557076 -0.75105 0.07727491 -0.8666591 -0.4989004 8.54543e-4 -0.8637456 -0.503928 -2.44151e-4 -0.821639 -0.5700078 -8.85058e-4 -0.4666127 -0.8843333 0.01507663 -0.4698718 -0.8827339 -0.001220762 -0.3996209 -0.9166804 -4.8831e-4 -0.3809075 -0.9245729 -0.008636832 -0.416926 -0.9089298 -0.004425287 -0.472681 -0.8776704 0.07916671 -0.3825905 -0.922966 0.04193353 -0.6108793 -0.789327 0.06155788 -0.5620971 -0.8211721 0.09860652 -0.4582204 -0.8789324 0.1323328 -0.4079127 -0.9088159 0.08752757 -0.4000777 -0.9094144 0.1135929 -0.3814 -0.9136265 0.1407856 -0.399096 -0.9018037 0.1657482 -0.3391312 -0.9277582 0.1557403 -0.3713266 -0.9129503 0.1692287 -0.8642202 -0.5031138 1.83117e-4 -0.8647656 -0.5021653 0.003235042 -0.8227546 -0.5683809 0.00427258 -0.8652939 -0.5012375 0.005249142 -0.8640474 -0.5033461 0.008056938 -0.8638774 -0.5035979 0.01025444 -0.8698562 -0.4930061 0.01718223 -0.8646275 -0.5022475 0.01290941 -0.8716753 -0.4897642 0.01770085 -0.9743492 -0.2193704 -0.05020368 -0.8644545 -0.5027112 1.22077e-4 -0.8625086 -0.5060421 -6.10388e-4 -0.7900604 -0.6130164 -0.003937005 -0.8577811 -0.5139789 -0.00613439 -0.8786656 -0.4773134 -0.01089519 -0.3872872 -0.9215544 0.02731454 -0.7221988 -0.6916189 0.009613394 -0.4001326 -0.9142836 0.06308245 -0.3971428 -0.9177347 0.006378412 -0.5171139 -0.8559052 -0.004425227 -0.6906272 -0.7040252 0.165477 -0.6075121 -0.7731389 0.1821681 -0.6515862 -0.7448835 0.143471 -0.5133908 -0.8352442 0.1969696 -0.5567352 -0.7935658 0.2455592 -0.4713143 -0.8472853 0.2448893 -0.5367403 -0.8274962 0.1648034 -0.4261057 -0.8802889 0.2086276 -0.4271181 -0.8853964 0.1834212 -0.381947 -0.9036106 0.1939185 -0.3862781 -0.8979585 0.2108553 -0.3802128 -0.9055461 0.1882141 -0.7489401 -0.6537509 0.1081598 -0.7139402 -0.6587305 0.2374103 -0.666909 -0.6820772 0.3000053 -0.6389195 -0.7300499 0.2425056 -0.6059275 -0.7295912 0.3170941 -0.648745 -0.669498 0.3618042 -0.570676 -0.7293141 0.3773987 -0.6956556 -0.5891435 0.4110636 -0.6221055 -0.6496645 0.4369449 -0.5534372 -0.6764911 0.4858675 -0.566901 -0.6210122 0.5412645 -0.5044468 -0.678496 0.5340195 -0.6564646 -0.5651516 0.4996578 -0.5996133 -0.6324216 0.490415 -0.3943088 -0.596682 0.6989215 -0.4281922 -0.62242 0.6551677 -0.4381072 -0.5535929 0.7082352 -0.5014111 -0.5928792 0.630144 -0.5308812 -0.5240449 0.6659896 -0.4712116 -0.578577 0.6657389 -0.3434342 -0.600865 0.7218132 -0.3113875 -0.5375348 0.7836417 -0.303667 -0.5845054 0.7524226 -0.3558523 -0.5340531 0.7669137 -0.3744738 -0.4565406 0.8070566 -0.3277175 -0.4871509 0.8094969 -0.1717007 -0.6321738 0.7555628 -0.2245603 -0.6887574 0.6893373 -0.2111341 -0.6304117 0.7469963 -0.2253251 -0.3406887 0.9127759 -0.2098501 -0.3918668 0.8957697 -0.2652714 -0.4105114 0.872417 -0.08517879 -0.06982767 0.9939159 -0.05865669 -0.08490264 0.9946613 -0.1278447 -0.1194214 0.9845783 -0.2468034 -0.6346939 0.7322922 -0.2548677 -0.5825852 0.7717751 -0.2210793 -0.5765337 0.7865957 -0.1827478 -0.570858 0.8004525 -0.1428915 -0.5679955 0.8105327 -0.1001945 -0.6364164 0.7648106 -0.1728012 -0.6959964 0.6969426 -0.1416388 -0.6368709 0.7578483 -0.07834315 -0.8011631 0.593296 -0.1316607 -0.7771463 0.6153934 -0.06103843 -0.7223594 0.6888188 0.01394718 -0.6590605 0.7519607 -0.02951204 -0.732308 0.6803337 -0.1858635 -0.9026743 0.388116 -0.2301464 -0.9040444 0.3601894 -0.2085983 -0.8834986 0.4194245 0.01315385 -0.7501986 0.6610817 -0.02688711 -0.8266344 0.5620968 -0.2010886 -0.9382709 0.2814446 -0.1998986 -0.9364104 0.2884033 -0.149848 -0.9366265 0.3166646 -0.163705 -0.921558 0.352039 -0.07687723 -0.9269218 0.3672956 -0.06457853 -0.9090131 0.4117339 -0.1317223 -0.9452822 0.2984812 -0.1692868 -0.9470844 0.2727144 -0.1461274 -0.9645384 0.2198014 -0.1566259 -0.9571516 0.2435759 -0.1704199 -0.9584904 0.2285898 -0.168038 -0.9600692 0.2236743 -0.1908345 -0.942331 0.2749445 -0.2110995 -0.9236559 0.3198386 -0.2010298 -0.9304994 0.306199 -0.05951285 -0.566532 0.821888 -0.06799608 -0.6450477 0.7611111 -0.2019746 -0.5117424 0.8350605 -0.1565638 -0.5043309 0.8491986 -0.2548967 -0.5252056 0.8119033 -0.2784008 -0.474429 0.835111 0.008545398 -0.05398887 0.998505 -0.01818919 -0.1341606 0.9907928 -0.1650776 -0.3188939 0.9333039 -0.2032597 -0.2702195 0.9410988 -0.1375496 -0.2439697 0.9599786 -0.1537883 -0.1932196 0.9690281 -0.2228468 -0.2220838 0.9492198 -0.1819576 -0.1461581 0.9723834 -0.3201787 -0.4303841 0.8439521 -0.2010881 -0.1194199 0.9722667 -0.24965 -0.1729848 0.9527598 -0.3995903 -0.5177003 0.7565144 -0.4287338 -0.4779613 0.7666424 -0.4835785 -0.5035077 0.7159831 -0.4721609 -0.2800127 0.8358571 -0.4035847 -0.3360459 0.850995 -0.4693212 -0.3606125 0.8060374 -0.4407995 -0.657827 0.6107041 -0.4638555 -0.436297 0.7710274 -0.4959376 -0.6445358 0.5819103 -0.5220997 -0.4622507 0.716754 -0.6084905 -0.5560281 0.566191 -0.5620755 -0.56058 0.6081292 -0.6679251 -0.498754 0.5523772 -0.6211631 -0.4875793 0.6135332 -0.5390663 -0.7173919 0.4413123 -0.7095478 -0.6268095 0.3219502 -0.7682681 -0.596199 0.2330471 -0.7622154 -0.5630475 0.3193827 -0.7686467 -0.6233771 0.1434689 -0.8347595 -0.5458958 0.07193356 -0.8265014 -0.548712 0.1257408 -0.8784002 -0.4716724 0.07706063 -0.3774605 -0.897018 0.2299615 -0.374835 -0.8960087 0.2380486 -0.4017248 -0.8789846 0.256911 -0.3831977 -0.8867931 0.2583746 -0.8592682 -0.4755808 0.1883645 -0.887232 -0.4591962 0.04425323 -0.8909734 -0.4507055 0.05505633 -0.8937195 -0.4419156 0.07730472 -0.812033 -0.5383339 0.2253867 -0.8784078 -0.4582175 0.1357805 -0.3698035 -0.8877786 0.2740336 -0.8685702 -0.4604704 0.1831749 -0.3291816 -0.9003205 0.2847149 -0.3898501 -0.8675951 0.3087 -0.4631339 -0.8339462 0.300068 -0.54327 -0.779213 0.3125458 -0.8154285 -0.4810229 0.3220146 -0.8656556 -0.4452492 0.2288963 -0.8586294 -0.4405763 0.262008 -0.07132184 -0.9789746 0.1911072 -0.3681558 -0.8610751 0.3507292 -0.3874117 -0.8393411 0.3813383 -0.3710576 -0.8512535 0.3710576 -0.4135989 -0.8432511 0.3433127 -0.4822958 -0.7791566 0.4003821 -0.8370169 -0.4440529 0.3197181 -0.3853366 -0.8639707 0.3241454 -0.496092 -0.7939302 0.3515218 -0.8237243 -0.4316998 0.3675782 -0.7765628 -0.4612987 0.4291314 -0.7603281 -0.5227351 0.3855507 -0.3753856 -0.8616474 0.3415399 -0.7199792 -0.5099458 0.4707286 -0.8063215 -0.4261723 0.4101497 -0.3645516 -0.8645777 0.3458433 -0.3287569 -0.8713949 0.3641291 -0.350541 -0.8581326 0.3751393 -0.4813515 -0.7311831 0.4833963 -0.4792387 -0.7588837 0.4409375 -0.7844674 -0.4103927 0.4649611 -0.7309346 -0.436577 0.5245333 -0.4395018 -0.8014553 0.4055954 -0.768904 -0.4002 0.4986248 -0.3636971 -0.8517904 0.3770645 -0.7432345 -0.3980316 0.5377486 -0.6697668 -0.4080371 0.6204178 -0.7210495 -0.3761201 0.5819119 -0.374682 -0.8255394 0.4220169 -0.4219859 -0.7902891 0.4442648 -0.7037385 -0.369555 0.6067795 -0.1716682 -0.9742209 0.1463681 -0.3482872 -0.8324773 0.4309032 -0.3530493 -0.8317778 0.4283713 -0.3612884 -0.8181024 0.4474141 -0.451134 -0.7114928 0.5387544 -0.5737995 -0.4927394 0.6541882 -0.5944243 -0.424676 0.6828692 -0.6155634 -0.3512099 0.7055022 -0.6657643 -0.3484314 0.6598132 -0.3563402 -0.8463538 0.3958624 -0.4035814 -0.7832055 0.4729813 -0.413595 -0.7175654 0.560392 -0.6612566 -0.319382 0.6787746 -0.6383799 -0.331352 0.6947497 -0.3561891 -0.8331426 0.4230871 -0.3434352 -0.833669 0.432491 -0.3391928 -0.8396807 0.4241283 -0.534691 -0.3915879 0.7488421 -0.5456284 -0.3159078 0.7762036 -0.5905746 -0.3086089 0.7456421 -0.3875969 -0.7725082 0.502991 -0.5701265 -0.2924641 0.7677373 -0.343094 -0.8362497 0.4277535 -0.3376322 -0.8266085 0.4502475 -0.3403788 -0.8148583 0.4691997 -0.3345496 -0.8274624 0.4509797 -0.5108934 -0.2689667 0.8164833 -0.361158 -0.7772497 0.5152163 -0.4036808 -0.679241 0.6129221 -0.3703858 -0.7393983 0.562232 -0.3625684 -0.6746275 0.642979 -0.4926998 -0.2527589 0.8326823 -0.3406868 -0.8278662 0.4456121 -0.3282032 -0.8318306 0.4475942 -0.3279317 -0.8334562 0.4447602 -0.404749 -0.4116159 0.8165481 -0.4004492 -0.2472708 0.8823252 -0.4335296 -0.2329553 0.8705079 -0.326983 -0.7358797 0.5929276 -0.3256714 -0.6924828 0.6437435 -0.3351572 -0.6447397 0.6870083 -0.3237459 -0.2096657 0.9226208 -0.3518865 -0.195384 0.9154239 -0.3569478 -0.2822988 0.8904469 -0.4168317 -0.2129632 0.8836844 -0.330587 -0.8305876 0.448148 -0.3188607 -0.8297154 0.4581487 -0.3226192 -0.8286287 0.4574838 -0.3196554 -0.8156799 0.4821688 -0.3456953 -0.3881481 0.8543043 -0.336657 -0.3243883 0.8839879 -0.3294909 -0.7749262 0.539375 -0.2962506 -0.635686 0.7128388 -0.2817847 -0.1623626 0.9456405 -0.2938687 -0.2517217 0.922105 -0.325087 -0.8290452 0.4549754 -0.312177 -0.8362765 0.4507629 -0.3134004 -0.8347272 0.452781 -0.2853863 -0.3638821 0.8866479 -0.2689371 -0.2976558 0.9160097 -0.297231 -0.7785872 0.5526806 -0.2858721 -0.7363944 0.6131889 -0.2733304 -0.6878428 0.6724306 -0.255021 -0.1420072 0.9564509 -0.3155662 -0.8321304 0.456045 -0.3058398 -0.8351463 0.4571574 -0.3099529 -0.8356155 0.4535152 -0.2982326 -0.8215438 0.4859251 -0.151129 -0.09762954 0.9836812 -0.0862168 -0.1630642 0.9828411 -0.2275186 -0.4608359 0.8578261 -0.2969514 -0.8421761 0.450066 -0.3011925 -0.837107 0.4566565 -0.1542731 -0.3744671 0.9143162 -0.2675603 -0.7862312 0.5570027 -0.2467204 -0.7418096 0.6235765 -0.1795722 -0.4460008 0.8768337 -0.01837247 -0.03647035 0.9991659 -0.2772678 -0.8323833 0.4798549 -0.2904829 -0.8456599 0.4477489 -0.294813 -0.8454052 0.4453935 -0.1049254 -0.2979906 0.9487847 -0.07226884 -0.218363 0.9731881 -0.1290636 -0.4341591 0.8915429 -0.09845548 -0.3581449 0.9284604 -0.2804353 -0.8528726 0.4404138 -0.2843784 -0.8480386 0.4471682 -0.1107248 -0.4978039 0.8601927 -0.006744563 -0.1942508 0.9809287 -0.04449677 -0.2779983 0.9595504 0.03415119 -0.01901358 0.9992359 -0.2779366 -0.8580418 0.4318744 -0.2548066 -0.8472494 0.4660924 -0.07785457 -0.423302 0.9026374 -0.0418111 -0.3427598 0.9384922 0.05166923 -0.04831212 0.9974951 0.03402823 -0.1113623 0.9931972 -0.273783 -0.8589178 0.4327854 -0.2366819 -0.7976992 0.554669 -0.2159811 -0.7481672 0.6273739 0.01538163 -0.2552322 0.9667574 0.03653186 -0.1746634 0.9839503 0.06500589 -0.1155458 0.9911728 -0.2617346 -0.87194 0.4137824 -0.2670141 -0.8620505 0.4307811 -0.1019334 -0.5665546 0.8176953 -0.02548336 -0.4136548 0.9100772 -0.06399881 -0.4924277 0.8679972 0.07623744 -0.1914176 0.9785435 0.01590061 -0.3287857 0.9442708 0.06729507 -0.245589 0.9670354 -0.1790578 -0.7599048 0.6248865 -0.1128579 -0.7077885 0.6973512 -0.01565623 -0.488457 0.8724476 0.02716177 -0.4018729 0.9152926 0.05621671 -0.3185006 0.9462543 0.08429288 -0.2544047 0.9634174 -0.2018238 -0.8155663 0.5423274 0.03363215 -0.4822037 0.8754134 -0.01538169 -0.5683902 0.8226154 0.09155708 -0.3427594 0.934951 -0.2317004 -0.8647872 0.4454863 0.06936931 -0.3988813 0.9143751 -0.2600526 -0.8746449 0.4091076 -0.2428396 -0.8903307 0.3851497 -0.2448857 -0.8846588 0.396749 0.03241127 -0.5670146 0.8230699 -0.02646064 -0.6499501 0.7595162 0.09491556 -0.423641 0.9008437 -0.249344 -0.8785638 0.4073738 0.05902481 -0.4825143 0.8738971 -0.2324323 -0.8966771 0.3767564 -0.2373799 -0.893242 0.3817978 -0.1647406 -0.838047 0.5201324 0.09427243 -0.4966319 0.8628265 0.1201847 -0.5669252 0.814955 0.08588135 -0.586093 0.8056795 -0.2345998 -0.9058356 0.352739 -0.2258116 -0.907733 0.3535956 0.05520981 -0.6775029 0.7334452 0.09146445 -0.6361312 0.7661406 -0.2113745 -0.9189877 0.33284 -0.2141562 -0.9142152 0.3440172 -0.1248565 -0.8636192 0.4884391 0.0675683 -0.7084298 0.7025396 -0.2190961 -0.9103826 0.3509993 0.00952208 -0.7519412 0.6591616 0.06433558 -0.7661368 0.6394494 -0.08798635 -0.8857847 0.4556798 0.08114945 -0.8257774 0.5581277 4.27273e-4 -0.8543941 0.5196254 -0.2075022 -0.9262371 0.3146868 0.07162898 -0.8591517 0.5066831 0.003265559 -0.8729189 0.4878543 -0.01016288 -0.9084361 0.4179002 -0.1853757 -0.9463807 0.264574 0.04190206 -0.1108437 0.9929541 0.04550427 -0.06055033 0.9971275 0.04553413 -0.07007133 0.9965022 0.03857588 -0.135443 0.9900339 0.04794543 -0.0388202 0.9980953 0.04919624 -0.05737525 0.9971399 0.05212706 -0.04968553 0.9974038 0.04953241 -0.06537181 0.9966309 0.04409992 -0.08279794 0.9955902 0.0448932 -0.0762971 0.996074 0.04541176 -0.07321423 0.9962819 0.04583966 -0.07190304 0.9963577 0.04840356 -0.06924825 0.9964244 0.05133277 -0.0408343 0.9978466 0.04928863 -0.03851532 0.9980418 0.05009913 0.02100437 0.9985234 0.05322486 -0.03234994 0.9980585 0.05101984 0.02236318 0.9984473 0.05033528 0.02064418 0.998519 0.05047011 0.02085238 0.9985079 0.05027341 0.0188784 0.9985572 0.05005908 0.01797908 0.9985845 0.04977059 0.01842385 0.9985908 0.05016469 0.02122151 0.9985155 0.05147504 0.02850455 0.9982674 0.05093836 0.02564585 0.9983725 0.05045461 0.02322828 0.9984563 0.0495035 0.01711356 0.9986273 0.04992115 0.01910871 0.9985704 0.04967647 0.01634252 0.9986317 0.05020707 0.02049618 0.9985285 0.05031955 0.0191363 0.9985498 0.05034202 0.02065366 0.9985185 0.05068635 0.02132076 0.9984871 0.05057334 0.0210545 0.9984984 0.05070751 0.02100229 0.9984928 0.05072587 0.02141487 0.9984831 0.05154758 0.01563954 0.9985482 0.05300551 0.04317808 0.9976603 0.05115699 0.02302569 0.9984252 0.05224776 0.003204405 0.998629 0.05087524 -0.00778234 0.9986748 0.05121123 0.003936946 0.9986801 0.05075258 -0.02145463 0.9984809 0.05285871 -0.02179044 0.9983643 0.05243235 -0.007629811 0.9985954 0.05426216 -0.005798518 0.99851 0.05560499 0.002960264 0.9984486 0.05563676 -0.004608392 0.9984405 0.05627101 0.01423805 0.998314 0.05563074 0.02013605 0.9982484 0.05611902 0.01217013 0.9983499 0.03663641 -0.1916508 0.9807792 0.04950147 -0.02530008 0.9984536 0.05304247 -0.04486334 0.997584 0.0363633 -0.1818661 0.9826507 0.03480297 -0.1904251 0.9810847 0.0187692 -0.3404402 0.9400789 0.03497475 -0.1915982 0.9808502 0.0481891 -0.0127263 0.9987572 0.04980689 -0.007263481 0.9987325 0.04937988 -0.02124124 0.9985543 0.03105288 -0.2236483 0.9741752 0.01758843 -0.3559474 0.9343404 0.05227875 -0.02190887 0.9983922 0.05408018 -0.02725374 0.9981647 0.01528924 -0.3616961 0.9321707 0.04779231 -0.02508634 0.9985423 0.04281771 -0.05392652 0.9976265 0.04766499 -0.02412807 0.9985719 0.0461018 -0.02088415 0.9987185 0.0536831 -0.01580888 0.9984329 0.04647302 -0.02101099 0.9986986 0.04670512 -0.01759868 0.9987537 0.0512278 0.02189248 0.9984471 0.05517858 -0.01211607 0.998403 0.04608303 -0.02084416 0.9987201 0.04660218 -0.01760929 0.9987584 0.04577893 -0.02868413 0.9985398 0.0511772 0.02076929 0.9984737 0.053083 0.02925503 0.9981615 0.04375833 -0.03934925 0.998267 0.05119431 0.02243095 0.9984368 0.05081343 0.01257365 0.998629 0.05350041 0.003296077 0.9985625 0.05450612 0.003814816 0.9985061 0.0513041 0.02170991 0.9984471 0.05138945 0.02182251 0.9984403 0.05296796 0.0292927 0.9981665 0.05290681 0.02979522 0.9981549 0.05136376 0.003177165 0.998675 0.05143648 0.01203995 0.9986038 0.05301141 0.01220756 0.9985194 0.05252087 0.01226359 0.9985446 0.05414026 0.0127263 0.9984523 0.05554437 0.01351982 0.9983648 0.05612379 0.003479123 0.9984178 0.05088931 0.01695704 0.9985603 0.05463296 0.03150725 0.9980093 0.05105042 0.02249205 0.9984428 0.05026 0.003495573 0.9987301 0.05597156 0.01611393 0.9983024 0.0533027 0.02969318 0.9981369 0.05129683 0.0238015 0.9983998 0.0516147 0.01208263 0.9985941 0.05145096 0.01946353 0.9984859 0.05307424 0.01240545 0.9985135 0.05236548 0.01908534 0.9984456 0.05307543 0.01242071 0.9985133 0.05485492 0.01282364 0.9984121 0.0545938 0.0195406 0.9983175 0.05676603 0.01403886 0.9982889 0.05358386 0.03054141 0.9980962 0.05085849 0.02178609 0.9984682 0.05035048 0.01165664 0.9986637 0.05205196 0.02029699 0.9984381 0.05179959 0.01837843 0.9984885 0.05632764 0.02129679 0.9981852 0.05375128 0.02502226 0.9982408 0.05403107 0.01964956 0.9983459 0.05532836 0.02563387 0.9981392 0.0572738 0.02548027 0.9980334 0.4293463 -0.674203 0.6009261 0.4764362 -0.7507739 0.4575448 0.4212912 -0.6639212 0.6178368 0.4582795 -0.7228218 0.5172125 0.4857714 -0.766516 0.4200945 0.4977135 -0.7857574 0.3672422 0.5095898 -0.805266 0.3030925 0.5083003 -0.8025682 0.3122743 0.5238045 -0.8302498 0.1905631 0.5171087 -0.8173516 0.2540376 0.528472 -0.8388225 0.1307446 0.52948 -0.8374203 0.1355669 0.4724099 -0.744643 0.4715248 0.5338444 -0.8449892 0.03167903 0.5323748 -0.843883 0.06662315 0.5335106 -0.8436188 0.0606116 0.5334065 -0.8443314 0.05081367 0.4425604 -0.6985259 0.5623182 0.361621 -0.5680829 0.7392646 0.365133 -0.5719929 0.7345082 0.3922023 -0.6172814 0.6820126 0.4218444 -0.6640189 0.6173542 0.3551222 -0.5576786 0.7502552 0.2883148 -0.4492121 0.8456259 0.2896246 -0.4532977 0.842994 0.3185878 -0.5014576 0.8043892 0.2787347 -0.4361544 0.8556146 0.2263318 -0.3566802 0.9063957 0.1827514 -0.2837713 0.9413161 0.1695332 -0.2666143 0.9487757 0.1233886 -0.188974 0.9741992 0.1154546 -0.1793621 0.976985 0.05960309 -0.08804661 0.9943316 0.08505761 -0.1260452 0.9883714 0.09879088 -0.1496665 0.9837888 0.5339885 -0.8454919 -6.20103e-5 0.5339152 -0.8455381 0 0.5340229 -0.84547 -2.92937e-5 0 0 1 0 0 1 0 0 1 0 0 1 0 2.10949e-7 1 -1.46438e-7 3.93444e-6 1 1.13512e-6 2.37108e-6 1 -1.26109e-6 -1.60574e-6 1 -1.30542e-6 -3.06049e-6 1 -1.28253e-6 -2.14616e-6 1 -2.70649e-6 -2.01789e-4 1 -1.32914e-6 -4.84479e-6 1 -1.31761e-6 -3.82144e-6 1 -1.27342e-6 -1.88444e-6 1 -1.2948e-6 -2.56809e-6 1 -1.65925e-5 -2.94387e-4 1 -7.11367e-7 -6.84987e-5 1 9.88719e-7 -1.91619e-5 1 -1.67656e-7 3.93733e-6 1 1.60775e-7 4.08274e-6 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.03945004 -0.999221 0.001056373 -0.03938865 -0.9992237 8.26192e-4 -0.03929275 -0.9992274 9.033e-4 -0.03846669 -0.9992575 -0.002226591 -0.03942018 -0.9992219 0.001335442 -0.03947436 -0.9992197 -0.001415729 -0.03938686 -0.9992228 0.001568615 -0.03949731 -0.9992191 -0.001206874 -0.03948456 -0.9992201 -5.40844e-4 -0.03951162 -0.9992186 -0.001118302 -0.03952634 -0.9992186 9.74063e-5 -0.03943884 -0.999222 1.40775e-4 -0.03944361 -0.9992218 6.47196e-5 -0.03958517 -0.999215 -0.001584112 -0.03957337 -0.9992161 -0.001178801 -0.03931617 -0.9992259 0.001327872 -0.03951823 -0.9992188 -5.64586e-4 -0.03929585 -0.9992268 0.00137943 -0.03946113 -0.9992212 -5.6867e-5 -0.03923416 -0.9992284 0.001862883 -0.03945392 -0.9992215 0 -0.0396257 -0.9992139 -0.001177251 -0.03989076 -0.9992038 8.33911e-4 -0.03885716 -0.9992441 -0.001173198 -0.03925275 -0.9992292 -4.77073e-4 -0.0397194 -0.9992107 5.90278e-4 -0.03987962 -0.9992042 8.1165e-4 -0.03912782 -0.9992339 -7.57521e-4 -0.03943085 -0.9992224 0 -0.04031389 -0.9991852 0.001942157 -0.03888702 -0.9992428 -0.001253783 -0.03942722 -0.9992225 -5.64461e-5 -0.03990584 -0.9992029 0.001150786 -0.03983831 -0.9992061 -4.56323e-4 -0.04025208 -0.9991893 -8.04809e-4 -0.03945076 -0.9992216 -1.07379e-4 -0.03960251 -0.9992156 -1.78336e-4 -0.03945553 -0.9992214 -9.72501e-5 -0.03921985 -0.9992306 6.73904e-5 -0.03890883 -0.9992374 0.00331521 -0.03866285 -0.9992405 0.004883348 -0.03884005 -0.9992393 0.003528594 -0.03885191 -0.9992389 0.003477513 -0.03906637 -0.9992341 0.002266764 -0.04160153 -0.9990602 -0.01217454 -0.03917217 -0.9992317 0.001297831 -0.03911226 -0.9992334 0.001729846 -0.03940874 -0.9992232 2.74016e-4 -0.03935086 -0.9992252 7.11851e-4 -0.03964465 -0.9992136 -7.08643e-4 -0.0395568 -0.9992172 -4.99749e-4 -0.03985744 -0.9992041 -0.001590251 -0.03971982 -0.9992104 -0.001009285 -0.04016792 -0.9991905 -0.002278447 -0.03863888 -0.9992495 0.002762436 -0.03895014 -0.9992403 0.001325368 -0.03941553 -0.999223 8.86248e-5 -0.03921973 -0.9992305 7.06159e-4 -0.03998488 -0.9991997 -0.001174509 -0.03963059 -0.9992144 -4.06311e-4 -0.03913974 -0.9992337 6.01091e-4 -0.0388391 -0.9992448 0.001198112 -0.0398882 -0.9992041 -4.57149e-4 -0.04007643 -0.9991962 -9.30008e-4 -0.03960424 -0.9992155 -1.91931e-4 -0.03950327 -0.9992195 -3.78113e-5 -0.03891187 -0.9992424 7.44763e-4 -0.03911679 -0.9992346 3.15563e-4 -0.04024398 -0.9991896 -9.19124e-4 -0.03807312 -0.9992744 0.001059472 -0.03913289 -0.9992341 2.63889e-4 -0.03850591 -0.9992583 5.85763e-4 -0.04134029 -0.9991443 -0.00133866 -0.03925859 -0.9992291 7.40329e-5 -0.04020369 -0.9991914 -4.85123e-4 -0.03984707 -0.9992055 7.56159e-4 -0.03934419 -0.9992257 1.77971e-5 -0.03860861 -0.999253 -0.001658678 -0.03996127 -0.9992008 9.6286e-4 -0.03900873 -0.9992378 -0.001435279 -0.04003024 -0.9991972 0.001654803 -0.03934824 -0.9992249 -0.001188218 -0.03963673 -0.9992133 0.001384496 0.6728025 -0.7398223 6.14993e-7 0.6727961 -0.7398281 -2.00422e-6 0.6728464 -0.7397823 5.95753e-6 0.6727743 -0.7398478 -1.82394e-6 0.672823 -0.7398036 7.91979e-6 0.6732409 -0.7394233 1.24064e-4 0.6727341 -0.7398844 -7.92439e-6 0.6726662 -0.7399461 -5.3025e-5 0.6730577 -0.73959 5.89747e-5 0.6731325 -0.7395219 1.29008e-4 0.6720772 -0.7404811 -2.58827e-4 0.6729336 -0.7397029 3.50526e-5 0.6731386 -0.7395164 1.40495e-4 0.6734938 -0.7391928 3.25718e-4 0.671985 -0.7405648 -3.73716e-4 0.6722172 -0.740354 -3.01901e-4 0.6724504 -0.7401422 -1.74299e-4 0.6737017 -0.7390033 5.1932e-4 0.6727984 -0.7398259 1.15764e-5 0.6734128 -0.7392665 -5.1445e-4 0.671693 -0.7408289 0.001069307 0.6725316 -0.7400684 1.59819e-4 0.6726096 -0.7399976 1.43553e-4 0.6728467 -0.7397819 2.7849e-5 0.670442 -0.7419614 9.6068e-4 0.6705642 -0.7418511 7.57272e-4 0.67539 -0.73746 -0.001103937 0.676698 -0.7362602 -8.32176e-4 0.6701388 -0.7422353 8.1948e-4 0.692426 -0.7214835 -0.002798497 0.6766377 -0.7363157 -7.99808e-4 0.6660797 -0.7458795 0.001297593 0.6708409 -0.7416011 5.58255e-4 0.6801396 -0.7330795 -0.002126097 0.6732347 -0.7394289 -1.68554e-4 0.6731308 -0.7395235 -1.0567e-4 0.6755294 -0.7373321 -0.001242041 0.6728567 -0.7397729 -4.23453e-5 0.6725297 -0.7400702 1.54808e-4 0.6727727 -0.7398493 8.13379e-5 0.6737962 -0.738917 -5.71862e-4 0.6716575 -0.7408615 6.45879e-4 0.6721959 -0.7403733 4.19406e-4 0.6719331 -0.7406117 5.11044e-4 0.672598 -0.7400081 1.43091e-4 0.6743184 -0.73844 -0.001116454 0.6714156 -0.7410803 0.001068353 0.6739869 -0.7387426 -0.00105375 0.6729754 -0.7396649 -9.65116e-5 0.6722547 -0.7403198 5.35946e-4 0.67275 -0.7398699 1.40453e-5 0.672631 -0.7399781 9.18521e-5 0.672802 -0.7398227 -9.89655e-6 -0.02730536 -0.9996272 -2.11007e-6 -0.02729982 -0.9996273 3.55677e-5 -0.0272957 -0.9996275 -2.10855e-6 -0.02730005 -0.9996273 1.05545e-4 -0.02729827 -0.9996274 -1.07923e-4 -0.02727794 -0.999628 0 -0.02729767 -0.9996274 -7.37158e-5 -0.0273025 -0.9996273 1.45626e-4 -0.02729296 -0.9996276 -1.5587e-4 -0.02730226 -0.9996272 3.79319e-5 -0.02729076 -0.9996275 -2.52363e-4 -0.02730637 -0.9996272 2.00784e-4 -0.02731043 -0.999627 1.85283e-4 -0.02730178 -0.9996272 8.76145e-5 -0.02731466 -0.9996269 2.10206e-4 -0.02728807 -0.9996277 -1.47884e-4 -0.02730393 -0.9996272 1.25322e-4 -0.02729165 -0.9996275 -1.14835e-4 -0.02727669 -0.999628 5.4235e-5 -0.02729934 -0.9996274 0 -0.02729541 -0.9996274 2.48217e-5 -0.02727925 -0.999628 0 -0.02733838 -0.9996263 -2.11143e-4 -0.02730756 -0.9996272 0 -0.02730071 -0.9996274 -6.36363e-6 -0.02735769 -0.9996258 -1.81239e-4 -0.02720075 -0.9996301 -4.76358e-5 -0.02734881 -0.999626 1.15739e-5 -0.02725702 -0.9996285 0 -0.02734726 -0.9996261 3.52353e-5 -0.0274809 -0.9996224 1.28346e-4 -0.02710115 -0.9996328 -1.32209e-4 -0.0274018 -0.9996246 1.75718e-5 -0.02716839 -0.9996309 -6.30483e-5 -0.02712458 -0.9996321 -1.07296e-4 -0.02749949 -0.9996217 -7.04157e-4 -0.02688723 -0.999638 9.74686e-4 -0.02728807 -0.9996277 0 -0.02723139 -0.9996292 1.10725e-4 -0.0272721 -0.9996281 0 -0.02715438 -0.9996312 4.75675e-4 -0.02722567 -0.9996293 2.89756e-4 -0.02735155 -0.9996259 -3.80798e-4 -0.02724111 -0.9996289 1.51512e-4 -0.02724748 -0.9996287 1.08135e-4 -0.02728593 -0.9996278 -9.17721e-5 -0.02730304 -0.9996272 -1.92116e-4 -0.02726083 -0.9996284 4.29754e-5 -0.0272569 -0.9996285 1.32046e-4 -0.02726888 -0.9996282 4.10751e-5 -0.02727383 -0.9996281 -4.17569e-5 -0.02727252 -0.9996281 -8.03945e-5 -0.02727127 -0.9996281 -8.13843e-5 -0.02742648 -0.9996239 1.08993e-4 -0.02731812 -0.9996268 4.49477e-6 -0.02721631 -0.9996297 7.78159e-7 -0.02728277 -0.9996278 -6.42114e-7 -0.02729934 -0.9996274 1.72371e-6 -0.02731204 -0.9996271 0 -0.02728927 -0.9996277 -3.90864e-5 -0.02730029 -0.9996274 3.85883e-6 -0.02730101 -0.9996273 8.00156e-6 -0.02730613 -0.9996271 2.27465e-5 -0.0273084 -0.9996271 2.44675e-5 -0.02728939 -0.9996276 -2.82883e-5 -0.02729028 -0.9996276 -1.24225e-5 -0.02729833 -0.9996274 -3.08356e-6 -0.02728372 -0.9996278 -1.67433e-5 -0.02730989 -0.9996271 1.0413e-5 -0.02729409 -0.9996275 -4.21252e-6 -0.02730315 -0.9996273 -1.05029e-6 -0.02730387 -0.9996272 -3.16435e-6 -0.02728754 -0.9996277 0 -0.02729874 -0.9996274 0 -0.02730059 -0.9996274 0 -0.02731627 -0.9996269 1.87737e-5 -0.02729433 -0.9996275 -9.70346e-7 -0.02728974 -0.9996277 -1.45332e-6 -0.02729725 -0.9996274 -2.93107e-6 -0.02730059 -0.9996274 0 -2.51607e-5 5.04556e-5 1 4.32131e-6 1.68297e-4 1 0.4558986 -0.8900318 6.64931e-5 0.4557133 -0.8901267 0 0.4559288 -0.8900164 1.2873e-4 0.4559285 -0.8900164 6.48731e-5 0.4559941 -0.8899826 6.49133e-4 0.8944276 0.4472129 -1.19768e-5 0.8947926 0.446481 -9.3117e-4 0.8943004 0.4474659 0.001123249 0.8941757 0.4477162 4.42383e-4 0.8944296 0.447209 6.09476e-6 0.8949869 0.4460925 -3.28561e-4 0.8941715 0.4477246 4.38036e-4 0.8931362 0.4497858 7.57726e-4 0.895038 0.44599 -3.54455e-4 0.8956338 0.4447922 -3.65859e-4 0.8946045 0.4468589 4.13391e-5 0.8881448 0.4595631 -7.69358e-4 0.8946016 0.4468648 3.06778e-5 0.8928236 0.450406 -6.08743e-4 0.9015347 0.4327069 -3.38052e-5 0.8893107 0.4573032 -7.06002e-4 0.8854585 0.4647155 -0.001621782 0.897291 0.4414393 3.27993e-4 0.8916888 0.4526484 -6.80742e-4 0.8961524 0.4437464 4.15167e-4 0.8925171 0.451013 -7.55509e-4 0.8941786 0.4477106 -1.93646e-4 0.8971769 0.4416696 0.001279771 0.8945807 0.4469065 0 0.8946196 0.4468287 4.21075e-6 0.8944971 0.4470738 -1.04731e-5 0.04550427 -0.8503599 0.5242304 0.02996999 -0.9506168 0.3089169 0.01431351 -0.8941829 0.4474729 0.03698867 -0.998512 0.04007107 0.02224844 -0.9952601 0.09467041 0.03683614 -0.9984527 0.0416581 0.039034 -0.9988313 0.0285049 0.03662329 -0.9982913 0.04553496 0.0397666 -0.9988041 0.02844393 0.0371415 -0.998152 0.04809778 0.03750747 -0.9981147 0.04858577 0.03668403 -0.9982821 0.04568719 0.05099791 -0.9986869 0.00488305 0.03875952 -0.9980741 0.04843419 0.04635775 -0.9988435 0.01275676 0.04635781 -0.9988447 0.01266521 0.04727333 -0.9988133 0.0117191 0.04913514 -0.9987559 0.008514702 0.03915578 -0.9980616 0.0483725 0.04080355 -0.9980856 0.04648005 0.04199361 -0.9981116 0.04483181 0.0421167 -0.9981363 0.04416149 0.03149545 -0.9922298 0.1203665 0.04202497 -0.9980091 0.04703009 0.04199463 -0.9978619 0.05008226 0.04226851 -0.997568 0.05542212 0.04205495 -0.9977226 0.05273658 0.04764038 -0.9849754 0.1659937 0.0454117 -0.997196 0.05948078 0.04461902 -0.997184 0.06027537 0.05255359 -0.879831 0.4723724 0.04831176 -0.9080356 0.4160978 0.05468964 -0.9282904 0.3678126 0.044954 -0.9967406 0.06698852 0.04526031 -0.9965509 0.06955379 0.04559606 -0.9963689 0.07190382 0.04602324 -0.9961836 0.07416212 0.04699945 -0.9958707 0.07767122 0.04648071 -0.9960245 0.07599276 0.04947209 -0.9953932 0.08212792 0.05746698 -0.9589942 0.2775385 0.0611903 -0.9424223 0.3287796 0.0611 -0.9933183 0.09790652 0.05945086 -0.9933612 0.09848463 0.05691742 -0.9920419 0.1123089 0.06479179 -0.9709613 0.2302962 0.07391631 -0.9764461 0.2027052 0.06415081 -0.9879598 0.1407839 0.07013231 -0.9844467 0.1610785 0.06463903 -0.9908875 0.1181691 0.06647157 -0.9893217 0.1297081 0.04461926 -0.9971283 0.06119126 0.06799685 -0.9884573 0.1353833 0.04379433 -0.9971985 0.06064063 0.04342859 -0.9972108 0.06070238 0.04297095 -0.9973059 0.05945134 0.042544 -0.9974352 0.05755954 0.03970521 -0.8149189 0.5782134 0.02047818 -0.9965362 0.08060061 0.03030502 -0.9980833 0.05395704 0.04495477 -0.780743 0.6232332 0.03570693 -0.7551871 0.6545362 0.007934808 -0.9942669 0.1066321 -6.71424e-4 -0.8155358 0.5787063 0.0283221 -0.716537 0.696974 0.03372406 -0.6739321 0.7380232 -0.002105772 -0.9914985 0.1301021 -0.01736527 -0.9871056 0.1591259 -0.01101732 -0.9809078 0.1941612 -0.04330593 -0.8737789 0.4843917 -0.0165109 -0.716378 0.6975171 0.02401828 -0.6442525 0.7644357 0.01672458 -0.5964092 0.8025064 0.02435427 -0.5361613 0.8437643 -0.04410058 -0.9556866 0.2910642 -0.03665328 -0.9774317 0.2080479 -0.05246233 -0.9701415 0.2367978 0.01406949 -0.4940507 0.8693193 -0.03225862 -0.6020193 0.7978297 0.007324516 -0.4390774 0.8984194 0.01461845 -0.3858178 0.9224592 -0.08997082 -0.715891 0.692391 -0.04525947 -0.4750566 0.8787906 -0.008240044 -0.2088404 0.9779151 0.003479182 -0.2411623 0.9704786 -0.003906428 -0.2961589 0.9551308 -0.1318742 -0.5153198 0.8467908 -0.1332786 -0.4538249 0.8810674 -0.1250967 -0.4358092 0.8913031 -0.06207525 -0.3357071 0.9399189 -0.08438456 -0.2675281 0.9598479 -0.06921708 -0.261151 0.9628132 -0.05157786 -0.22737 0.9724417 -0.01028472 0.01596122 0.9998198 -0.005249202 -0.05017286 0.9987268 -0.01251274 -0.1106004 0.9937862 -0.005951106 -0.02484226 0.9996737 -0.00714147 -0.09970664 0.9949914 -0.08276861 -0.2804429 0.9562955 -0.01486265 -0.1550049 0.9878019 -0.1744778 -0.7713711 0.6120001 -0.1786588 -0.7501901 0.6366285 -0.1605612 -0.7476583 0.6443814 -0.1062679 -0.3771566 0.9200326 -0.1412101 -0.465136 0.8739039 -0.1493303 -0.4683471 0.8708338 -0.1837261 -0.731883 0.6561952 -0.1814681 -0.6814973 0.7089647 -0.1567155 -0.4620895 0.8728765 -0.1544891 -0.474546 0.8665676 -0.1903157 -0.6932973 0.6950674 -0.1922388 -0.6688836 0.7180801 -0.1948655 -0.654272 0.7307227 -0.170786 -0.555085 0.8140718 -0.1877535 -0.6034238 0.7750022 -0.1711823 -0.4693552 0.8662577 -0.1877542 -0.5802619 0.7924926 -0.1795141 -0.5039641 0.8448639 -0.1877825 -0.5599297 0.8069798 -0.1161239 -0.410325 0.9045157 -0.163337 -0.8070108 0.5674986 -0.1370311 -0.8138855 0.5646353 0.002807736 -0.3526768 0.9357411 -0.1105701 -0.6187409 0.7777751 -0.06735557 -0.8017361 0.5938707 -0.1087698 -0.8719898 0.4772872 -0.08087611 -0.954491 0.2870645 -0.07712149 -0.9190496 0.3865233 -0.06415069 -0.9638475 0.2586171 -0.09338802 -0.9475834 0.3055559 -0.1432257 -0.8591715 0.4912341 -0.1356902 -0.8742346 0.4661567 -0.02847391 -0.9829459 0.1816777 -0.01849478 -0.9300504 0.3669661 0.006348013 -0.9695693 0.2447347 -0.1906868 -0.7278636 0.6586754 -0.1571724 -0.8241329 0.5441524 -0.1029414 -0.9336756 0.3430059 -0.1705121 -0.7964662 0.5801443 -0.1506092 -0.8448768 0.5133228 -0.001159667 -0.04675453 0.9989058 0.007049918 -0.1499111 0.9886745 0.002288877 -0.09879028 0.9951057 0.03286874 -0.4424005 0.8962151 0.0280472 -0.4505866 0.8922922 0.01751816 -0.3016854 0.9532466 0.05350029 -0.6834792 0.7280068 0.05429321 -0.6755375 0.7353241 0.06259423 -0.7792393 0.6235929 0.0480057 -0.5207082 0.8523841 0.04617583 -0.5267342 0.8487749 0.03616529 -0.3978492 0.9167378 0.03796523 -0.5903233 0.8062736 0.04147595 -0.5828609 0.8115128 0.05090641 -0.7068611 0.7055183 0.0222786 -0.288707 0.9571583 0.03470009 -0.4203689 0.9066895 0.03378421 -0.4314738 0.9014927 0.02160727 -0.2960324 0.9549335 0.05179107 -0.6991344 0.7131122 0.04348993 -0.5772418 0.8154143 0.05505627 -0.6674813 0.7425885 0.04602307 -0.5493777 0.8343058 0.05575919 -0.6593751 0.7497435 0.05264592 -0.6913561 0.7205937 0.04275768 -0.5691877 0.8210951 0.04403942 -0.5552392 0.830524 0.04483276 -0.5634464 0.8249354 0.03869754 -0.3887457 0.9205321 0.05011248 -0.5121428 0.8574371 0.04519861 -0.5410715 0.8397611 0.03549402 -0.4091731 0.9117661 0.04709035 -0.5351459 0.8434461 0.06445705 -0.7624675 0.643808 0.02340805 -0.2815073 0.9592736 0.02353048 -0.2736372 0.9615452 0.02707064 -0.2600861 0.9652059 0.02374374 -0.2664916 0.9635449 0.01489341 -0.1303176 0.9913604 0.0117805 -0.1362695 0.9906018 0.01956254 -0.1927263 0.9810576 0.01281785 -0.1313831 0.9912488 0.03067201 -0.309681 0.9503457 0.006592094 -0.06030577 0.9981582 0.009186327 -0.06232053 0.998014 0.00213629 -0.02291959 0.9997351 0.0465722 -0.7146674 0.6979123 0.04831171 -0.73023 0.6814911 0.04101741 -0.6736441 0.7379169 0.03109925 -0.5001526 0.8653787 0.0277419 -0.4274519 0.9036124 0.02176004 -0.3623825 0.9317755 0.001342833 -0.07217735 0.9973909 0.001037597 -0.01528984 0.9998826 0.01373374 -0.2275835 0.9736618 0.01046806 -0.1615684 0.986806 0.02014225 -0.2969457 0.9546819 0.03613489 -0.5617391 0.8265249 0.03851532 -0.6276905 0.7775098 0.05377477 -0.8191348 0.5710749 0.04977744 -0.7783412 0.6258653 0.05566656 -0.8173892 0.5733902 0.05432337 -0.8528777 0.519277 0.06686854 -0.736317 0.6733245 0.06610435 -0.7451546 0.6636075 0.05707097 -0.6429187 0.7638054 0.05966377 -0.8999319 0.4319294 0.06354093 -0.7709146 0.6337613 0.05722266 -0.8815956 0.4685241 0.04770177 -0.5066523 0.8608298 0.05426377 -0.5646121 0.8235707 0.06128263 -0.9093514 0.4114909 0.06018394 -0.9317835 0.3579909 0.06387704 -0.9559895 0.2863634 0.06964486 -0.7272431 0.6828376 0.06045895 -0.6259536 0.7775132 0.06564563 -0.6938116 0.7171584 0.06531107 -0.7538853 0.6537518 0.05643016 -0.6512209 0.7567872 0.06408923 -0.9511762 0.3019214 0.08402055 -0.919465 0.3840896 0.07968699 -0.8985924 0.4314879 0.08087641 -0.8908309 0.4470788 0.07055985 -0.9711138 0.2279462 0.06589049 -0.9757534 0.2087194 0.06314373 -0.9678483 0.2434803 0.06366235 -0.9798694 0.189217 0.06817942 -0.9856109 0.1546702 0.07843452 -0.9060561 0.4158251 0.08273649 -0.9264904 0.3671109 0.07736498 -0.8132326 0.5767734 0.08252376 -0.8636921 0.4972181 0.08365267 -0.8826718 0.4624856 0.07464951 -0.822274 0.5641747 0.07892173 -0.8268777 0.5568165 0.08597302 -0.9002295 0.4268437 0.08649235 -0.9122289 0.4004468 0.08929866 -0.9144724 0.3946722 0.07223826 -0.9666563 0.2456773 0.06833249 -0.9504906 0.3031474 0.06991976 -0.94497 0.3195984 0.07144594 -0.9391743 0.3359273 0.07547378 -0.9567744 0.2808675 0.07388645 -0.9618672 0.2633484 0.0583831 -0.8111994 0.5818479 0.06421184 -0.8928316 0.4457901 0.0655561 -0.885801 0.4594116 0.05948185 -0.8034171 0.5924381 0.005585014 -0.07346016 0.9972825 0.01123106 -0.145577 0.9892832 0.07703089 -0.9513503 0.298327 0.0729416 -0.9331031 0.3521339 0.06686788 -0.8785603 0.4729277 0.06058031 -0.7955102 0.6029043 0.005279839 -0.07223933 0.9973735 0.07437425 -0.9267635 0.368209 0.07852667 -0.9456164 0.3156632 0.07577854 -0.9201464 0.3841725 0.07996034 -0.9395646 0.3329036 0.06158697 -0.7874165 0.613337 0.06811761 -0.8711246 0.4863148 0.01165807 -0.1408435 0.9899633 0.00576812 -0.07181191 0.9974016 0.06934052 -0.8634909 0.4995752 0.005371391 -0.06970602 0.9975531 0.07712239 -0.9132304 0.4000781 0.08139556 -0.933196 0.3500286 0.07049936 -0.8556366 0.5127533 0.005585014 -0.07010287 0.9975242 0.07162773 -0.8476003 0.5257789 0.00601232 -0.06912654 0.9975898 0.07269608 -0.8393622 0.5386897 0.05768108 -0.6345837 0.7706989 0.00564593 -0.06772106 0.9976884 0.07370436 -0.8309218 0.551486 0.0352801 -0.3694645 0.9285749 0.006103694 -0.06726312 0.9977166 0.07641971 -0.7875137 0.6115408 0.04172015 -0.4401218 0.8969684 0.02343875 -0.2485178 0.9683437 0.005615472 -0.06433421 0.9979127 0.07223874 -0.7491226 0.6584808 0.05978602 -0.6277074 0.7761501 0.005829036 -0.0650047 0.997868 0.1623333 -0.9844071 0.06775331 0.2654263 -0.9638602 0.02285891 0.1596472 -0.9849234 0.06662392 0.158546 -0.9853655 0.06259435 0.2446109 -0.9691656 0.02972561 0.1531161 -0.9865109 0.05789536 0.1091651 -0.993473 0.03308218 0.2178149 -0.9746584 0.05096691 0.148109 -0.9874442 0.05493426 -0.1087703 -0.8955854 0.4313886 0.09940016 -0.99388 0.0481894 0.1093484 -0.993474 0.03244131 0.1065436 -0.9920365 0.06717342 0.1025446 -0.9936758 0.04574829 0.1924222 -0.9800257 0.05023425 0.1660534 -0.9849371 -0.04821985 0.1726751 -0.9836196 0.05172926 0.115453 -0.9929323 0.02749752 0.1229014 -0.9919709 -0.0298174 0.09769022 -0.9950611 0.01760923 0.1489933 -0.9873783 -0.05371326 0.1089532 -0.9937028 0.02615487 0.08533042 -0.9963151 0.00866729 0.08871942 -0.9960563 -8.85058e-4 0.07068276 -0.9974634 0.008423328 0.0706827 -0.9974626 0.008514881 0.1675793 -0.9834108 0.06943047 0.2812377 -0.959535 0.01406949 0.2819643 -0.9506337 0.1295832 -0.03909492 -0.877179 0.4785695 0.1637957 -0.9838122 0.07269638 0.2515376 -0.9594561 0.1271726 0.3181896 -0.9415678 0.1104782 0.3318014 -0.9364113 0.1142017 0.2559674 -0.9567877 0.1379788 0.3443834 -0.9314587 0.1174089 0.2588313 -0.9553044 0.1428287 0.2595629 -0.9542635 0.1483521 0.3589636 -0.9253339 0.1220757 0.1584227 -0.9844121 0.07638835 0.3751721 -0.9198781 0.1143248 0.2622482 -0.9532856 0.1499084 0.2651808 -0.9518309 0.1539385 0.383537 -0.9161916 0.1161567 0.2612454 -0.9522943 0.1577543 -0.04580861 -0.7875663 0.6145251 0.3806343 -0.9009546 0.2083234 0.3489851 -0.9080022 0.2318225 0.3459365 -0.9114903 0.2225164 0.2571849 -0.9526251 0.1623619 0.1559196 -0.9843167 0.08252227 0.350758 -0.9054152 0.239149 0.3515774 -0.9032061 0.2461957 0.446375 -0.867663 0.2188842 0.3541112 -0.8995456 0.2557792 0.2541984 -0.9521223 0.169842 0.3547215 -0.8982026 0.2596245 0.1503087 -0.9852929 0.08127349 0.1051983 -0.9935093 0.04327565 0.2479045 -0.9534698 0.1715769 0.3430296 -0.9013683 0.264322 0.3474904 -0.900344 0.261976 0.1546394 -0.9828618 0.1003462 0.3429428 -0.8972303 0.2781509 0.2496461 -0.9491742 0.1916904 0.3402616 -0.8951669 0.2879208 0.4232738 -0.8310743 0.3607701 0.4258341 -0.8336618 0.3516724 0.2478781 -0.9464355 0.2069212 0.3363798 -0.8907565 0.3056167 0.338917 -0.8932393 0.2953964 0.1559819 -0.9784045 0.1356258 0.08691865 -0.9883336 0.1250676 0.1564118 -0.9774744 0.1417014 0.4180864 -0.8187767 0.3934572 0.4215381 -0.8214073 0.384182 0.334733 -0.8874025 0.3169709 0.4191501 -0.8164486 0.3971458 0.2453737 -0.9426748 0.2261772 0.2446727 -0.9401147 0.2373176 0.156868 -0.9762135 0.1496655 0.1574493 -0.9737195 0.1645603 0.2431478 -0.9384402 0.2453757 0.3290939 -0.8830569 0.3345264 0.1573886 -0.9719516 0.1747541 0.239634 -0.9346706 0.2626148 0.2419581 -0.9370078 0.2519379 0.3232563 -0.8756486 0.3588108 0.4012961 -0.8002119 0.445671 0.4051069 -0.8040795 0.4351374 0.2388741 -0.932119 0.2722012 0.3244191 -0.8785257 0.3506351 0.3198999 -0.8730259 0.3680894 0.2381109 -0.9288218 0.2838897 0.3171886 -0.8695294 0.3785632 0.2360951 -0.9275647 0.2896255 0.1568387 -0.965112 0.2096676 0.2339879 -0.9260942 0.2959717 0.3879321 -0.7897505 0.4751871 0.3916498 -0.7921807 0.4680387 0.3156555 -0.8662137 0.387344 0.2330433 -0.9236584 0.3042137 0.1559822 -0.9627502 0.2208655 0.2312099 -0.9181254 0.3218505 0.3097118 -0.8597342 0.4061229 0.2310918 -0.9205525 0.3149282 0.2270955 -0.9131431 0.3385221 0.3024771 -0.8515198 0.4282777 0.229108 -0.9156997 0.3301572 0.3690973 -0.7723454 0.5169621 0.3000951 -0.8477008 0.4374315 0.2267299 -0.9118334 0.342277 0.2239814 -0.9094153 0.350423 0.2840137 -0.8313185 0.477751 0.2813891 -0.8284804 0.4841907 0.3452636 -0.749124 0.5653374 0.2787305 -0.8255709 0.4906548 0.3419733 -0.7458711 0.5716036 0.2754958 -0.8222455 0.4980106 0.3381828 -0.742043 0.5787959 0.1443841 -0.9368334 0.318585 0.1449667 -0.938988 0.3119074 0.1070622 -0.9567847 0.2703718 0.2728123 -0.8191693 0.504515 0.2705584 -0.8163144 0.5103224 0.3313156 -0.736396 0.5898737 0.1066027 -0.9554263 0.2753115 0.1434703 -0.9350443 0.3242044 0.264419 -0.8101954 0.523131 0.3239271 -0.7286681 0.6034187 0.2678707 -0.8133785 0.5163921 0.09036684 -0.9485621 0.3034203 0.1418212 -0.9282622 0.3438257 0.1410584 -0.9302166 0.338821 0.09579813 -0.9427831 0.3193475 0.1408771 -0.9229651 0.3581747 0.1400817 -0.9248747 0.3535307 0.09879171 -0.9359123 0.3380955 0.1370313 -0.9132266 0.3837181 0.1384643 -0.9146821 0.3797162 0.1017515 -0.9264451 0.3624172 0.1329414 -0.9029704 0.408621 0.1342529 -0.9051623 0.4033082 0.2806589 -0.691698 0.6654205 0.235731 -0.7814466 0.5777303 0.2321002 -0.7772076 0.5848742 0.09885197 -0.9330362 0.3459363 0.1366938 -0.9103768 0.3905495 0.2473249 -0.7922089 0.5578849 0.243851 -0.7873731 0.5661982 0.2958208 -0.7048366 0.6447446 0.1380394 -0.9200693 0.3666299 0.2538861 -0.7988608 0.5453104 0.3101978 -0.7156767 0.6257669 0.2574011 -0.8021122 0.5388514 0.2600266 -0.8058996 0.5318949 0.3145052 -0.719959 0.6186643 0.09192311 -0.9461184 0.3104999 0.09815055 -0.953428 0.2852044 0.1429502 -0.9329 0.3305495 0.3046146 -0.7118354 0.6328511 0.2502565 -0.7955107 0.5518463 0.240091 -0.7838743 0.5726234 0.2863962 -0.6969158 0.6574844 0.2652399 -0.6798699 0.6836848 0.2258759 -0.7715367 0.5947363 0.2223014 -0.7673426 0.6014711 0.1027892 -0.9230273 0.3707491 0.1308364 -0.8987947 0.4183897 0.1318121 -0.9009249 0.4134732 0.1040409 -0.9207727 0.3759695 0.1304383 -0.8971983 0.4219256 0.1284555 -0.8947631 0.4276661 0.2369567 -0.6582844 0.7145022 0.2077144 -0.7540711 0.6230822 0.200941 -0.7491339 0.6312062 0.1272656 -0.8920494 0.4336491 0.1032764 -0.918104 0.3826476 0.1030951 -0.9150993 0.3898267 0.1242733 -0.8884074 0.4419147 0.1258935 -0.8902275 0.4377738 0.2273402 -0.6498836 0.7252364 0.1971536 -0.7453079 0.6369039 0.1942254 -0.7429032 0.6406022 0.1901653 -0.7403354 0.6447797 0.2213531 -0.6471823 0.7294915 0.1822019 -0.7338131 0.6544622 0.2123517 -0.6405037 0.7380121 0.1863207 -0.7371953 0.6494827 0.1793909 -0.7312363 0.6581128 0.2074681 -0.6364127 0.7429239 0.2000517 -0.6322306 0.7485077 0.1739009 -0.7277716 0.6634056 0.1813468 -0.6195152 0.7637503 0.1653551 -0.7221851 0.6716446 0.1604387 -0.7194563 0.675753 0.1121273 -0.8755022 0.4700251 0.1141721 -0.8769674 0.4667901 0.09998166 -0.9062444 0.4107612 0.1076114 -0.8722139 0.4771403 0.1095343 -0.8738026 0.4737841 0.09753978 -0.904044 0.4161617 0.09668302 -0.9031683 0.4182578 0.1050152 -0.8706406 0.4805797 0.1455153 -0.5996707 0.7869057 0.1388022 -0.7061276 0.694347 0.1330314 -0.7030919 0.6985446 0.1397482 -0.5965315 0.7903295 0.1289454 -0.7012495 0.7011579 0.102179 -0.8690099 0.4841295 0.09503644 -0.9022055 0.4207057 0.1236326 -0.6994352 0.7039215 0.1331238 -0.5934724 0.7937686 0.1267473 -0.5906738 0.7968938 0.1183219 -0.696717 0.7075206 0.09875988 -0.8678724 0.4868717 0.09390801 -0.9014804 0.4225098 0.1115484 -0.6946213 0.7106745 0.1148124 -0.5851711 0.8027409 0.09195548 -0.9008772 0.4242223 0.09576869 -0.867076 0.4888842 0.1063297 -0.6922113 0.713819 0.1004384 -0.6900679 0.7167416 0.1024534 -0.5798673 0.8082434 0.0906099 -0.8665472 0.4908013 0.09042805 -0.9003438 0.4256803 0.09433394 -0.688934 0.7186594 0.09640961 -0.5769013 0.8111044 0.08749991 -0.6868149 0.7215463 0.09055 -0.574277 0.8136379 0.07992959 -0.6852767 0.7238834 0.07950168 -0.5707948 0.8172349 0.09399896 -0.8608232 0.5001478 0.08658361 -0.9001705 0.4268447 0.07150644 -0.5673211 0.8203862 0.0730623 -0.684143 0.7256793 0.03900343 -0.6757244 0.7361218 0.06320488 -0.5648157 0.822793 -0.5001232 -0.7919508 0.3502724 0.0699203 -0.910826 0.4068259 0.08395946 -0.9187932 0.385707 -0.5516358 -0.7644772 0.3335756 -0.08963423 -0.8854471 0.4560146 -0.5792182 -0.6955561 0.4250977 -0.08356297 -0.8080403 0.583171 -0.6147546 -0.6097799 0.5002453 0.08673441 -0.7755744 0.6252692 -0.5266746 -0.7203817 0.4512915 -0.5351231 -0.644107 0.5465983 -0.02670407 -0.7015705 0.7120996 -0.6326138 -0.5229258 0.571269 0.007996141 -0.5677277 0.8231776 -0.5506303 -0.5513933 0.6267151 -0.03335726 -0.552425 0.8328949 -0.6604641 -0.4230559 0.6203315 0.01229929 -0.4373133 0.8992252 -0.506525 -0.4590068 0.7298941 -0.1019038 -0.4057536 0.9082839 -0.6615993 -0.3263438 0.6751194 -0.6742584 -0.2226368 0.7041366 0.1285456 -0.2667658 0.9551503 -0.4521451 -0.3473719 0.8215215 0.08652067 -0.1247302 0.9884112 -0.7231144 -0.2167146 0.6558508 -0.3283277 -0.2110722 0.9206789 -0.7123821 -0.1191779 0.6915984 -0.7571031 -0.1208887 0.6420132 0.005981743 -0.04315429 0.9990506 0.01629728 -0.02179074 0.9996297 0.1571143 -0.6049267 0.7806273 0.144112 -0.7096342 0.6896746 0.1634597 -0.609098 0.7760674 0.1504919 -0.7129368 0.6848893 0.09940177 -0.9052674 0.41305 0.1705117 -0.6135311 0.7710417 0.1569904 -0.7165587 0.6796305 0.1008358 -0.9073084 0.4081957 0.1161245 -0.878701 0.4630331 0.1878767 -0.6246384 0.7579771 0.170479 -0.7247649 0.6675723 0.1187183 -0.8808959 0.4581794 0.1014767 -0.9085903 0.4051743 0.1936764 -0.628426 0.7533726 0.1020258 -0.909992 0.4018773 0.1200017 -0.8832578 0.453272 0.1231758 -0.8860971 0.446833 0.1030327 -0.9118208 0.3974509 0.2174497 -0.6443838 0.7331338 0.1030621 -0.9134594 0.3936625 0.2332547 -0.6544745 0.7192047 0.1028206 -0.9165655 0.3864396 0.2116186 -0.7579998 0.6169716 0.2486376 -0.6659533 0.703339 0.2540117 -0.6704164 0.6971513 0.2151036 -0.7621101 0.6106708 0.2590124 -0.6752266 0.6906386 0.2192798 -0.7649922 0.6055603 0.1021164 -0.9246633 0.3668379 0.2709194 -0.6836923 0.677619 0.2296587 -0.7743999 0.5895438 0.1358096 -0.9076656 0.3971132 0.1016905 -0.928582 0.3569239 0.276782 -0.6880943 0.6707592 0.1007144 -0.9308149 0.3513407 0.1394712 -0.9166038 0.3746802 0.09705126 -0.938773 0.3305848 0.3007659 -0.7088676 0.6380022 0.3191111 -0.7241038 0.6114261 0.08813989 -0.9507393 0.2971975 0.3279032 -0.7328685 0.5961405 0.3340345 -0.7388129 0.5853005 0.38952 -0.6446017 0.6578472 0.1083447 -0.9583775 0.2641474 0.1462775 -0.9412667 0.3043354 0.1087709 -0.9600163 0.2579494 0.147895 -0.9436774 0.2959731 0.1488732 -0.945397 0.2899336 0.1092579 -0.9620192 0.250164 0.1483836 -0.9467006 0.2859024 0.3532908 -0.7564806 0.5503841 0.2895032 -0.8371361 0.4641024 0.2868508 -0.8342754 0.4708516 0.4164432 -0.6664006 0.618454 0.3564618 -0.7604112 0.5428718 0.1086467 -0.9642397 0.2417389 0.1500937 -0.9486302 0.2785187 0.2911284 -0.8391726 0.4593841 0.150642 -0.9498144 0.2741528 0.2946977 -0.8425557 0.4508361 0.1070608 -0.9658365 0.2360038 0.1517422 -0.9513795 0.2680514 0.3645588 -0.7674199 0.5274123 0.2966204 -0.845089 0.4447933 0.2230356 -0.9067919 0.3577482 0.3069012 -0.8561859 0.4156411 0.3817628 -0.7817759 0.4930352 0.1565646 -0.9613924 0.2263015 0.3851485 -0.7862585 0.4831753 0.3125524 -0.8627924 0.3973667 0.417723 -0.8126477 0.4063391 0.1566526 -0.9794678 0.1268968 0.08304327 -0.9894087 0.1190562 0.07974618 -0.9904335 0.1126151 0.1563203 -0.9805271 0.118873 0.07779204 -0.9913684 0.1055335 0.1558313 -0.9814686 0.1115173 0.1550366 -0.9821634 0.1063893 0.07580924 -0.9921739 0.09921735 0.07403826 -0.9929248 0.09283775 0.07217842 -0.9936822 0.08594268 0.03174018 -0.07217842 0.9968866 0.02166855 -0.1475296 0.9888203 0.03613448 -0.2927076 0.955519 0.08533191 -0.9000447 0.4273617 0.04956334 -0.4332219 0.8999236 0.03933888 -0.07654142 0.99629 0.08447617 -0.7846702 0.6141308 0.03170931 -0.1535721 0.9876286 0.05591064 -0.4364513 0.897989 0.04489356 -0.2982019 0.9534465 0.04886126 -0.07959413 0.9956292 0.05279815 -0.08203548 0.99523 0.06555455 -0.440113 0.8955463 0.04043728 -0.1593382 0.9863955 0.05505645 -0.3024137 0.9515854 0.0466634 -0.1628488 0.985547 0.06174069 -0.08875036 0.9941386 0.08734637 -0.9001986 0.4266299 0.06155776 -0.3049507 0.9503766 0.07352173 -0.4433278 0.8933393 0.0549646 -0.166664 0.9844806 0.0716893 -0.09387665 0.9929994 0.07593065 -0.09579837 0.9925005 0.08817154 -0.9000577 0.4267576 0.06860738 -0.3089471 0.9486016 0.09173929 -0.7856439 0.6118397 0.0806328 -0.446685 0.8910505 0.08517968 -0.5727886 0.8152654 0.06183201 -0.1708163 0.9833609 0.08295035 -0.1002545 0.991498 0.07632952 -0.3127954 0.9467486 0.06903368 -0.1738965 0.9823414 0.08908462 -0.9000024 0.4266847 0.08658123 -0.1044346 0.9907559 0.08872079 -0.4509595 0.888124 0.07385492 -0.177618 0.9813243 0.08035695 -0.3152326 0.9456062 0.09741735 -0.786755 0.6095299 0.0954324 -0.1084334 0.9895125 0.08893239 -0.319229 0.9434956 0.09555655 -0.4539473 0.88589 0.08319586 -0.1825366 0.9796729 0.1019023 -0.1108748 0.9885963 0.08899259 -0.1861032 0.9784917 0.1059006 -0.1127979 0.9879584 0.09634923 -0.3238701 0.9411827 0.09055113 -0.9006896 0.4249221 0.1018117 -0.4563522 0.8839554 0.1030946 -0.7884085 0.6064516 0.1122794 -0.1182305 0.986618 0.09769243 -0.1921193 0.976497 0.1069393 -0.4588868 0.8820357 0.1090469 -0.5822553 0.8056597 0.1026657 -0.3265526 0.9395867 0.1206102 -0.1217393 0.985207 0.1118531 -0.3316223 0.9367581 0.1230535 -0.1240912 0.9846113 0.1077334 -0.1972162 0.9744226 0.1127082 -0.46182 0.8797836 0.1286368 -0.1293083 0.9832254 0.09250342 -0.9011687 0.4234834 0.1130733 -0.200419 0.9731632 0.1223205 -0.4658738 0.8763557 0.1344996 -0.1333094 0.9819056 0.1080372 -0.7899534 0.603574 0.122992 -0.3377856 0.9331527 0.1209153 -0.2044451 0.9713814 0.1455752 -0.1379149 0.9796875 0.1222599 -0.5885324 0.799176 0.1281789 -0.3405898 0.9314337 0.1281507 -0.209729 0.9693252 0.1128905 -0.7912714 0.6009537 0.1290066 -0.4700945 0.8731372 0.15763 -0.1410888 0.9773672 0.1360853 -0.344135 0.9290059 0.1512852 -0.1442657 0.9779061 0.1380069 -0.2161051 0.9665675 0.135078 -0.4733833 0.870438 0.1593092 -0.1476815 0.9761203 0.1442642 -0.3493227 0.9258303 0.1419435 -0.4772548 0.8672255 0.1166741 -0.7931277 0.5977756 0.161691 -0.1496664 0.9754261 0.1465551 -0.2197716 0.9644802 0.09521955 -0.9027546 0.4194849 0.1507659 -0.35372 0.9231208 0.1532671 -0.2244377 0.9623602 0.1660539 -0.1547924 0.973892 0.1496027 -0.4812189 0.8637404 0.120796 -0.7950018 0.5944583 0.1764286 -0.1573544 0.9716545 0.1588807 -0.3574359 0.9203242 0.163429 -0.2306624 0.9592112 0.1790534 -0.1598266 0.9707705 0.1559517 -0.4847017 0.8606645 0.1859844 -0.1654144 0.9685288 0.1241827 -0.796735 0.5914322 0.1659349 -0.3614433 0.9175099 0.1514993 -0.6018468 0.78411 0.161628 -0.4882411 0.8576112 0.1715152 -0.2355435 0.9566096 0.1954436 -0.17054 0.9657733 0.1742358 -0.3657152 0.9142726 0.1800635 -0.2407968 0.9537264 0.1684654 -0.4916323 0.8543519 0.1285451 -0.7993178 0.5869986 0.0976625 -0.9046604 0.4147912 0.2036851 -0.1761263 0.9630639 0.183205 -0.3719035 0.9100131 0.1721569 -0.4938564 0.852331 0.1894336 -0.2454976 0.9507082 0.2121407 -0.1792407 0.9606608 0.1791175 -0.4973419 0.8488628 0.1944364 -0.2485771 0.9488962 0.2161357 -0.1810693 0.9594265 0.1916884 -0.3775784 0.9059196 0.1326057 -0.8021045 0.582275 0.221601 -0.185344 0.9573614 0.2012429 -0.2528813 0.9463363 0.185708 -0.5005419 0.8455591 0.224254 -0.1894013 0.9559485 0.1984354 -0.3812145 0.9029392 0.2075885 -0.2569984 0.9438533 0.136085 -0.8046078 0.5780028 0.1900424 -0.5038399 0.8426324 0.1755161 -0.6160615 0.7678948 0.233382 -0.1937983 0.9528773 0.2049989 -0.385277 0.8997428 0.2154981 -0.2621014 0.9406718 0.2428721 -0.1969711 0.9498503 0.1983156 -0.5081493 0.838126 0.2140287 -0.3908855 0.8952097 0.2443961 -0.199228 0.9489883 0.1396872 -0.8070853 0.5736731 0.2247131 -0.2675621 0.936971 0.2511693 -0.2024308 0.9465389 0.2039601 -0.5114415 0.8347623 0.2293201 -0.2704903 0.935012 0.254439 -0.2069205 0.9446929 0.2214467 -0.3963212 0.8910056 0.1441711 -0.8103979 0.5678645 0.2118063 -0.5164535 0.8297072 0.2391472 -0.2756174 0.9310444 0.2290201 -0.4001747 0.8873613 0.2668873 -0.2132961 0.9398277 0.2702753 -0.2158601 0.9382728 0.2334444 -0.4025536 0.8851296 0.2467167 -0.2813255 0.9273548 0.2183632 -0.5213556 0.8249278 0.1469802 -0.8125722 0.5640243 0.2754344 -0.2216903 0.9354087 0.2408586 -0.406487 0.8813374 0.2576144 -0.2881033 0.9222968 0.1500337 -0.8146255 0.5602458 0.2243461 -0.5256308 0.8205981 0.2779672 -0.2253218 0.9337903 0.2815676 -0.2254128 0.932689 0.247785 -0.4111541 0.8772428 0.101507 -0.9108162 0.4001378 0.2308784 -0.5293875 0.8163604 0.2859001 -0.2281585 0.9307013 0.2662173 -0.2936234 0.9181033 0.1528091 -0.8180949 0.5544099 0.2547119 -0.41689 0.8725392 0.2350589 -0.5314004 0.8138557 0.2931039 -0.2340803 0.9269825 0.2754922 -0.2981066 0.9139127 0.2428133 -0.5354346 0.80892 0.3006411 -0.2396644 0.9231338 0.262524 -0.4219551 0.8677759 0.1571425 -0.8205042 0.5496172 0.266798 -0.4244597 0.8652472 0.2846229 -0.3045215 0.9089866 0.3097422 -0.2434539 0.9191246 0.2495884 -0.5411108 0.8030596 0.1595859 -0.8231387 0.5449544 0.2772985 -0.4305055 0.8589358 0.3134966 -0.2461094 0.9171424 0.2957624 -0.3112662 0.9031268 0.3210306 -0.249921 0.9134982 0.2569748 -0.5470024 0.7967135 0.1620271 -0.8264941 0.5391241 0.3251855 -0.2521828 0.9114046 0.2855091 -0.437038 0.8529259 0.3021095 -0.3151412 0.8996754 0.2622814 -0.5497715 0.79307 0.3329932 -0.2573976 0.9071174 0.1638864 -0.8286489 0.5352403 0.3104686 -0.3207229 0.8948442 0.2676858 -0.5533782 0.788744 0.2958271 -0.443054 0.8462798 0.3392173 -0.2628591 0.9032368 0.1669397 -0.8312502 0.5302398 0.3198125 -0.3274728 0.8890903 0.2446413 -0.6621123 0.7083488 0.2751324 -0.5586271 0.7824564 0.3483152 -0.2664933 0.8986979 0.1697766 -0.8339289 0.5251082 0.102087 -0.9189966 0.3808196 0.3049199 -0.4489412 0.839926 0.3526478 -0.2685067 0.896406 0.32726 -0.3318989 0.8847282 0.280354 -0.5620205 0.7781611 0.1714593 -0.8361769 0.5209702 0.3585989 -0.272993 0.8926824 0.3326569 -0.3345186 0.8817238 0.3120332 -0.4542549 0.8344386 0.3620498 -0.2774505 0.8899108 0.2874882 -0.5666753 0.7721592 0.3399863 -0.3390402 0.8771892 0.1733483 -0.8383285 0.5168711 0.3203021 -0.4593184 0.8285127 0.3690308 -0.282236 0.8855276 0.3487417 -0.3459949 0.8710149 0.2948754 -0.5719582 0.7654492 0.3776511 -0.2854204 0.8808603 0.1765555 -0.841149 0.5111718 0.3301547 -0.4663916 0.8206563 0.3853371 -0.2879499 0.8766984 0.3568958 -0.3516159 0.8654432 0.1775325 -0.8434701 0.5069916 0.2998255 -0.5757846 0.7606424 0.1802438 -0.8457666 0.5021863 0.3062586 -0.5800754 0.7547969 0.3389482 -0.473325 0.8130668 0.3957474 -0.2933847 0.8702353 0.363271 -0.3549087 0.8614372 0.3983426 -0.2989401 0.8671552 0.371422 -0.3600078 0.8558272 0.1829329 -0.8492617 0.4952678 0.3120878 -0.5848976 0.7486628 0.3466334 -0.4780477 0.8070413 0.4053016 -0.3041899 0.8620901 0.3786813 -0.3649476 0.8505374 0.1854932 -0.8529086 0.4879954 0.3183136 -0.5884987 0.7431997 0.3532596 -0.4823557 0.8015864 0.4117914 -0.3091259 0.8572452 0.385916 -0.3695272 0.8452919 0.3219134 -0.5925244 0.7384353 0.3598831 -0.4869349 0.7958509 0.4182088 -0.3142594 0.8522573 0.1892811 -0.8570447 0.479215 0.3939361 -0.3748314 0.8392353 0.3296074 -0.5978712 0.7306908 0.3671826 -0.4915809 0.7896363 0.4268501 -0.3192372 0.8461008 0.4003779 -0.3794114 0.834113 0.2919815 -0.7021046 0.6494582 0.1896433 -0.8601702 0.473437 0.3342189 -0.6010203 0.7259976 0.4319063 -0.323594 0.8418694 0.3738001 -0.4959688 0.7837656 0.4080145 -0.3845145 0.8280537 0.3396202 -0.6051393 0.7200449 0.4390159 -0.3269196 0.8368922 0.193734 -0.8625255 0.4674581 0.3801793 -0.5006086 0.7777242 0.441881 -0.3295415 0.8343522 0.1948931 -0.8645676 0.4631841 0.4169892 -0.3904066 0.8207939 0.09442704 -0.9399067 0.3281143 0.345017 -0.6092808 0.713961 0.3861885 -0.5054876 0.7715834 0.4487537 -0.3334523 0.8291139 0.3518522 -0.6159626 0.7048336 0.4524824 -0.3356537 0.8261939 0.1968472 -0.8675928 0.4566551 0.393667 -0.5096704 0.7650245 0.4247407 -0.3954419 0.8143839 0.1986453 -0.8704201 0.4504541 0.458983 -0.3405673 0.8205783 0.4312326 -0.4001338 0.8086603 0.4009614 -0.5136383 0.758555 0.3590545 -0.6231037 0.6948537 0.09116125 -0.9443908 0.3159363 0.4645683 -0.3454201 0.8153903 0.1999006 -0.8732454 0.4443898 0.4400572 -0.4058757 0.8010086 0.4721357 -0.3491424 0.8094366 0.2020356 -0.8749179 0.4401141 0.4096049 -0.5203304 0.7493198 0.3641857 -0.6266815 0.6889407 0.475425 -0.3515483 0.8064645 0.2034675 -0.8771046 0.4350732 0.4491176 -0.412037 0.792792 0.3710569 -0.6308699 0.6814103 0.4814138 -0.3552159 0.8012881 0.4195239 -0.5279909 0.7383938 0.4841236 -0.3572559 0.7987444 0.4576573 -0.4174643 0.7850307 0.2064327 -0.8803603 0.4270263 0.3776406 -0.6356776 0.6732769 0.2072549 -0.8822144 0.4227805 0.4258059 -0.533936 0.7304806 0.4887351 -0.3634232 0.7931341 0.4631911 -0.4197927 0.7805306 0.3842372 -0.6398969 0.6655026 0.2088406 -0.8847419 0.4166741 0.4317294 -0.5377237 0.7241982 0.4709351 -0.4256147 0.7727046 0.4988309 -0.3686985 0.7843655 0.2107956 -0.8874657 0.4098414 0.5015862 -0.3705664 0.7817236 0.1071814 -0.9574 0.2681367 0.4403886 -0.5425051 0.7153644 0.4798907 -0.4299911 0.7647305 0.5183091 -0.3740444 0.7690557 0.2128099 -0.8904567 0.4022421 0.3956196 -0.6500577 0.6487759 0.4852001 -0.4378948 0.7568547 0.5735164 -0.3770339 0.7272719 0.4484241 -0.5491692 0.7052158 0.5625904 -0.3837481 0.732277 0.4896566 -0.4436635 0.7505992 0.2140625 -0.8933616 0.3950726 0.3999916 -0.6532443 0.6428676 0.554287 -0.3928717 0.7337696 0.2165321 -0.8957623 0.3882318 0.4949671 -0.4504085 0.7430611 0.3491056 -0.7526264 0.5582821 0.4053829 -0.6567978 0.6358313 0.4565662 -0.5558144 0.6947069 0.5473873 -0.4019342 0.734041 0.2178136 -0.8975008 0.3834704 0.532661 -0.4038372 0.743766 0.5001193 -0.4573007 0.7353618 0.4110642 -0.6617495 0.6269881 0.5348862 -0.412289 0.7375057 0.09158736 -0.409717 0.9076033 0.4603792 -0.5540421 0.6936055 0.1080079 -0.9628852 0.2473592 0.2190346 -0.8998518 0.3772144 0.5283196 -0.4333741 0.7301133 0.4685936 -0.5552074 0.6871424 0.2202547 -0.9020771 0.3711401 0.5968626 -0.4967598 0.6300674 0.4713099 -0.5612198 0.6803672 0.2219036 -0.9043084 0.3646715 0.5936944 -0.5048828 0.6265944 0.420771 -0.669962 0.6116394 0.4737876 -0.56672 0.6740577 0.3615285 -0.7641052 0.5342664 0.475739 -0.5705022 0.6694772 0.5814162 -0.5141219 0.6305822 0.4258306 -0.674041 0.6036034 0.1079468 -0.967462 0.2288337 0.4808301 -0.5775761 0.6597032 0.5759616 -0.5269475 0.6249757 0.5436951 -0.5294122 0.6512439 0.4311457 -0.6781076 0.5952173 0.4829334 -0.582639 0.6536874 0.1530831 -0.9537481 0.2587092 0.1071519 -0.9691284 0.2220557 0.4865435 -0.5871667 0.646924 0.5407485 -0.5380627 0.6465909 0.437312 -0.6825656 0.5855446 0.4931631 -0.5948233 0.6348036 0.3732193 -0.7768052 0.5072291 0.1530544 -0.9559569 0.2504416 0.1066658 -0.9707964 0.2148881 0.5413175 -0.5527011 0.6336378 0.440819 -0.6814627 0.5841981 0.5295396 -0.5545959 0.641881 0.1543676 -0.9583737 0.2401885 0.3775226 -0.77943 0.4999657 0.002533018 -0.5037139 0.8638669 0.1055967 -0.9724667 0.2077448 0.5249344 -0.576207 0.626442 0.4506445 -0.6851531 0.572263 0.5749502 -0.6279314 0.5245326 0.1538158 -0.9601284 0.2334399 0.1052895 -0.9745234 0.1980359 0.452018 -0.6887545 0.5668308 0.5710471 -0.63468 0.5206598 0.4544951 -0.694103 0.5582611 0.5634113 -0.6424861 0.5194029 0.4572107 -0.6992903 0.5495012 0.1026674 -0.9764698 0.1896478 0.5568518 -0.650515 0.516475 0.4595059 -0.7049156 0.5403224 0.101171 -0.9781394 0.1816806 0.4620674 -0.7112299 0.5297601 0.5482453 -0.6586939 0.5153151 0.393606 -0.79356 0.4640443 0.5366215 -0.6672748 0.5165092 0.3973273 -0.7963026 0.4561069 0.09943234 -0.9796438 0.1743881 0.1565318 -0.967207 0.2000213 0.4655777 -0.7178534 0.5176137 0.0965923 -0.980145 0.1731642 0.1559852 -0.9686588 0.1933106 0.5267673 -0.6775644 0.5132472 0.4684073 -0.720953 0.5107069 0.09875971 -0.9810968 0.1664205 0.4727698 -0.7265658 0.4985889 0.1571428 -0.9703241 0.183786 0.5283492 -0.6898266 0.4949612 0.09644156 -0.9824222 0.1598305 0.5151909 -0.6932997 0.5038989 0.4735703 -0.7323447 0.4892878 0.09293073 -0.983815 0.1532061 0.4084743 -0.8022688 0.4353316 0.327897 -0.8814521 0.339891 -0.07290971 -0.5866045 0.806585 0.5107445 -0.7157443 0.476288 0.09235161 -0.9851351 0.144845 0.4146066 -0.8051028 0.4241591 0.5346059 -0.753307 0.3830472 0.4147306 -0.8072429 0.4199494 0.1560148 -0.9750315 0.158029 0.332293 -0.8855144 0.3247242 0.4172903 -0.8093412 0.4133228 0.09055018 -0.9861332 0.1390755 0.5336639 -0.7598134 0.3713307 0.08832347 -0.9871845 0.1329125 0.5287727 -0.7644407 0.3688225 0.5198385 -0.770556 0.3687975 0.2456139 -0.9442768 0.2191237 0.5156892 -0.778188 0.3584524 0.422017 -0.8244408 0.377093 0.5140963 -0.7829402 0.3502997 0.4223 -0.829096 0.3664186 0.5063426 -0.7890717 0.3478263 0.248304 -0.9476512 0.2007551 0.4986307 -0.7984561 0.3373951 0.4258301 -0.8381404 0.3408656 0.4900468 -0.8053712 0.3335138 0.4243704 -0.8443765 0.3270139 0.0899083 -0.994027 0.06186151 0.4808077 -0.8121298 0.3305591 0.1759717 -0.8200417 0.5445784 0.4603852 -0.8279914 0.320118 0.1052302 -0.9935531 0.04217755 0.4736911 -0.8504831 0.2286816 0.10593 -0.993502 0.04162734 0.4653264 -0.8574067 0.2198299 0.3527442 -0.9013015 0.2514501 0.4549442 -0.8624927 0.2216582 0.1064821 -0.993467 0.04104852 0.1067861 -0.9934557 0.04052925 0.4378529 -0.873356 0.2133873 0.1069082 -0.9934867 0.03943061 0.4214665 -0.8804104 0.2173559 0.1067864 -0.9935203 0.03891187 0.1073654 -0.9934816 0.03830116 0.4021846 -0.8880534 0.2227305 0.1077331 -0.993464 0.03772181 0.1077943 -0.9934962 0.03668421 0.1074579 -0.9935506 0.03619569 0.1080996 -0.9934975 0.03573817 0.1086156 -0.9934717 0.03488272 0.1086781 -0.993485 0.0343033 0.1088609 -0.9934818 0.0338149 0 0 1 0 0 1 -1.25301e-5 -2.24733e-5 1 -1.97939e-5 -3.60399e-5 1 0 0 1 0 0 1 4.19151e-6 -5.01415e-5 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 5.98523e-7 4.08157e-6 1 2.34119e-5 -3.30409e-4 1 5.76928e-6 -1.42091e-5 1 -1.09708e-5 1.81214e-4 1 5.63824e-5 -4.71897e-4 1 1.21102e-4 -9.10448e-4 0.9999997 -1.27226e-4 0.001632809 0.9999987 1.06614e-5 -1.05759e-4 1 -2.10824e-5 2.86062e-4 1 -7.75944e-5 9.68001e-4 0.9999996 2.19903e-6 -4.86313e-5 1 -2.11902e-5 1.72575e-4 1 -6.90841e-6 1.20491e-4 1 3.85896e-5 -4.94965e-4 0.9999999 -4.29974e-6 8.92954e-5 1 -3.35986e-6 6.32208e-5 1 -1.62885e-5 2.45866e-4 1 -1.24628e-5 1.76156e-4 1 -3.52381e-6 2.98704e-5 1 7.1065e-6 -1.02922e-4 1 5.76882e-6 -6.71167e-5 1 9.88113e-6 -1.61513e-4 1 -3.6418e-6 5.45963e-5 1 -4.38889e-6 6.7775e-5 1 -8.0784e-6 1.04927e-4 1 6.57982e-7 2.33894e-5 1 -5.25255e-7 3.29767e-5 1 1.31854e-5 -6.20873e-5 1 1.00118e-5 -4.2637e-5 1 -3.9975e-6 3.18842e-5 1 2.36037e-6 -1.11055e-6 1 1.11212e-5 -3.38078e-5 1 -8.15726e-6 5.18335e-5 1 5.4659e-6 -8.58439e-5 1 2.03132e-5 -7.17537e-5 1 0 0 1 0 0 1 0 5.77538e-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 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 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.9693e-7 2.10055e-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 1 1.14258e-5 0 1 -1.54697e-5 0 1 -1.1269e-5 0 1 1.47277e-5 0 1 5.91172e-5 0 1 2.18592e-5 0 1 -3.51454e-5 0 1 -1.76242e-5 0 1 -8.72993e-6 0 1 8.76682e-6 0 1 7.96575e-6 0 1 -9.01925e-6 0 1 -4.31429e-6 0 1 -4.4169e-6 0 1 4.78106e-6 0 1 4.52546e-6 0 1 9.69504e-6 0 1 -9.57847e-6 0 1 -7.46618e-6 0 1 -1.45166e-5 0 1 -1.44345e-5 0 1 1.31611e-5 0 1 9.54441e-6 0 1 1.47775e-5 0 1 7.6717e-5 0 1 -2.66608e-5 0 1 2.89565e-5 0 1 2.86571e-5 0 1 -7.90282e-5 0 1 -2.86348e-5 0 1 4.02342e-5 0 1 -4.22357e-6 0 1 6.83911e-6 0 1 -2.90242e-5 0 1 9.04183e-6 0 1 4.55656e-6 0 1 -3.82031e-5 0 1 -7.33336e-7 0 1 8.24105e-6 0 1 -8.11575e-6 0 1 -8.99257e-6 0 1 -8.69273e-6 0 1 1.52091e-5 0 1 2.97295e-5 0 1 7.51876e-6 0 1 -3.55107e-5 0 1 7.4021e-6 0 1 -2.97007e-5 0 1 7.39581e-6 0 1 -2.75934e-5 0 1 9.13879e-6 0 1 -3.75205e-6 0 1 3.98302e-5 0 1 -1.15527e-5 0 1 1.23634e-5 0 1 4.63054e-5 0 1 8.64394e-6 0 1 7.24977e-6 0 1 -4.51851e-5 0 1 6.99578e-6 0 1 1.65901e-4 0 1 -3.11852e-5 0 1 -4.79307e-5 0 1 -3.05478e-5 0 1 -1.20429e-5 0 1 8.37565e-6 0 1 -1.50519e-5 0 1 6.16058e-5 0 1 3.77485e-5 0 1 -3.7004e-6 0 1 -2.14497e-5 0 1 -2.17137e-5 0 1 9.59113e-6 0 1 9.65809e-6 0 1 -9.47045e-6 0 1 9.40943e-6 0 1 9.15951e-6 0 1 -9.05361e-6 0 1 8.92955e-6 0 1 8.86854e-6 0 1 8.91746e-6 0 1 -1.33395e-5 0 1 1.33238e-5 0 1 2.869e-5 0 1 4.56765e-6 0 1 7.30955e-6 0 1 -4.10456e-5 0 1 -1.15628e-5 0 1 6.58935e-5 0 1 -7.48671e-5 0 1 1.60485e-4 0 1 -8.50598e-5 0 1 5.92921e-5 0 0.9993385 -0.0363698 5.07999e-6 0.9993323 -0.03653967 0 0.9993578 -0.03583508 -1.16161e-4 0.9993164 -0.0369718 2.62861e-5 0.9993289 -0.03662937 8.60301e-5 0.9993373 -0.03640353 -2.98918e-5 0.9993435 -0.03623241 -9.28977e-5 0.9993571 -0.03585255 -2.83047e-4 0.9993125 -0.03707605 -1.68326e-4 0.9993332 -0.03651267 8.38272e-5 0.9993373 -0.03640031 0 0.9993637 -0.03566855 4.40995e-5 -0.698973 -0.7151479 -5.79858e-4 -0.7085246 -0.7056863 0 -0.7251365 -0.6886051 -1.22077e-4 -0.7465026 -0.6653823 -6.71425e-4 0.02175265 -0.9997594 0.002801179 -0.7404619 -0.6720984 0 -0.006810545 -0.9999746 0.002156257 -0.01314997 -0.9999107 -0.002422928 -0.01251405 -0.9999215 -7.17902e-4 -0.053433 -0.9985696 -0.001969575 -0.4830548 -0.8755901 4.27266e-4 -0.4695946 -0.8828819 -7.62973e-4 -0.4334889 -0.9011588 3.96744e-4 -0.07294082 -0.9973363 -2.44153e-4 -0.07010185 -0.9975399 1.22075e-4 -0.0767548 -0.99705 0 -0.08511632 -0.9963708 7.62965e-4 -0.3911956 -0.9203076 1.83115e-4 -0.3878073 -0.9217405 -3.96749e-4 -0.3597908 -0.9330331 2.74673e-4 -0.3469425 -0.9378862 -7.01942e-4 -0.3276492 -0.9447994 4.883e-4 -0.2949565 -0.9555106 4.86613e-4 -0.5272254 -0.8497255 3.05196e-5 -0.5227345 -0.8524954 -5.18828e-4 -0.7555975 -0.6550363 -1.22077e-4 -0.770129 -0.6378881 -3.05195e-4 -0.7844616 -0.6201775 6.10381e-5 -0.7984774 -0.6020244 -7.93503e-4 -0.7982792 -0.6022877 3.66225e-4 -0.8125503 -0.5828913 3.05195e-5 -0.827178 -0.5619402 -2.74668e-4 -0.8461791 -0.5328981 -7.32464e-4 -0.8395923 -0.5432171 0 -0.8503322 -0.5262464 6.10388e-5 -0.8627099 -0.5056991 -1.22076e-4 -0.8760123 -0.482289 3.05188e-5 -0.8849438 -0.4656972 -7.01949e-4 -0.8855919 -0.4644643 3.05187e-4 -0.9039099 -0.4277229 -1.83114e-4 -0.8939934 -0.4480801 6.1038e-5 -0.9176927 -0.3972904 -7.01926e-4 -0.9150508 -0.4033389 9.1557e-5 -0.9208632 -0.3898859 1.22078e-4 -0.9451244 -0.3267101 -7.62985e-4 -0.9270789 -0.3748662 -2.44153e-4 -0.9343885 -0.3562555 -4.57794e-4 -0.9433706 -0.3317407 3.35708e-4 -0.9465907 -0.3224378 3.66233e-4 -0.951031 -0.3090957 9.15568e-5 -0.9562378 -0.2925907 -3.66234e-4 -0.9614156 -0.2751 -1.52596e-4 -0.9680923 -0.2505913 -0.001159667 -0.9638875 -0.2663104 6.10384e-5 -0.9668799 -0.2552323 1.22077e-4 -0.9712154 -0.2382031 -3.05193e-5 -0.9730631 -0.2305394 -2.7467e-4 -0.9748319 -0.2229399 -8.24008e-4 -0.975893 -0.2182384 -0.002227842 -0.9776677 -0.210152 -0.001434326 -0.9778046 -0.2095143 -0.001464903 -0.9820228 -0.1887625 1.83116e-4 -0.9807517 -0.1952592 -2.13632e-4 -0.9826967 -0.1852227 2.44156e-4 -0.9830803 -0.1831755 3.3571e-4 -0.9857436 -0.168253 7.62983e-4 -0.9867712 -0.162117 8.54532e-4 -0.9883862 -0.15196 9.63796e-4 -0.6801198 -0.733101 2.13634e-4 -0.6416692 -0.7669816 3.05193e-4 -0.6548886 -0.7557253 -5.18832e-4 -0.6133149 -0.7898383 -4.88308e-4 -0.6032423 -0.797558 9.15576e-5 -0.5703489 -0.8214025 -4.27273e-4 -0.566253 -0.8242316 -1.22077e-4 -0.426661 -0.9044115 -4.27271e-4 -0.3132781 -0.9496613 -6.10381e-4 -0.2974703 -0.9547311 3.6623e-4 -0.288101 -0.9576001 -3.96749e-4 -0.2751282 -0.9614075 3.05189e-4 -0.2700623 -0.962843 -1.22076e-4 -0.2657486 -0.9640424 4.25026e-4 -0.2616692 -0.9651576 -8.01566e-5 -0.2401219 -0.9707418 -0.001373291 -0.2379298 -0.9712824 -3.96753e-4 -0.2572789 -0.9663372 1.83117e-4 -0.2264237 -0.9740279 -0.001464903 -0.2269898 -0.9738969 -6.34525e-4 -0.2185781 -0.9758191 -8.54536e-4 -0.2037164 -0.9790293 -0.001159727 -0.2100554 -0.977689 -0.001039087 -0.1926712 -0.9812629 -9.94673e-4 -0.1841226 -0.9829031 -6.40904e-4 -0.1860461 -0.9825408 -8.24023e-4 -0.168708 -0.9856661 -3.35707e-4 -0.1668186 -0.9859877 -1.52597e-4 -0.1583605 -0.9873815 -3.98836e-5 -0.1518645 -0.9884013 3.05194e-4 -0.1514678 -0.9884622 2.13636e-4 -0.1378527 -0.9904524 8.54522e-4 -0.1334909 -0.9910499 6.40903e-4 -0.1222277 -0.992501 0.001495361 -0.1113325 -0.9937829 8.24007e-4 -0.103277 -0.9946514 0.001586973 -0.08948177 -0.9959884 4.88304e-4 -0.07226854 -0.9973852 -2.4415e-4 -0.05337733 -0.9985744 -6.10376e-5 -0.05761986 -0.9983383 -8.85052e-4 -0.05856972 -0.9982833 4.81205e-4 -0.04095637 -0.9991589 -0.002075254 -0.0345776 -0.9993943 -0.003936886 -0.0479753 -0.9988451 -0.002655088 -0.03695827 -0.9993091 -0.003936886 -0.02395719 -0.9997029 -0.004486203 -0.02649021 -0.9996399 -0.004303097 -0.02116268 -0.9997683 -0.00395137 -0.01507622 -0.9998838 -0.002319395 -0.01779258 -0.9998362 -0.003326535 -0.005566477 -0.9999825 -0.002035737 0.002130806 -0.9999977 4.34658e-4 0.005882024 -0.9999756 0.003773748 -0.001998543 -0.9999959 0.002074301 0.008698701 -0.9999549 0.003820836 0.004327476 -0.9999781 0.005025863 0.01103705 -0.9999269 0.004928708 0.009482026 -0.9999451 0.004466414 0.01786565 -0.9998367 0.002750694 0.004041373 -0.9999918 -2.24741e-4 0.004781126 -0.9999886 0 0.001048386 -0.9999992 7.25556e-4 -0.001677334 -0.9999983 -7.33896e-4 0.9999985 -0.001767814 0 0.9999858 0.005345821 0 -1.36407e-7 0 1 1.38503e-6 0 1 1.64465e-7 0 1 -4.87075e-7 0 1 3.19168e-7 0 1 -6.23322e-7 0 1 -1.06101e-6 0 1 2.46036e-6 0 1 -5.84522e-7 0 1 1.19166e-6 0 1 -4.2194e-7 0 1 -1.33778e-7 0 1 5.22069e-7 0 1 -1.23709e-7 0 1 7.78972e-7 0 1 0 0 1 0 0 1 1.45532e-7 0 1 1.09948e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 4.81451e-7 0 1 0 0 1 -1.18272e-6 0 1 0.9993312 -0.03656554 4.11544e-4 0.9993174 -0.03694343 9.12935e-5 0.9993508 -0.03602868 0 0.9993722 -0.03542989 -3.76105e-4 0.9993422 -0.03626888 -9.34156e-5 0.9992994 -0.03742015 6.97687e-4 0.9993493 -0.0360704 -1.74339e-4 0.9993645 -0.03564167 -6.43621e-4 0.9993405 -0.03631174 -8.49375e-5 0.9993332 -0.03651213 4.34005e-4 0.9993155 -0.03699576 0 0.9993448 -0.03619098 -6.04617e-4 0.9993399 -0.03632712 3.35189e-4 -0.03632229 -0.9993402 0 -0.03633338 -0.9993398 0 -0.03632813 -0.9993399 8.13775e-6 1 2.10722e-7 0 1 -2.42018e-6 0 1 0 5.22944e-6 -0.03272044 -0.9994646 2.61741e-6 -0.03271728 -0.9994647 0 -0.03271722 -0.9994647 0 -0.03273928 -0.999464 2.1024e-4 -0.03270065 -0.9994653 -1.56664e-4 -0.0327807 -0.9994625 5.50725e-4 -0.03266942 -0.9994662 -3.94801e-4 -0.03271895 -0.9994646 0 -0.03271889 -0.9994646 0 -0.03272736 -0.9994644 -1.43849e-4 -0.03272557 -0.9994644 0 -0.03271484 -0.9994648 0 -0.03271985 -0.9994646 2.04872e-6 -0.03272122 -0.9994646 2.07529e-5 -0.03272008 -0.9994646 2.18374e-4 -0.03273504 -0.9994642 0 -0.03272324 -0.9994645 -4.36143e-5 -0.03271865 -0.9994647 8.50952e-5 -0.03269261 -0.9994654 2.36554e-4 -0.03274154 -0.9994639 -1.58519e-4 -0.03270763 -0.9994651 7.99785e-5 -0.03275382 -0.9994634 -2.24486e-4 -0.0326513 -0.9994668 3.46665e-4 -0.03274464 -0.9994637 -1.43268e-4 -0.03281259 -0.9994615 -4.39376e-4 -0.03273594 -0.999464 -3.49341e-5 -0.03275936 -0.9994633 -2.28162e-4 -0.03260058 -0.9994684 5.59561e-4 -0.03259074 -0.9994688 -2.28573e-4 -0.03272277 -0.9994645 0 -0.03272807 -0.9994643 1.28375e-6 -0.03277367 -0.9994628 9.66299e-5 -0.03281116 -0.9994617 1.58368e-4 -0.03265923 -0.9994666 -8.84719e-5 -0.03265714 -0.9994666 -1.37357e-4 -0.03274959 -0.9994636 1.07504e-4 -0.03266209 -0.9994665 -1.40651e-4 -0.03259509 -0.9994687 -2.51222e-4 -0.03277063 -0.999463 8.51912e-5 -0.03272944 -0.9994643 0 -0.03272294 -0.9994645 0 -0.03276312 -0.9994632 -1.08196e-5 -0.03248381 -0.999472 -7.43655e-4 -0.03271001 -0.9994649 -6.19708e-5 -0.03286892 -0.9994596 4.66601e-4 -0.03279167 -0.9994622 2.25185e-4 -0.03272134 -0.9994646 5.16092e-5 -0.03272962 -0.9994643 3.62322e-5 -0.03271067 -0.9994649 -7.94235e-5 -0.03269273 -0.9994655 -1.55792e-4 -0.03270584 -0.9994651 -6.64074e-5 -0.03269976 -0.9994653 -1.68241e-4 -0.03274542 -0.9994637 1.17284e-4 -0.03271383 -0.9994648 -7.85475e-5 -0.03271853 -0.9994646 2.69776e-5 -0.03271448 -0.9994648 -1.52021e-4 -0.03273296 -0.9994642 2.05823e-4 -0.03272074 -0.9994645 7.50184e-5 -0.0327183 -0.9994646 5.66324e-6 -0.03271847 -0.9994646 3.45206e-6 -0.03271943 -0.9994646 -1.47049e-5 -0.03272485 -0.9994644 -3.5562e-5 -0.03272068 -0.9994646 2.71473e-5 -0.03271585 -0.9994648 -2.0995e-5 -0.03271907 -0.9994646 -4.34153e-5 0.6553964 2.74671e-4 -0.7552852 0.6668172 -1.22077e-4 -0.7452214 0.5417166 -3.35712e-4 -0.8405611 0.515254 3.3571e-4 -0.8570374 0.4003481 -1.52595e-4 -0.9163632 0.3825297 1.22077e-4 -0.9239432 0.2450697 6.10385e-5 -0.9695055 0.251695 9.15588e-5 -0.9678067 0.1235727 -1.52597e-4 -0.9923356 0.1093495 3.0519e-5 -0.9940034 0.06781327 -3.96748e-4 -0.997698 0.04773187 0 -0.9988602 0.7737533 9.15576e-5 -0.6334871 0.7775468 -9.15587e-5 -0.628825 0.8553041 9.1558e-5 -0.5181266 0.8644888 -1.83116e-4 -0.5026523 0.9096544 2.13634e-4 -0.4153659 0.9226131 -2.4415e-4 -0.3857268 0.951308 3.0519e-4 -0.308242 0.9629368 -2.74671e-4 -0.2697273 0.9896903 -1.83112e-4 -0.1432241 0.9851391 3.66223e-4 -0.1717584 0.995395 3.66223e-4 -0.09585893 0.9969934 -1.22076e-4 -0.07748764 0.06281071 0.9980229 0.002241969 -0.1845771 -0.8811972 0.4352273 -0.240647 -0.7737938 0.5859457 -0.2275818 -0.8687296 0.439904 0.0628463 0.998023 5.98479e-4 0.06622701 0.9970681 0.03833234 0.06735569 0.9968768 0.04123133 0.06460797 0.9976854 0.02121043 0.07178133 0.9907478 0.1151798 0.072178 0.9889459 0.1295237 0.07626724 0.9814032 0.1761563 0.07120048 0.9937555 0.08591061 0.06979751 0.9950497 0.07074362 0.07364195 0.9833478 0.1661446 0.07425272 0.9812773 0.1777121 0.0673179 0.9977282 -0.002598881 0.0920161 0.7835254 0.6145088 0.09372311 0.7979741 0.59536 0.09161812 0.7974624 0.5963724 0.09085619 0.8734341 0.4783912 0.0960741 0.8068334 0.5829148 0.06656396 0.9977734 -0.004199206 0.09888297 0.8183176 0.5661966 0.1038565 0.7576978 0.6442888 0.1006218 0.8322285 0.5452258 0.07333678 0.9942734 0.07773149 0.06885164 0.997067 0.03341865 0.07733464 0.9847811 0.1556459 0.09152632 0.8120178 0.5764115 0.06145989 0.9980477 -0.01111918 0.04882788 0.7221047 0.6900584 0.06341373 0.9979742 -0.005127608 0.06768542 0.9977059 -0.00125426 0.06219321 0.9980641 2.64627e-4 0.06145209 0.9981094 -0.001130461 0.06790459 0.9961985 0.05456781 0.06737959 0.9977273 -3.30174e-4 0.06758272 0.9977136 -3.21988e-4 0.07144516 0.9923284 0.1008961 0.07263642 0.9871838 0.1420988 0.07312399 0.9852514 0.1547018 0.06746184 0.9977217 -6.98282e-4 0.0675708 0.9977144 -3.84979e-4 0.06759238 0.997713 1.13155e-4 0.06702989 0.9977497 -0.001608192 0.06754189 0.9977162 -8.13778e-4 0.06740081 0.997726 -3.52803e-4 0.06747555 0.9977208 -6.70666e-4 0.06726002 0.9977355 1.53822e-5 0.0674467 0.9977227 -5.66185e-4 0.06740862 0.9977254 -4.44241e-4 0.06747049 0.9977211 -6.98447e-4 0.06740915 0.9977253 -4.3548e-4 0.06741702 0.9977249 -4.23745e-4 0.06744551 0.9977228 -5.68059e-4 0.0674743 0.9977208 -7.29202e-4 0.06749576 0.9977192 -8.7864e-4 0.06743371 0.9977237 -4.73141e-4 0.06743776 0.9977235 -4.45301e-4 0.06747573 0.9977206 -7.7523e-4 0.06748133 0.9977201 -9.20422e-4 0.0674498 0.9977226 -5.03981e-4 0.06741565 0.9977251 -1.58625e-4 0.0673877 0.9977269 2.55347e-4 0.06730258 0.9977319 0.001218736 0.06706744 0.9977474 -0.001471877 0.06726628 0.9977349 -7.41312e-4 0.06745797 0.9977222 -1.27651e-4 0.06729423 0.997733 -6.27611e-4 0.06728947 0.9977333 -6.91225e-4 0.0674234 0.9977244 -4.33165e-4 0.06720697 0.9977387 -8.53293e-4 0.06727123 0.9977345 -6.88481e-4 0.06728297 0.9977337 -6.80599e-4 0.06732583 0.9977309 -6.27207e-4 0.06718784 0.99774 -8.29842e-4 0.06721794 0.997738 -7.95468e-4 0.0674799 0.9977206 -4.83404e-4 0.06715655 0.9977421 -8.43842e-4 0.06665271 0.9977761 -5.3565e-4 0.06753194 0.9977171 -4.27066e-4 0.06680572 0.9977661 7.93011e-6 0.0668835 0.9977602 -0.001093089 0.06678915 0.9977671 3.80454e-4 0.06681168 0.9977657 -8.66526e-5 0.06679457 0.9977667 3.02057e-4 0.06680005 0.9977664 6.94979e-5 0.06679856 0.9977665 0 0.07510679 0.978464 0.1922686 0.07635945 0.9744834 0.2110719 0.07788592 0.9698816 0.230789 0.07944118 0.9653801 0.248456 0.08130353 0.9584605 0.2733924 0.08502626 0.9358687 0.3419362 0.08069354 0.9616692 0.2620708 0.08151692 0.9537267 0.2894141 0.08185142 0.9481277 0.3071718 0.07770073 0.9825516 0.1689824 0.08243149 0.941599 0.3264909 0.08304274 0.9360241 0.3419982 0.06885051 0.9961965 0.05340796 0.08368343 0.9309859 0.3553342 0.08453673 0.9251742 0.3700086 0.08588087 0.9172531 0.3889361 0.08734536 0.9092829 0.4069097 0.0881381 0.9007607 0.4252787 0.09232074 0.8792597 0.4673108 0.08878016 0.8730303 0.4795166 0.0892384 0.8663207 0.4914522 0.09018474 0.8567706 0.5077509 0.09064233 0.8530759 0.5138537 0.08972603 0.8609429 0.5007263 0.08594268 0.9396933 0.3310443 0.08804845 0.9430803 0.3206979 0.1029097 0.8035321 0.5862985 0.09949141 0.8623099 0.4965111 0.09561669 0.8958917 0.4338612 0.09161859 0.7004764 0.7077704 0.09305369 0.7414999 0.6644689 0.09189254 0.7375822 0.6689755 0.09143584 0.8292404 0.551362 0.09177035 0.8220267 0.5620057 0.09195518 0.8264675 0.555424 0.09058082 0.8353705 0.5421729 0.09176993 0.826712 0.5550908 0.09256613 0.820504 0.5640965 0.09347915 0.7641916 0.6381794 0.09793663 0.7233395 0.6835118 0.1013839 0.7387415 0.6663201 0.09366446 0.7435474 0.6620908 0.1066346 0.6868074 0.7189748 0.1054121 0.6722086 0.7328191 0.1069687 0.659849 0.7437454 0.09091627 0.7320914 0.6751123 0.09015285 0.7247633 0.6830745 0.08167046 0.9116514 0.4027674 0.0941202 0.8193711 0.5654844 0.08603364 0.8397974 0.5360396 0.08963501 0.7163174 0.6919935 0.105443 0.5749771 0.8113465 0.1066336 0.6318666 0.7677069 0.08923727 0.7055359 0.7030333 0.08899384 0.6922049 0.716193 0.08948326 0.6649901 0.7414721 0.09402894 0.6153848 0.7825983 0.09808868 0.6291532 0.7710675 0.09442514 0.7120035 0.695798 0.08865785 0.656404 0.749182 0.0899403 0.6079136 0.7888929 0.08771294 0.6488133 0.7558755 0.08527064 0.6013198 0.7944453 0.08594292 0.6461589 0.7583486 0.09668499 0.5241072 0.8461465 0.1014773 0.5464514 0.8313203 0.08466035 0.6413617 0.7625535 0.08313542 0.6298334 0.7722684 0.08200579 0.614601 0.784564 0.08115142 0.5969316 0.7981774 0.07861679 0.8526691 0.5165027 0.08719205 0.7846372 0.6137931 0.07779258 0.8277026 0.5557488 0.0805391 0.5613629 0.8236415 0.07944202 0.5566743 0.8269237 0.0773366 0.5520384 0.8302245 0.07644999 0.4999922 0.8626491 0.09915572 0.4323301 0.8962471 0.09366422 0.4073128 0.9084731 0.08676588 0.7617273 0.6420617 0.1007735 0.340927 0.934673 0.1023324 0.3279948 0.9391207 0.1033068 0.3606734 0.9269533 0.07574814 0.5442151 0.8355191 0.0921368 0.5082938 0.8562408 0.08862757 0.3899737 0.916551 0.07788401 0.8062769 0.5863887 0.07410007 0.5304198 0.8444904 0.08755868 0.4995943 0.8618231 0.07269668 0.5136684 0.8549035 0.08493536 0.7361882 0.6714261 0.07242214 0.5111057 0.8564614 0.069705 0.4864091 0.8709464 0.07074266 0.3806614 0.9220046 0.06445592 0.2474778 0.9667473 0.0712617 0.2442736 0.9670844 0.06848478 0.5060978 0.8597528 0.08154809 0.4974679 0.8636409 0.06698954 0.4510732 0.8899694 0.08365225 0.3799601 0.9212127 0.07898449 0.7707092 0.6322727 0.08264523 0.6992499 0.7100841 0.06528019 0.438589 0.8963136 0.06558465 0.3883809 0.9191621 0.07907426 0.7237237 0.6855446 0.09079521 0.1187205 0.9887678 0.09427267 0.1630927 0.9820966 0.09686744 0.1680684 0.9810045 0.0637238 0.4237878 0.9035172 0.07733666 0.3771613 0.922913 0.06033629 0.3830152 0.9217694 0.06079393 0.4241539 0.9035473 0.08072292 0.6546341 0.7516236 0.07806873 0.6755176 0.7331994 0.05878013 0.4040142 0.9128622 0.07794475 0.2481476 0.9655814 0.05758988 0.3833529 0.9218048 0.05569791 0.3389792 0.9391437 0.07867807 0.6143484 0.7851024 0.05408036 0.2679604 0.9619109 0.05438429 0.3285031 0.9429359 0.07770222 0.6237847 0.7777243 0.04959416 0.2703417 0.9614863 0.07022333 0.1042516 0.9920688 0.05139321 0.3233441 0.944885 0.07681614 0.5753734 0.8142756 0.04937952 0.3058907 0.9507852 0.07681602 0.04464912 0.9960451 0.07382452 0.02270585 0.9970127 0.08032572 0.05212628 0.9954048 0.07648086 0.5692729 0.8185836 0.06311351 0.09799683 0.9931835 0.07675594 0.5363458 0.8405009 0.04794609 0.2878293 0.9564808 0.07587069 0.4967913 0.8645474 0.0461139 0.2312104 0.9718103 0.06640893 0.004577815 0.9977821 0.06918591 0.02243125 0.9973516 0.07159692 0.02014231 0.9972304 0.04065144 0.1257387 0.9912303 0.04471033 0.2200115 0.9744722 0.06415086 0.01104784 0.997879 0.07510703 0.5151594 0.8537973 0.05868744 0.256052 0.9648799 0.08380436 0.1317188 0.9877384 0.08444583 0.1437441 0.9860054 0.08468967 0.1400203 0.9865202 0.03830152 0.1327584 0.9904082 0.04336744 0.2167457 0.9752644 0.078799 0.4728859 0.8775932 0.07687777 0.4395676 0.8949136 0.0772733 0.04602217 0.9959473 0.07568788 0.4478098 0.8909197 0.05609399 0.09918689 0.9934866 0.05700927 0.004181087 0.998365 0.07763981 0.4156051 0.9062255 0.03360128 0.1187795 0.992352 0.0315265 0.02313369 0.9992353 0.04193276 0.2103659 0.976723 0.07315504 0.4666116 0.8814318 0.074009 0.04834234 0.9960852 0.0787099 0.08438652 0.9933196 0.04058998 0.2009054 0.9787694 0.06177067 -0.006836235 0.998067 0.07666498 0.3726433 0.9248024 0.07574814 0.3634203 0.9285408 0.05020356 0.004089474 0.9987307 0.04992878 0.105412 0.9931745 0.0448634 0.1148747 0.9923665 0.07391792 0.3254892 0.9426521 0.07895344 0.1617523 0.9836679 0.07901352 0.1608653 0.9838085 0.07898247 0.1312611 0.9881966 0.03915601 0.187601 0.9814646 0.07892316 0.1623022 0.9835798 0.0752905 0.2735423 0.9589087 0.07324695 0.2538006 0.9644792 0.07294112 0.3712063 0.9256811 0.07266569 0.4214367 0.9039419 0.03906404 0.186714 0.9816374 0.07489371 0.1532972 0.9853381 0.07892203 0.1653212 0.983077 0.0737943 0.117192 0.9903638 0.04968488 -0.01568675 0.9986418 0.04470992 0.007812738 0.9989695 0.03961354 0.01318413 0.9991281 0.03766059 0.1859835 0.9818309 0.07440501 0.08636838 0.993481 0.07471179 0.2575237 0.9633793 0.07303136 0.3223696 0.9437925 0.07425218 0.1557984 0.9849942 0.07434451 0.154335 0.9852175 0.0742228 0.1574487 0.9847339 0.02821499 1.48838e-4 0.9996019 0.03671455 0.1782625 0.9832978 0.03720241 0.1827161 0.9824617 0.07086527 0.1323612 0.9886652 0.07016241 0.1337329 0.9885307 0.0702542 0.1092877 0.9915244 0.0713849 0.1292192 0.9890432 0.07107824 0.132543 0.9886254 0.06793558 0.09210675 0.993429 0.06827139 0.1213748 0.9902561 0.06878894 0.1158792 0.9908785 0.06903517 0.1146923 0.9909995 0.06711208 0.111884 0.9914525 0.06582868 0.07181036 0.9952437 0.05948185 0.01791471 0.9980687 0.05829203 0.004364252 0.9982901 0.05597168 0.00338757 0.9984267 0.05639946 -0.008179128 0.9983748 0.05496484 -0.007171928 0.9984626 0.07196462 0.1388325 0.9876977 0.0716899 0.1580291 0.9848287 0.07165968 0.156107 0.9851374 0.03640919 0.1747825 0.9839336 0.03381514 0.1163388 0.9926338 0.03537178 0.08713245 0.9955686 0.03589075 0.1736246 0.9841578 0.03582936 0.177621 0.9834465 0.03567665 0.1798484 0.9830472 0.03512758 0.1790866 0.9832061 0.03372389 -0.005188286 0.9994178 0.02884018 -0.002929747 0.9995798 0.03302109 -0.001403808 0.9994537 -0.006286799 0.008911371 0.9999406 -0.0476405 0.01113951 0.9988025 -0.005340874 0.01480185 0.9998763 -0.1362974 0.1083726 0.9847226 -0.1261041 0.05499505 0.9904915 -0.1355343 0.0474568 0.9896355 0.03360098 -0.2001413 0.9791908 0.0346086 -0.2321583 0.9720621 0.04513734 -0.05694818 0.9973563 -0.1603496 -0.182873 0.9699719 -0.1469787 -0.06625634 0.9869182 -0.09024572 0.03155696 0.9954195 -0.04843342 0.01590031 0.9986999 -0.1026958 0.005035579 0.9947001 -0.1043745 0.006256341 0.9945184 -0.1513755 -0.01666349 0.9883359 -0.1489026 -0.01367253 0.9887574 -0.1535717 -0.02020359 0.9879311 -0.1112126 -0.08762109 0.9899265 -0.1738661 -0.322249 0.9305516 -0.1008654 0.004577815 0.9948896 -0.1454839 -0.007385551 0.989333 -0.1468589 -0.01062071 0.9891004 -0.4919744 -0.5126667 0.7036578 -0.7282365 -0.4585735 0.5092956 -0.5163905 -0.5608879 0.6471056 -0.004089534 0.02224838 0.9997442 0.04239118 0.01040703 0.999047 0.02578824 0.01553398 0.9995468 0.04541182 0.0155645 0.9988472 -0.1571747 -0.01046812 0.9875153 -0.1602882 -0.008942186 0.9870298 -0.01007121 -0.02038669 0.9997416 0.02853488 0.0227974 0.9993328 0.04248231 -0.2201941 0.9745306 0.03793495 -0.1496035 0.9880182 0.04049891 -0.2412234 0.9696242 -0.09857547 0.0032655 0.9951242 -0.0473352 0.005798637 0.9988623 -0.09787482 0.001190245 0.995198 -0.1645895 -0.00552392 0.9863468 -0.1627562 -0.007324457 0.9866392 0.03149521 -0.0167852 0.999363 0.02905428 -0.004944086 0.9995656 0.03247183 -0.07980626 0.9962814 -0.007080256 0.002563536 0.9999718 -0.1440186 3.66227e-4 0.989575 -0.1442317 -0.002441465 0.989541 -0.002471983 0.2574567 0.9662867 0.00991857 0.11414 0.9934152 0.02771162 0.1218945 0.9921562 0.03518831 0.1413637 0.9893323 0.03549313 0.2014535 0.9788548 0.03537195 0.2056093 0.9779947 -0.1435317 -5.18826e-4 0.9896457 -0.1424937 -3.96748e-4 0.9897957 0.01562571 0.2705817 0.9625702 0.03637915 0.1316304 0.9906311 -0.02835255 0.2480926 0.9683213 -0.06231933 0.2417697 0.9683305 -0.01757884 0.1082503 0.9939683 0.03775227 0.1412735 0.9892506 0.0268566 0.2874878 0.9574077 0.0347616 0.2175425 0.9754317 0.03427302 0.22279 0.9742639 -0.03610384 0.3816694 0.9235935 -0.06668376 0.3766335 0.9239592 -0.01165819 0.3896046 0.9209085 -0.1406947 0.01565647 0.9899293 -0.09854644 0.0170297 0.9949868 -0.1368796 0.0990355 0.9856247 0.03341889 0.2285304 0.9729632 0.03241151 0.2324353 0.9720717 -0.05499488 0.1040386 0.9930517 -0.101048 0.1011396 0.9897273 -0.1304689 0.230144 0.9643712 0.03250283 0.3046114 0.951922 0.03238052 0.2355446 0.971324 0.03512692 0.2895607 0.9565149 -0.1472851 0.1496351 0.9777098 0.0350055 0.3018348 0.9527174 0.03442519 0.3291757 0.943641 0.03479194 0.3146535 0.9485689 -0.1029707 0.2375895 0.9658926 -0.1318407 0.2836102 0.9498333 0.006866812 0.4013888 0.915882 -0.01800626 0.5114697 0.8591127 0.0338146 0.3464169 0.937471 0.03323572 0.3577498 0.9332259 -0.1437454 0.2521192 0.9569604 0.03259414 0.3685767 0.9290258 -0.1231162 0.2986652 0.9463835 -0.100926 0.3731852 0.9222509 -0.1187795 0.3965015 0.9103176 -0.1213746 0.360126 0.9249745 -0.02160745 0.6231079 0.7818375 5.49343e-4 0.5196477 0.8543805 -0.06030642 0.7271264 0.6838498 -0.06573915 0.6209514 0.7810876 -0.04232949 0.6212092 0.7825008 0.03134268 0.4591233 0.8878195 0.02819955 0.4347742 0.900098 0.03213614 0.4375459 0.8986217 -0.114874 0.432151 0.8944549 0.03012198 0.4778928 0.8779017 -0.04068142 0.7253381 0.6871897 -0.1120064 0.4891963 0.8649518 -0.1130123 0.4619374 0.879683 -0.09521961 0.5025889 0.8592659 -0.04077363 0.5064358 0.8613132 -0.07519829 0.7300096 0.6792873 -0.08679646 0.6221328 0.7780856 0.02386617 0.5543239 0.8319589 -0.05154645 0.8192811 0.5710705 -0.003540158 0.6271333 0.7789039 -0.02240121 0.7244387 0.6889752 -0.1021185 0.5616214 0.8210684 -0.1065415 0.5386589 0.8357605 0.02752858 0.5755369 0.8173124 0.02865749 0.5621325 0.8265506 -0.09973806 0.5813069 0.8075487 -0.03573787 0.8162032 0.5766586 -0.1002544 0.6132765 0.7834801 0.0257883 0.5884315 0.8081358 0.01196366 0.6337707 0.7734286 -0.09354102 0.6562826 0.7486944 -0.09723454 0.6376401 0.7641732 0.02017337 0.6290684 0.7770882 0.02560573 0.6049863 0.7958242 -0.03927791 0.8954578 0.4434105 0.02694839 0.6438013 0.7647181 0.02609336 0.6568208 0.7535952 -0.08569657 0.6933246 0.7155117 -0.08816832 0.6764457 0.7311961 -0.02725315 0.892121 0.450974 -0.02029496 0.8133555 0.5814129 -0.06064146 0.8231314 0.5646039 -0.07269674 0.7796744 0.6219511 -0.08700996 0.7188472 0.6897014 -0.08517825 0.7334304 0.6744068 0.009796559 0.725682 0.6879605 -0.08258622 0.7469388 0.659744 0.02310305 0.6726132 0.7396335 0.01821976 0.684265 0.7290058 -0.07950145 0.7583615 0.6469679 -0.005340814 0.8104696 0.5857563 -0.01504594 0.8884459 0.4587348 -0.02359145 0.953029 0.3019588 -0.07208633 0.8078735 0.5849308 -0.0722692 0.7946258 0.6027827 -0.07077491 0.8197259 0.5683665 0.01764011 0.734722 0.6781392 0.01693832 0.7485839 0.6628239 -0.04513829 0.8960524 0.4416476 -0.05401891 0.8629602 0.5023761 -0.01513755 0.950432 0.3105643 -0.06805789 0.8314662 0.5513911 0.01580888 0.7606591 0.6489591 0.01620584 0.773853 0.633158 0.008759081 0.8073965 0.5899443 0.01644986 0.7872149 0.6164594 -0.06366223 0.843845 0.5327973 0.01651084 0.8003961 0.5992442 0.01635831 0.8139812 0.5806609 -0.05832165 0.854316 0.5164716 0.01562577 0.8283489 0.5599946 -0.006378471 0.947223 0.3205121 -0.002685606 0.8840111 0.4674583 9.76621e-4 0.9878216 0.1555879 -0.05441552 0.8862743 0.4599532 -0.0528295 0.8979184 0.4369802 0.01574778 0.8567289 0.5155267 0.009186148 0.8785179 0.4776212 0.01495426 0.8417451 0.5396679 -0.04925841 0.9074361 0.417293 -0.03122103 0.9328168 0.3589963 -0.04324555 0.9164584 0.3977861 0.002716183 0.9430658 0.3325954 0.006439507 0.9865339 0.1634304 0.0114445 0.9377172 0.3472111 -0.03399819 0.9255511 0.3770933 0.01626646 0.8848006 0.4656861 0.01568686 0.8978775 0.439966 0.0114752 0.9993498 0.03418141 -0.003936886 0.9887476 0.149542 0.01458787 0.9992104 0.03695803 -0.02694785 0.9529426 0.3019508 -0.03116017 0.9579697 0.2851722 -0.03439474 0.9499612 0.3104686 0.01547306 0.9101645 0.413958 0.01657158 0.9218767 0.387129 -0.02395766 0.9652059 0.2603914 -0.01855581 0.9706096 0.2399438 0.002471983 0.9972251 0.07440429 -0.001892149 0.9944913 0.1048021 -0.004547297 0.9932742 0.1156978 0.01730418 0.9329327 0.3596349 0.01763975 0.9430564 0.3321648 0.01837217 0.9990559 0.03936892 0.01208561 0.984856 0.1729525 -0.005737602 0.9886088 0.1503986 -0.0112003 0.9810808 0.1932741 -0.01428282 0.976117 0.2167758 -0.01059007 0.9900659 0.1402041 0.01715177 0.9533603 0.3013471 -0.01202452 0.9859506 0.1666038 0.01513725 0.9998854 2.74669e-4 0.01300096 0.9999155 1.52594e-4 0.0179758 0.9656893 0.2590777 0.01663285 0.9827743 0.1840603 0.01986801 0.9895875 0.1425555 0.02032548 0.9787371 0.2041096 0.02127164 0.9988838 0.04217708 0.02322494 0.9987342 0.04461872 0.02085858 0.9997825 1.09888e-4 0.02069181 0.9961692 0.08496475 0.02496457 0.9992545 0.02945083 0.02365458 0.9997203 7.58641e-5 0.01694446 0.9998539 0.002278685 0.01815891 0.7028582 0.7110983 -0.612148 -0.02401834 0.7903784 -0.6215808 -0.05060052 0.7817142 -0.3964418 -0.09021413 0.9136167 -0.005554497 0.7245012 0.6892513 -9.15555e-5 -1 0 -0.00100708 -0.9999976 0.001983702 -0.2917011 -0.01181083 0.9564367 0.01532047 0.531579 0.8468703 0.02923762 0.5496859 0.8348597 -0.1099911 0.5129665 0.8513327 0.02890175 0.4978007 0.8668098 0.03244203 0.4014514 0.9153056 0.03241127 0.4182341 0.9077609 0.03225922 0.3821061 0.9235553 -0.1210077 0.3243861 0.938153 0.02017295 0.4174976 0.9084541 -0.1449357 0.1982223 0.9693821 -0.153452 0.1013857 0.9829413 -0.1532647 0.04303127 0.9872478 -0.06784391 0.503687 0.8612182 -0.1602552 -0.007751822 0.9870453 -0.1574157 0.003631711 0.9875258 -0.1619022 -0.009155631 0.9867644 0.035097 0.2122607 0.9765827 -0.04889184 0.01748752 0.998651 -0.1698399 -5.41648e-5 0.9854717 -0.009216606 0.01812809 0.9997932 0.03570681 0.1857978 0.981939 0.03470045 0.1757608 0.9838212 -0.1651407 -0.002685666 0.9862664 0.1020544 0.1311998 0.9860891 0.04019397 0.006073296 0.9991735 0.04657161 0.003296017 0.9989095 0.04892158 0.005493342 0.9987876 0.04239088 -5.49342e-4 0.9991011 -0.1438675 0.03915607 0.988822 -0.08993834 0.07477056 0.9931368 -0.1437131 -0.01654118 0.9894812 0.02548313 -0.1703555 0.9850531 0.005920708 -0.1503686 0.9886124 0.01055973 -0.314809 0.9490964 -0.1069679 0.007080316 0.9942373 -0.149635 -0.01452702 0.9886347 0.04886132 -0.953117 0.2986311 0.04892194 -0.9258248 0.3747735 0.04242157 -0.9785345 0.2016703 -0.1475307 0.009552538 0.9890115 -0.1579983 0.01474076 0.9873294 -0.1649532 7.93484e-4 0.9863011 -0.2590434 0.930182 0.2601116 -0.1560738 -5.49341e-4 0.9877452 -0.1418232 0.02795565 0.9894972 -0.3981882 -0.02829158 0.9168674 -0.6052483 -0.004974544 0.7960212 -0.5972702 -0.6003221 0.5318665 -0.3317701 -0.00665307 0.9433368 -0.4258022 -0.8184912 0.3857001 -0.6409042 -0.2165951 0.7364295 -0.3904321 -0.01223814 0.9205504 -0.5032587 -0.3397072 0.7945626 -0.5109239 -0.4081653 0.7565433 -0.09819591 3.12605e-6 0.9951672 -0.1595848 -0.02938997 0.9867467 -0.1538143 -0.1115154 0.9817869 -0.1796954 -0.2295938 0.9565544 -0.11991 -0.02560561 0.9924546 -0.1927899 -0.3162403 0.9288833 -0.1919665 -0.209149 0.9588564 -0.2438507 -0.07526105 0.9668881 -0.2295058 -0.03027522 0.9728363 -0.2017003 -0.3988839 0.8945438 -0.2802256 -0.01818931 0.9597619 -0.30305 3.05186e-5 0.9529747 -0.1911115 0.004059016 0.98156 6.10389e-5 -0.9999999 -4.57792e-4 -2.44148e-4 -1 0 -0.458636 -0.1884533 0.8684115 -0.4906567 -0.2738791 0.8271918 -0.5136659 -0.4853442 0.7075228 -0.5109478 -0.5478146 0.6624437 -0.5041521 -0.6042561 0.6170133 -0.4935909 -0.6565342 0.5703778 -0.4794594 -0.705791 0.521515 -0.462332 -0.7503702 0.4724339 -0.1518608 -0.09009104 0.9842876 -0.6045287 -0.6254956 0.4932549 -0.5964453 -0.6569353 0.4611823 -0.5862079 -0.6882022 0.4274789 -0.5741238 -0.718021 0.3934817 -0.1383718 -0.005951106 0.9903625 -0.6311084 -0.07761055 0.7718024 -0.6395826 -0.1033061 0.7617493 -0.3973272 -0.1565931 0.9042177 -0.6635591 -0.1782349 0.7265822 -0.6704468 -0.2017627 0.7139979 -0.4003428 -0.216804 0.8903492 -0.007477045 -0.9976536 0.06805652 0.1431359 -0.09900486 -0.9847387 -0.1577529 0.002929806 0.9874743 -0.6482356 -0.1292809 0.7503846 -0.1652003 0.002105772 0.9862578 0.1474283 -0.1340494 -0.9799467 -0.1534198 -0.011994 0.9880884 -0.05755817 -0.02276688 0.9980826 -0.0506609 0.02313309 0.998448 -0.1098692 0.007233023 0.9939198 -0.1481406 -0.01260441 0.9888861 -0.06348031 -0.9435071 0.3252147 -0.07257401 -0.8774192 0.4742031 -0.1033392 -0.8791158 0.4652706 -0.05868917 -0.426359 0.9026482 -0.0363484 -0.5628054 0.8257898 -0.02548384 -0.4323713 0.9013355 -0.04947185 0.02063107 0.9985625 -0.06918746 -0.5597566 0.8257638 -0.04349046 -0.6828463 0.7292665 -0.3650413 -0.7572447 0.5415953 -0.3506071 -0.8084289 0.4727763 -0.3461227 -0.8097154 0.4738777 -0.322197 -0.8105129 0.48914 -0.3181962 -0.8094683 0.4934696 -0.4745417 -0.6610134 0.5812671 -0.5828614 -0.7852667 0.2088754 -0.4718318 -0.6883373 0.5509689 -0.5810928 -0.7619518 0.2859379 -0.4429243 -0.6803326 0.5839227 -0.4616038 -0.7584341 0.4601083 -0.4646576 -0.7408274 0.4850445 -0.4685387 -0.7155042 0.5181943 -0.4472016 -0.824941 0.3456634 -0.4450945 -0.8336977 0.3268625 -0.4498895 -0.8138358 0.3677918 -0.4526598 -0.801707 0.3903397 -0.5784072 -0.8048625 0.1328212 -0.4467982 -0.8417751 0.3029621 -0.4495161 -0.8519717 0.2684767 -0.4538518 -0.8427891 0.289353 -0.7166518 -0.6872313 0.1188417 -0.441524 -0.8681545 0.226637 -0.4381035 -0.8747421 0.2071034 -0.4454042 -0.860472 0.2473925 -0.4349862 -0.8805932 0.1879966 -0.4319992 -0.8860638 0.1681302 -0.5689668 -0.8200166 0.06204521 -0.7081389 -0.7026149 0.06979757 -0.7031947 -0.7096037 0.04449707 -0.4306222 -0.8906646 0.1458805 -0.4219944 -0.9024339 0.08679771 -0.4255623 -0.8985518 0.1072451 -0.4295002 -0.8940368 0.1273882 -0.4134103 -0.9101985 0.02511709 -0.4162465 -0.9081186 0.04538148 -0.6943078 -0.7196691 0.003631711 -0.5613663 -0.8274615 0.01324522 -0.6977899 -0.7160404 0.01937961 -0.4089822 -0.9125422 -4.88301e-4 -0.4103281 -0.9119081 0.007385551 -0.3771887 -0.9128644 0.1562286 -0.3574374 -0.9320779 0.05890148 -0.3775858 -0.9256222 0.0255447 -0.5387143 -0.8409399 0.05105757 -0.3687003 -0.8451939 0.3869202 -0.3866837 -0.8663608 0.3160613 -0.5757468 -0.7960658 0.186534 -0.5778547 -0.737746 0.3490201 -0.1568996 -0.1455464 0.976831 -0.7699743 -0.6336136 0.07532191 -0.2029197 -0.1795423 0.9625945 -0.06598186 -0.0744661 0.9950384 -0.05829077 -0.06802624 0.9959793 -0.3672739 -0.2947592 0.8821717 -0.495481 -0.3793245 0.7814164 -0.8426144 -0.5385175 2.13637e-4 -0.7723164 -0.5356103 0.3415393 -0.6481399 -0.472623 0.5971115 -0.270218 -0.2277351 0.935478 -0.1230242 -0.1198502 0.9851401 -0.09830099 -0.1005899 0.9900599 -0.07977652 -0.0857582 0.993117 -0.4056054 -0.3749333 0.8336123 -0.5651015 -0.6867222 0.4572451 -0.5429039 -0.839 0.03653132 -0.4930941 -0.869789 0.01803666 -0.451501 -0.8859418 0.1060847 -0.4127731 -0.878436 0.2407665 -0.3309485 -0.9436488 -3.66228e-4 -0.04483199 -0.8750332 0.4819824 -0.0167244 -0.9379412 0.346391 -0.02032595 -0.8719711 0.4891352 -0.1453623 -0.9448705 0.2934104 -0.1256471 -0.9819517 0.1413644 -0.1019334 -0.983658 0.1484138 -0.2196451 -0.9471262 0.2338975 -0.214826 -0.9505572 0.2242565 -0.2029541 -0.9404251 0.2727825 -0.4189322 -0.9055858 0.06640899 -0.2312706 -0.9339025 0.272654 -0.2291951 -0.9373197 0.262491 -0.7125819 -0.6952472 0.09411972 -0.4551389 -0.7904578 0.4099088 -0.4584022 -0.7749806 0.4350548 -0.4079474 -0.7711234 0.4888227 -0.4775709 -0.6135053 0.6289176 -0.4382849 -0.6567101 0.6137087 -0.7200777 -0.6791815 0.1421294 -0.7235016 -0.6696953 0.1674925 -0.4324329 -0.5716636 0.6972824 -0.4357903 -0.613018 0.6590111 -0.3549344 -0.8069188 0.4721269 -0.7295835 -0.6499292 0.2128384 -0.7260112 -0.6607621 0.1905287 -0.3420038 -0.8106949 0.4751918 -0.3387645 -0.8112341 0.4765897 -0.5774288 -0.7309113 0.3637923 -0.7325862 -0.6311704 0.2548364 -0.7314032 -0.640119 0.2351538 -0.3351611 -0.8115648 0.4785705 -0.3318734 -0.8116462 0.4807189 -0.3285053 -0.8114669 0.4833278 -0.3255139 -0.8111603 0.4858599 -0.734965 -0.6197547 0.2751922 -0.7357717 -0.6084125 0.2974461 -0.3143844 -0.8082252 0.4979304 -0.3621684 -0.6599724 0.6582329 -0.5699459 -0.6934265 0.4408192 -0.3109893 -0.8068633 0.5022524 -0.2916739 -0.7910017 0.5378128 -0.5566428 -0.65226 0.5144956 -0.7375329 -0.5710799 0.3604347 -0.2995157 -0.7523296 0.5867628 -0.2735127 -0.7310864 0.6250629 -0.5383585 -0.6079728 0.5835574 -0.7364848 -0.5310919 0.418965 -0.7376796 -0.584046 0.3387021 -0.7361829 -0.597626 0.3176128 -0.7327959 -0.4887341 0.473444 -0.2735146 -0.7454051 0.6079154 -0.2728407 -0.7731708 0.5725077 -0.1032153 0.06940025 0.9922351 -0.1286374 0.1480779 0.980574 -0.1310793 0.1367864 0.9818899 -0.1153638 0.06232088 0.9913665 -0.2670427 -0.8334481 0.4837899 -0.2686291 -0.8234054 0.4998419 -0.2703403 -0.809617 0.5209957 -0.2650291 -0.843552 0.4670971 -0.2341752 -0.9268124 0.2935659 -0.2349689 -0.9229376 0.3049194 -0.1878172 -0.6768622 0.711746 -0.1869617 -0.7049977 0.6841225 -0.1776213 -0.5408905 0.8221242 -0.1102662 -0.79164 0.6009555 -0.1461264 -0.7950891 0.5886259 0.02108836 -0.707453 0.7064459 0.01971548 -0.7905133 0.6121274 0.03433352 -0.7924493 0.6089707 -0.07648122 -0.7894417 0.6090424 0.0411399 -0.9901958 0.133491 0.04477107 -0.982981 0.1781689 -0.112006 -0.6847018 0.7201653 -0.07529038 -0.6823744 0.7271153 -0.1086493 -0.5621384 0.8198754 0.01870816 -0.9273217 0.3737975 0.03232008 -0.9239453 0.3811572 0.01886099 -0.8637304 0.5036011 -0.0463891 -0.7880964 0.6138014 -0.01693826 -0.6867796 0.7266685 -0.0202949 -0.7875649 0.6158974 -0.03860706 -0.9414334 0.3349815 0.0364089 -0.9981789 0.04809761 0.03790521 -0.9974079 0.06116104 0.0383929 -0.9942791 0.09967511 -0.02694803 -0.9851142 0.1697757 -0.04879933 -0.9855696 0.1620846 -0.01532071 -0.9990547 0.04068243 0.007110834 -0.9817565 0.1900095 0.01992863 -0.9794958 0.200477 0.002288877 -0.9329265 0.3600597 -0.1210996 -0.9444121 0.3056483 -0.1614784 -0.88424 0.4382287 -0.1835726 -0.4605337 0.8684526 -0.1785354 -0.3256667 0.9284753 -0.1359312 -0.8807452 0.4536636 -0.1735329 -0.8023228 0.5711082 -0.1831166 -0.4587377 0.8694987 -0.18455 -0.5871908 0.7881296 -0.1034275 -0.994632 -0.003204405 -0.1174665 -0.9929267 0.01727354 -0.1116686 -0.9936649 0.01266533 -0.1560122 -0.9461448 0.2836725 -0.1709381 -0.887377 0.4281847 -0.1725555 -0.942982 0.284622 -0.1373373 -0.9811992 0.1355977 -0.1395626 -0.9898782 0.02575784 -0.1245767 -0.9917917 0.02880948 -0.08169847 -0.9548987 -0.2854716 -0.1569011 -0.9210504 -0.3564382 -0.1900728 -0.7920311 0.5801371 -0.2232175 -0.9440507 0.2427803 -0.1914153 -0.958633 0.2106728 -0.1599796 -0.9782804 0.1318107 -0.1774978 -0.9787098 0.1030622 -0.1550663 -0.9570407 0.2450053 -0.1569278 -0.9600613 0.2316378 -0.181377 -0.8060795 0.5633278 -0.03524971 -0.9986502 0.03814899 -0.03054964 -0.999532 0.001617491 -0.008362233 -0.9837867 0.1791477 -0.02334725 -0.9997211 0.003570735 -0.02111923 -0.9997156 0.01107841 -0.01098662 -0.9999397 1.52593e-4 0.01293992 -0.9988468 0.04623579 0.02179026 -0.998568 0.04886025 0.03666746 -0.9993276 -1.18137e-6 -0.02991819 -0.9995524 1.08032e-4 -0.01849466 -0.9996886 0.01675504 -0.01052892 -0.9999446 1.83112e-4 -0.0182504 -0.9994719 0.02688735 0.02102768 -0.9997764 0.00225836 0.0283212 -0.9983543 0.04986733 7.32467e-4 -0.9990549 0.04345971 -0.0185858 -0.9997906 0.008575737 -0.01849436 -0.9997031 0.01586973 -0.0184946 -0.9996882 0.01678556 -0.01855546 -0.9997394 0.01330626 -0.01855528 -0.9997901 0.008697807 -0.01852518 -0.9998109 0.005920708 -0.01849472 -0.9998144 0.005401909 -0.01846373 -0.9998212 0.004089474 0.003448605 -0.9998832 -0.01489311 -0.01840281 -0.9998249 0.003418087 -0.01815879 -0.9998351 3.05191e-4 -0.01837229 -0.9998258 0.003296017 -0.01812833 -0.9998356 -4.88305e-4 -0.009613335 -0.9998502 -0.01440477 -0.001586973 -0.9995704 -0.02926802 -0.01068168 -0.9995968 -0.02630758 0.005768001 -0.9995496 -0.02945053 -0.00827068 -0.9999646 0.001556456 -0.0140388 -0.9998989 -0.002288877 0.01664578 -0.999856 0.003308475 -0.01855576 -0.9997834 0.009430468 0.0140385 -0.9998806 -0.006469905 0.04080283 -0.9991313 0.008468687 8.85063e-4 -0.8679723 0.496612 0.03854548 -0.9779202 0.2053928 0.03039735 -0.9781491 0.2056707 0.04287981 -0.9238549 0.3803336 0.03354012 -0.8612704 0.507039 -0.09128147 -0.9444019 0.3158687 -0.07407045 -0.9851038 0.1551909 -0.1006224 -0.4285226 0.8979107 -0.05914545 -0.9975997 0.03601217 -0.04831129 -0.9981187 0.03775179 -0.03558474 -0.9993651 0.001770079 -0.01049858 -0.5725414 0.8198086 -0.1404487 -0.3003382 0.9434359 -0.08850586 -0.2878578 0.9535747 0.04492413 -0.8615556 0.5056718 -0.0444048 -0.2862356 0.9571298 -0.1515579 -0.6904646 0.707311 -0.1290333 -0.1575683 0.9790417 -0.07288002 -0.1432881 0.986994 0.008667528 -0.5903686 0.8070873 0.004303157 -0.6955009 0.7185124 -0.02679586 -0.1412125 0.9896167 -0.01135313 -0.2947853 0.9554961 0.03479188 -0.7163473 0.6968761 0.02291995 -0.6139864 0.7889838 -0.08630841 -0.9956904 0.03393739 -0.1169197 -0.03918683 0.992368 -0.1596451 -0.06946134 0.9847277 -0.2354221 -0.9186163 0.3173652 -0.2351823 -0.910332 0.3405658 -0.2354869 -0.9148159 0.3281129 -0.1697773 -0.1863797 0.9676975 -0.2344459 -0.9049456 0.3551176 -0.2333474 -0.8992698 0.3699501 -0.1875406 -0.5878002 0.7869686 -0.1602845 -0.3920136 0.9058887 -0.2409518 -0.8952298 0.374841 -0.2319748 -0.8937485 0.3839288 0.02270621 -0.347033 0.937578 0.02902311 -0.3845032 0.9226673 0.0350365 -0.4078336 0.9123838 0.03488337 -0.2505012 0.9674876 0.03997999 -0.07410037 0.9964491 0.02362155 0.009491324 0.999676 -0.1511287 0.02948105 0.9880745 0.04098689 -1.52595e-4 0.9991597 0.02121073 -8.54534e-4 0.9997747 0.0290544 0.0262466 0.9992333 0.04107892 -0.009644031 0.9991094 0.03674483 -0.004730403 0.9993136 0.04281777 -0.01016271 0.9990313 0.05014258 -0.01428282 0.99864 0.04522973 -0.01458823 0.9988701 0.04654169 -0.01525956 0.9987999 0.06149578 0.01983731 0.9979103 0.06390738 0.0223096 0.9977065 0.06030619 0.005310356 0.9981659 0.05352962 -0.01733452 0.9984159 0.0519737 -0.01409971 0.9985489 0.05179089 -0.004852533 0.9986462 0.05438476 0.001068115 0.9985195 0.05264443 -0.005706965 0.9985971 0.06579929 0.08151668 0.9944976 0.06808805 0.1177121 0.9907109 0.06778305 0.117865 0.9907136 0.06857573 0.1167344 0.9907929 0.0683006 0.1174661 0.9907255 0.07272714 0.1523516 0.985647 0.07562685 0.187419 0.9793645 0.07541286 0.1792085 0.9809166 0.07785427 0.1062065 0.9912916 0.07419186 0.1586381 0.9845453 0.06714272 0.04620641 0.9966729 0.064121 0.0403465 0.9971263 0.0725128 0.1552495 0.9852104 0.07165855 0.1525033 0.9857017 0.07297146 0.1307138 0.9887312 0.08542191 -0.1926342 0.9775454 0.07419216 -0.06567734 0.995079 0.08414083 -0.1977325 0.9766382 0.0912823 -0.353227 0.9310738 0.09326756 -0.3487767 0.9325535 0.0824331 -0.2019473 0.9759212 0.06244122 -0.06613397 0.9958552 0.0744667 -0.2103685 0.974782 0.06396782 -0.06726384 0.9956825 0.08041787 -0.4936773 0.865919 0.07208603 -0.3598503 0.9302211 0.07602238 -0.4894915 0.868688 0.07516998 -0.7799916 0.6212588 0.07794511 -0.703856 0.7060534 0.07077491 -0.7445256 0.6638318 0.07193374 -0.4856826 0.8711706 0.0786485 -0.6026974 0.7940846 0.073704 -0.8094012 0.5826126 0.08160966 -0.8045604 0.5882368 0.06930971 -0.7859067 0.6144484 0.07233023 -0.7850429 0.6152041 0.05227845 0.001159667 0.9986319 0.05984747 -0.0652188 0.9960747 0.05490368 -0.001678526 0.9984903 0.09296208 -0.6190863 0.7798015 0.08743685 -0.4967575 0.8634737 0.09015417 -0.6157585 0.7827604 0.0548675 -0.9984937 3.5723e-5 0.05512404 -0.9984792 8.88541e-4 0.05501079 -0.9984858 3.77124e-4 0.06653153 -0.9817369 0.1782312 0.0655542 -0.9770874 0.2024917 0.06332761 -0.9850418 0.1602569 0.05281198 -0.9986045 1.11125e-5 0.0547955 -0.9984977 -7.83237e-5 0.0541734 -0.9985311 0.001045167 0.05389767 -0.9985464 3.58449e-4 0.05405712 -0.9985377 6.75019e-4 0.05277413 -0.9986065 6.88561e-5 0.05376446 -0.9985536 6.41496e-5 0.05352109 -0.9985668 4.77824e-5 0.05264991 -0.9986119 0.001535296 0.05266427 -0.9986103 0.002047717 0.05224841 -0.9986342 -6.09909e-5 0.05245554 -0.9986233 4.91069e-5 0.05192649 -0.9986509 -3.05208e-5 0.05253118 -0.9986193 1.92807e-4 0.08954346 -0.9172255 0.3881743 0.08707094 -0.9437721 0.3189244 0.08704042 -0.9445046 0.3167575 0.05264538 -0.9986132 5.72781e-4 0.05261069 -0.998615 4.29033e-4 0.05268788 -0.9986103 0.001186966 0.05339241 -0.9985736 -7.97804e-6 0.05268466 -0.9986108 8.98236e-4 0.05395197 -0.9985435 4.52761e-4 0.05429166 -0.998524 0.001544356 0.05424135 -0.9985271 0.001299023 0.05267196 -0.9985973 -0.00538963 0.04902333 -0.9984151 -0.02764445 0.05507695 -0.998482 6.31255e-4 0.06283855 -0.9909814 0.1183525 0.05734461 -0.9974734 0.0419327 0.05645954 -0.9977173 0.03704965 0.05356073 -0.9985498 0.005462884 0.06112998 -0.9949878 0.07913631 0.06689763 -0.9825591 0.1735005 0.05752861 -0.9974883 0.04132294 0.05526399 -0.9984703 0.001757442 0.0551818 -0.9984759 0.001045405 0.05552762 -0.9984572 1.88463e-4 0.05728429 -0.9975778 0.03946119 0.05835151 -0.9951499 0.07919567 0.06720232 -0.9833149 0.1690435 0.07516807 -0.9358629 0.3442535 0.07089632 -0.955987 0.2847147 0.06869941 -0.9674379 0.2436067 0.07651197 -0.9386225 0.3363537 0.07208549 -0.9425745 0.3261244 0.08047866 -0.8733326 0.4804306 0.064242 -0.9898764 0.1265613 0.07049971 -0.9797935 0.1871752 0.06503558 -0.9908542 0.1182299 0.07388722 -0.9269938 0.3677273 0.06634843 -0.9890925 0.1315066 0.08261615 -0.877892 0.4716781 0.08313435 -0.7972234 0.5979328 0.07757943 -0.8974131 0.4343168 0.07745724 -0.8842889 0.4604711 0.07660317 -0.9097165 0.4081028 0.0861864 -0.8029928 0.5897241 0.08484387 -0.8829867 0.4616667 0.07367306 -0.9716362 0.224712 0.06854641 -0.9871175 0.1445701 0.06827127 -0.9874164 0.1426464 0.08765006 -0.7143846 0.6942421 0.08884125 -0.8091547 0.5808408 0.08377462 -0.7090173 0.7001973 0.0881384 -0.8935917 0.4401427 0.08667391 -0.8883162 0.4509791 0.07962381 -0.9499623 0.3020457 0.0795015 -0.8530316 0.5157681 0.08124184 -0.8368645 0.541348 0.09058088 -0.7200999 0.6879326 0.08710294 -0.611979 0.7860628 0.07983875 -0.9609038 0.2651221 0.0833472 -0.9469725 0.3103167 0.0810281 -0.9488378 0.3051906 0.08920872 -0.8986489 0.429502 0.07226854 -0.2107629 0.9748623 0.08231067 -0.3630582 0.9281238 0.09924864 -0.492703 0.8645193 0.1019352 -0.6258637 0.7732425 0.104071 -0.6254031 0.7733306 0.09509813 -0.8977252 0.4301695 0.09204739 -0.8892217 0.4481207 0.09180176 -0.8963795 0.4336779 0.09457743 -0.2632238 0.9600878 0.09662348 -0.3310713 0.9386458 0.09854543 -0.330611 0.9386081 0.06394684 -0.01012253 0.997902 0.1016293 -0.4880648 0.8668704 0.1041932 -0.7035327 0.7029834 0.1045289 -0.6233586 0.774918 0.1028194 -0.746776 0.6570799 0.1045275 -0.7426799 0.6614384 0.09650099 -0.8644501 0.4933698 0.09735614 -0.8453508 0.5252656 0.09314465 -0.8906121 0.4451229 0.0982722 -0.8412651 0.531616 0.08704054 -0.945086 0.3150185 0.08133339 -0.9542413 0.2877647 0.07828187 -0.9705429 0.2278568 0.08697974 -0.9457905 0.3129135 0.09061163 -0.9146316 0.3940036 0.08487266 -0.9392759 0.3325019 0.08151632 -0.9539031 0.2888322 0.08087635 -0.9581562 0.2745829 0.0682094 -0.9852374 0.157019 0.07724392 -0.971394 0.2245599 0.0652492 -0.9896339 0.1279349 0.06024539 -0.9938966 0.09241288 0.05905354 -0.9936565 0.09570646 0.05563664 -0.9976455 0.04010236 0.05508643 -0.9984235 0.01077312 0.0664407 -0.9927347 0.1003172 0.0559827 -0.9984316 -7.4752e-4 0.05597114 -0.9984323 -5.28402e-4 0.05599033 -0.9984311 -7.62579e-4 0.05596035 -0.9984329 -4.58102e-4 0.0559861 -0.9984314 -6.68153e-4 0.05596804 -0.9984324 -5.74637e-4 0.05594706 -0.9984337 -4.85222e-4 0.05594253 -0.9984339 -4.54374e-4 0.0559377 -0.9984343 -4.45754e-4 0.05590057 -0.9984363 -3.88681e-4 0.05590897 -0.9984359 -3.85105e-4 0.0558747 -0.9984378 -3.41821e-4 0.05582869 -0.9984404 -2.89403e-4 0.05574542 -0.998445 -1.70382e-4 0.05562925 -0.9984515 -3.88704e-4 0.05572462 -0.9984462 -2.67729e-4 0.05575519 -0.9984445 -8.06699e-5 0.05574381 -0.9984451 -1.07425e-4 0.05575072 -0.9984447 -1.02726e-4 0.0557363 -0.9984455 -2.33041e-4 0.05575448 -0.9984445 7.63775e-5 0.05598312 -0.9984315 -8.03382e-4 0.05597358 -0.9984319 -9.57352e-4 0.05599474 -0.9984309 -6.96229e-4 0.08108872 -0.9562795 0.2809876 0.08710104 -0.9455072 0.3137347 0.08850651 -0.9284337 0.3608015 0.1029092 -0.7454818 0.6585338 0.09903514 -0.8268595 0.5536202 0.07193297 -0.06741613 0.9951285 0.1062387 -0.6127117 0.7831333 0.1045901 -0.5674173 0.8167611 0.0659511 -0.06814849 0.995493 0.07660365 -0.209424 0.9748197 0.07861626 -0.2077717 0.9750131 0.0618782 -0.008434236 0.9980481 0.0907942 -0.1976414 0.9760607 0.0880469 -0.1788406 0.9799305 0.0576483 -0.001776456 0.9983355 0.06261891 -0.007011413 0.998013 0.05945044 -0.004261672 0.9982222 0.05423265 -4.88308e-4 0.9985283 0.05139416 -0.002014219 0.9986765 0.05145514 3.05191e-4 0.9986753 0.05578958 -3.18781e-4 0.9984426 0.06979638 0.1330007 0.9886553 0.07428252 0.06628662 0.9950318 0.0731852 0.1472859 0.9863827 0.0730319 0.151252 0.9857937 0.07684677 0.08270645 0.9936068 0.08756107 0.7959852 0.5989497 0.09399968 0.1569612 0.9831212 0.09381526 0.1607434 0.9825276 0.07959437 0.1625459 0.9834855 0.08453917 0.1717336 0.9815094 0.06778216 0.004760921 0.9976888 0.07223945 0.1628211 0.9840075 0.06924766 0.1003466 0.9925399 0.03509634 0.01870787 0.9992088 0.06955236 0.1317497 0.98884 0.06927758 0.1131636 0.9911583 0.07028633 0.07754999 0.9945079 0.07049953 0.05093663 0.9962105 0.07181137 0.1537855 0.9854913 0.0719636 0.1529608 0.9856086 0.06375372 0.05407929 0.9964994 0.05545347 -0.01297068 0.9983771 0.05453658 -0.0160222 0.9983832 0.06464028 0.005035698 0.997896 0.05969494 -0.008331656 0.998182 0.06238102 0.005737543 0.9980359 0.07171976 0.1546096 0.9853691 0.07165831 0.1556463 0.9852104 0.06802785 0.1184155 0.9906311 0.0312519 1.22078e-4 0.9995116 0.0348531 -0.003418147 0.9993867 0.06869721 0.1404463 0.9877021 0.05783379 -0.009460926 0.9982814 0.06827181 0.1159736 0.9909032 0.06836342 0.1406333 0.9876988 0.06158804 0.03390699 0.9975256 0.06360197 0.05456829 0.9964824 0.06653171 0.02432376 0.9974878 0.03933948 -0.006500601 0.9992049 0.06839346 0.1404492 0.9877228 0.06836342 0.1408469 0.9876683 0.05130547 -0.01243817 0.9986056 0.1055043 0.454032 0.8847168 0.1060221 0.4857974 0.8676176 0.1039496 0.4649042 0.8792375 0.1059646 0.5445638 0.8319987 0.1068774 0.6049774 0.7890372 0.107092 0.5762951 0.8101947 0.08771258 0.8594552 0.5036302 0.07602339 0.7324617 0.6765505 0.08719414 0.9192468 0.3839045 0.07623565 0.9709212 0.2269369 0.08255487 0.9609937 0.2639619 0.08642923 0.9421156 0.3239572 0.09314471 0.7568771 0.6468858 0.08288931 0.9432171 0.3216692 0.07715272 0.9827514 0.1680697 0.0849353 0.9536685 0.2886215 0.08194434 0.9652646 0.2480914 0.1050463 0.7359347 0.6688539 0.06918668 0.9900687 0.1223814 0.07245224 0.9879938 0.1364507 0.07806807 0.9762172 0.2022506 0.07172065 0.9932249 0.09143626 0.06900423 0.9944116 0.0798996 0.08166819 0.9393979 0.3329597 0.06424194 0.9978719 0.01116985 0.06573849 0.9973701 0.03051924 0.05835181 0.9982489 -0.00970453 0.0790143 0.9571751 0.2785186 0.09454852 0.8868272 0.4523252 0.09164947 0.8380298 0.5378723 0.08816993 0.9478954 0.3061379 0.07300078 0.9818485 0.1750554 0.08813869 0.8868502 0.4535726 0.09448665 0.9139513 0.3946712 0.06573742 0.9958274 0.0632959 0.06879001 0.9946173 0.07748794 0.08813917 0.9535999 0.2878867 0.08371257 0.9708589 0.2245561 0.09146469 0.9349724 0.3427255 0.06174021 0.9980676 0.0070194 0.05844348 0.9982702 0.006408929 0.07953292 0.9835107 0.162423 0.06472426 0.9977953 -0.01467686 0.06668883 0.997739 -0.008342742 0.0866751 0.8286324 0.5530422 0.07913678 0.8832928 0.4620944 0.02126437 0.9997728 0.001546323 0.06717067 0.9977411 -9.80941e-4 0.06747406 0.9977208 -7.6945e-4 0.06505614 0.9978723 -0.004336178 0.06680572 0.9977505 -0.005552053 0.06526929 0.997855 -0.005064666 0.05881667 0.9981839 0.01302158 0.05573081 0.9984087 0.008616745 0.05854505 0.9982351 0.009973764 0.06656706 0.9977742 -0.003947734 0.05743724 0.9983468 0.002166867 0.05630838 0.9984135 -3.05195e-4 0.05508631 0.9984816 2.74669e-4 0.05839425 0.9982746 -0.006176114 0.01162767 0.9999194 0.005096614 0.01746118 0.9998477 6.9922e-5 0.02088344 0.999782 8.82629e-5 0.06680136 0.9977663 -2.56957e-4 0.06283462 0.9979596 -0.01133817 0.05863553 0.9982649 -0.005416989 0.06065028 0.9981406 -0.006086707 0.06700479 0.997739 -0.005228817 0.06739008 0.9977192 -0.003883183 0.06631767 0.9977834 -0.00551021 0.06335681 0.9979308 -0.01095616 0.01306217 0.2699419 0.962788 0.06470608 0.9978445 -0.01093077 0.06268453 0.9979744 -0.01085513 0.05725342 0.998334 -0.007171928 0.0174933 0.999847 9.56819e-5 0.02096587 0.9997802 4.24745e-4 0.02376198 0.9997177 -1.42712e-4 0.02699762 0.9996355 3.09744e-4 0.02567595 0.9996703 1.66839e-4 0.06575632 0.9978337 -0.002010703 0.06646978 0.9977754 -0.005090475 0.07013124 0.9964525 0.04651862 0.06538534 0.9978181 -0.009159266 0.06405264 0.9979035 -0.009267091 0.06015259 0.9979351 0.02252286 0.02566498 0.9996706 1.8478e-4 0.02677351 0.9996415 -4.18152e-5 0.06268167 0.9980335 4.37684e-4 0.06711202 0.9977383 -0.003814876 0.06164854 0.9282996 0.3666871 0.06946069 0.9964985 0.04654109 0.0471524 -0.511291 0.8581132 0.05963498 0.9981688 -0.01013243 0.06291955 0.9980171 0.001727044 0.06335705 0.9979656 0.007110834 0.0644139 0.9979231 -6.90717e-4 0.06695806 0.9977484 0.003845334 0.05931037 0.9981366 -0.01434665 0.06054514 0.9980632 -0.0142982 0.09167879 0.8988127 0.4286382 0.06482195 0.9954935 0.06921666 -0.03357076 0.9418131 0.3344566 0.01617521 0.8708062 0.4913602 0.0867964 0.8527046 0.5151324 -0.05371379 0.8732464 0.4843095 -0.0757789 0.7689287 0.6348278 0.1024209 0.8238235 0.5575168 0.101201 0.842996 0.5283145 0.09766149 0.8865832 0.4521422 0.02691751 0.6263056 0.7791129 0.1039468 0.7823785 0.6140676 0.1003164 0.7318184 0.6740761 0.02951204 0.5227023 0.8520043 0.1022087 0.6482273 0.7545561 0.1055069 0.7123318 0.6938673 0.1051679 0.7597973 0.6415978 0.1040412 0.4190644 0.9019759 0.02951252 0.5371767 0.8429533 0.09604364 0.2058209 0.9738652 0.0980575 0.203287 0.9741967 0.09912675 0.2363111 0.9666081 0.1002845 0.2913013 0.9513604 0.0889936 0.2779373 0.956468 0.1057813 0.5146847 0.850829 0.08658289 0.09610486 0.9915984 0.09238111 0.1648638 0.9819806 0.08337807 0.2594732 0.9621444 0.09515911 0.3049791 0.947593 0.08252274 0.137426 0.9870685 0.1035515 0.388875 0.9154525 0.08554595 0.1365134 0.9869377 0.08816897 0.1384946 0.9864308 0.0878641 0.1358094 0.9868312 0.0889939 0.1585776 0.9833277 0.08383476 0.07535058 0.9936267 0.0762974 0.1175896 0.990127 0.08939146 0.1666057 0.9819633 -0.1438991 6.10388e-5 0.9895924 -0.1668779 6.1038e-5 0.9859776 -0.1648632 -0.008484244 0.98628 0.03650057 0.02029502 0.9991276 0.01904404 0.01934927 0.9996314 0.0433669 0.02221751 0.9988121 0.0409559 0.02398759 0.9988731 0.03494405 0.02542221 0.9990659 0.03048843 0.02624624 0.9991906 0.07892251 0.164193 0.9832659 0.07898318 0.1608657 0.983811 0.08426392 0.1660558 0.9825097 0.07043808 0.02462887 0.9972121 0.09955328 0.2642343 0.9593067 0.08279764 0.08468979 0.9929614 0.09375625 0.1756099 0.9799852 0.0951271 0.1706917 0.9807218 0.04458808 -0.00100708 0.999005 0.0454688 5.00205e-5 0.9989659 0.04409968 -0.01043742 0.9989727 0.03418159 0.00125128 0.9994149 0.08859765 0.1514065 0.9844931 0.09222871 0.1751491 0.9802126 0.09363204 0.1890647 0.9774905 0.04486471 -4.7525e-4 0.998993 0.04092597 3.0519e-5 0.9991622 0.02945095 0.002166807 0.9995639 0.02805167 0.001543104 0.9996054 0.06662303 0.0669282 0.995531 0.08417117 0.1526252 0.9846933 0.08859759 0.146157 0.9852861 -0.1652296 -0.003082394 0.9862504 -0.1440485 -6.10375e-5 0.9895707 0.02806556 0.001555979 0.9996049 0.02946269 0.001525759 0.9995647 0.07892245 0.162728 0.9835096 0.08414208 0.1605932 0.9834277 -0.1670609 9.15569e-4 0.9859461 -0.04733455 0.001190185 0.9988784 0.03860652 -7.62976e-4 0.9992542 0.03338795 0.001312315 0.9994416 0.0292375 0.002136349 0.9995703 0.04945558 -0.01375275 0.9986817 0.03262484 2.44152e-4 0.9994677 0.02893173 0.002014219 0.9995794 0.05231547 -0.01949894 0.9984403 0.02811926 0.002855658 0.9996005 0.02817356 0.002741038 0.9995993 0.03854531 -0.004181027 0.9992482 0.06781381 0.1316296 0.9889768 0.06833183 0.1409668 0.9876533 0.06836253 0.1407231 0.9876861 0.02948147 0.001861631 0.9995636 0.04754793 -0.01065093 0.9988123 0.04416102 -0.005462884 0.9990096 0.03393667 0 0.999424 0.06741636 0.1309874 0.9890892 0.06732511 0.1312321 0.9890629 -0.4443859 -0.7872964 0.4274174 -0.1710173 -5.00194e-5 0.9852681 0.04031538 0 0.9991871 0.04979419 -0.007875204 0.9987285 0.03973513 -0.001861631 0.9992086 0.06207609 0.03903406 0.9973079 0.06756913 0.1301943 0.9891835 0.06750869 0.1306227 0.9891312 0.05832105 0.01376384 0.9982031 0.06836283 0.1406931 0.9876903 -0.559448 -0.7479348 0.3572276 -0.1580581 0.01239073 0.9873521 -0.1627599 0.02591091 0.9863255 0.02188175 0.002838194 0.9997566 0.03894168 0.001708984 0.9992401 0.02974772 0.001047968 0.9995569 0.02804428 0.00160849 0.9996054 0.04934698 -8.69354e-4 0.9987813 0.05114161 -0.01013392 0.99864 0.04815924 -0.003936946 0.9988319 0.04907244 -0.01017272 0.9987435 0.05177497 -0.005701005 0.9986426 0.0609458 0.01727354 0.9979916 0.06762939 0.1295518 0.9892637 0.06772267 0.128609 0.9893803 0.06778353 0.1274184 0.9895302 0.06787472 0.1257392 0.9897388 -0.1522296 0.02505618 0.9880276 0.03286868 1.52594e-4 0.9994598 0.03021693 0.001606166 0.9995421 0.04495495 -2.13635e-4 0.9989891 0.02981692 3.05189e-4 0.9995554 0.05038636 -3.19185e-4 0.9987298 0.05064529 -0.004018127 0.9987087 0.05972647 0.005707085 0.9981985 0.06335717 0.02175992 0.9977537 0.05688804 0.001434385 0.9983796 0.06567656 0.03009158 0.9973872 0.06823998 0.04004061 0.9968652 0.05816864 0.004364132 0.9982973 0.07098817 0.05194407 0.9961238 0.07187288 0.005157709 0.9974005 -0.6557968 -0.1537557 0.7391142 -0.1448436 0.04025465 0.9886354 0.02828449 0.001257658 0.9995992 0.04670298 -2.09619e-4 0.9989088 0.04752975 -0.002011895 0.9988678 0.05689775 0.004977405 0.9983677 0.06213694 -4.27268e-4 0.9980676 0.06412047 -6.10381e-4 0.997942 0.06650078 4.88303e-4 0.9977863 0.06909513 0.00250256 0.997607 0.07477229 0.00927782 0.9971576 0.07788497 0.01504594 0.9968489 0.08002156 0.03128224 0.9963021 -0.4061225 -0.272783 0.8721548 -0.6771283 -0.2250787 0.7005975 -0.6831673 -0.2473258 0.6871043 -0.1625122 0.01147502 0.9866398 -0.1417014 0.06924837 0.9874843 0.03988879 7.62984e-4 0.9992039 0.03430354 -6.10383e-5 0.9994115 0.05061799 -8.80183e-4 0.9987178 0.0586782 -0.002467989 0.998274 0.07999145 -3.05194e-4 0.9967955 -0.4148139 -0.3256984 0.8496177 -0.6890377 -0.2694562 0.6727707 -0.6943816 -0.290699 0.6582769 -0.1712418 0.01983726 0.9850293 -0.4266561 -0.3762692 0.822427 -0.7041485 -0.3317482 0.6277884 -0.442862 -0.4239097 0.7900468 0.04959785 0.003350853 0.9987636 0.04982239 -1.9925e-4 0.9987581 0.05741029 -0.002300798 0.9983481 0.07087546 -0.008777201 0.9974465 0.06805521 -0.008732914 0.9976434 -0.6995854 -0.3119035 0.6428813 -0.1834482 0.02645975 0.9826732 -0.1389209 0.09094554 0.9861187 0.02954876 -6.2835e-4 0.9995632 0.02839344 -6.08233e-4 0.9995967 0.04725474 0.001510143 0.9988818 0.06060498 -0.005890309 0.9981445 0.06297922 -0.00731188 0.9979881 0.0564301 -0.001589059 0.9984053 0.06808149 -0.008663117 0.9976422 0.06160849 -0.004657447 0.9980896 0.06364649 -0.006230115 0.9979531 0.06539028 -0.008498311 0.9978237 0.07730954 -0.005120277 0.996994 0.07095414 -0.008951902 0.9974395 0.07635384 -0.007578611 0.9970521 -0.7086588 -0.3517658 0.6116073 -0.1985275 0.03192305 0.9795754 -0.725627 -0.4429572 0.5265496 -0.7199774 -0.4068203 0.5622544 -0.465999 -0.4671893 0.7513849 0.03170931 -0.08292037 0.9960516 0.03460848 -0.08472067 0.9958035 0.02948153 -0.001312315 0.9995645 0.02999806 -0.001215815 0.9995493 0.05032855 0.001238465 0.998732 0.05758303 -0.002493321 0.9983377 0.06859922 -0.01107388 0.9975829 0.06586062 -0.007583796 0.9978001 0.07355833 -0.008905947 0.9972512 0.07785302 -0.004943966 0.9969527 0.07402181 -0.007843494 0.9972259 -0.7126218 -0.3705022 0.5957335 -0.7165694 -0.3894299 0.5786819 -0.2161689 0.03647065 0.9756746 -0.1337056 0.1231765 0.9833363 0.03726392 -0.2514476 0.9671534 0.02783542 -0.001219809 0.9996118 0.04452699 0.002563536 0.9990049 0.063784 -0.2085646 0.9759265 0.07574808 -0.3632673 0.9286006 0.05822402 -0.003351807 0.9982979 0.05663138 -5.93737e-4 0.998395 0.05971479 -0.003353476 0.9982098 0.07791465 -0.00100708 0.9969595 -0.723486 -0.424887 0.5440948 -0.2365217 0.04062068 0.9707768 -0.7353354 -0.5178539 0.4371605 0.03424239 0.008392751 0.9993783 0.03262466 -0.003112912 0.9994629 0.06036621 -0.2048118 0.9769381 0.05020302 -0.04101693 0.9978965 0.05618625 -0.09235179 0.99414 0.04636251 0.00322622 0.9989195 0.05812633 -0.004408419 0.9982995 0.07297778 -0.01104342 0.9972724 0.07084399 -0.0112608 0.9974239 0.07086443 -0.01129472 0.997422 0.06625914 -0.01077306 0.9977443 0.06851488 -0.01124894 0.9975867 -0.73094 -0.4747295 0.4902639 -0.2595632 0.04379457 0.9647327 -0.7375739 -0.5451461 0.398498 -0.7371345 -0.5592981 0.3792338 -0.1627854 -0.01605969 0.9865309 0.05035656 0.006683647 0.998709 0.03051006 0.05073267 0.9982462 0.05011236 -0.04822021 0.9975789 0.04327553 0.02478116 0.9987559 0.04004073 0.01431334 0.9990956 0.06228929 -0.2327685 0.9705355 0.06830179 -0.4184782 0.905655 0.0716291 -0.4696028 0.8799674 0.06662303 -0.3556689 0.9322345 0.05094486 0.00356853 0.9986951 0.04936182 0.00360918 0.9987745 0.0602644 -0.006520926 0.9981611 0.09573906 -0.339161 0.935844 0.05913448 -0.002826333 0.998246 0.0608313 -0.005222737 0.9981345 0.0645371 -0.008921861 0.9978755 0.07621586 -0.005632042 0.9970754 0.07514643 -0.009046196 0.9971315 -0.7347561 -0.5031134 0.4549841 -0.2854724 0.04406905 0.9573733 -0.2716211 -0.7949038 0.5425403 -0.1273576 0.1528413 0.98001 -0.1375204 -0.2384787 0.9613616 0.02252298 -0.02487295 0.9994369 0.04043757 -0.03805708 0.9984571 0.02801972 -0.002284228 0.9996048 0.02717584 -0.005058109 0.9996179 0.06900376 -0.3332079 0.940325 0.06949269 -0.5304887 0.8448388 0.07345956 -0.6253678 0.7768648 0.07175064 -0.6383092 0.7664288 0.05118638 0.001994311 0.9986872 0.08667528 -0.9262963 0.3666914 0.09097796 -0.9036152 0.4185721 0.08539247 -0.9307724 0.3554868 0.0763576 -0.06344819 0.9950598 0.08740615 -0.187142 0.9784366 0.08279699 -0.0858488 0.9928619 0.08667284 -0.1403551 0.9863004 0.06640386 -0.01046967 0.9977379 0.07882988 -0.02679544 0.996528 0.07977747 -0.05328667 0.9953874 0.07358068 -0.009401082 0.997245 -0.3096521 0.004577934 0.950839 -0.1346216 0.1099923 0.9847735 -0.2632318 -0.8509482 0.4545287 0.04159754 -0.4095665 0.9113314 0.03506714 -0.5297306 0.8474408 0.04718285 -0.3362924 0.940575 0.04705977 -0.3964679 0.9168416 0.04996031 -0.3861625 0.9210768 0.04562664 -0.286273 0.9570612 0.03540188 -0.09265536 0.9950688 0.03195345 0.04727405 0.9983708 0.04648852 0.003632962 0.9989122 0.06586074 -0.2702488 0.9605353 0.0667141 -0.6801727 0.7300099 0.05630707 -0.06131219 0.9965292 0.06842494 -0.2107989 0.9751318 0.09704965 -0.8363668 0.5395108 -0.3277783 -0.1028198 0.9391429 -0.1566567 -0.01190257 0.9875814 0.05703985 -0.7440823 0.6656486 0.05346888 -0.7921149 0.6080256 0.05688714 -0.7675798 0.638424 0.02542251 -0.5079016 0.8610399 0.01474088 -0.4745779 0.8800902 0.04407012 -0.5314058 0.8459704 0.03500545 -0.6303119 0.7755525 0.05154722 -0.4336196 0.8996204 0.06842464 -0.3108408 0.9479959 0.05157685 -0.05993908 0.9968687 0.06112891 -0.20475 0.9769037 0.05371266 -0.05923652 0.9967979 0.09601241 -0.8320363 0.5463491 0.09027451 -0.905614 0.4143838 0.06787353 -0.06854498 0.9953365 0.08478206 -0.361804 0.9283911 0.06988912 -0.06845474 0.9952033 0.08057123 -0.2053346 0.9753698 0.1008955 -0.3966847 0.9123932 0.1023604 -0.4818633 0.8702471 0.1034297 -0.459864 0.8819453 0.07846379 -0.05972528 0.9951264 -0.3420613 -0.2416525 0.9080739 -0.1835095 -0.1715461 0.9679341 -0.2603881 -0.8606358 0.4376119 -0.001281797 -0.4479334 0.8940661 0.04541295 -0.6316617 0.773913 0.05081456 -0.5195599 0.8529217 0.05267566 -0.4797881 0.8758018 0.07153642 -0.374834 0.924328 0.06503641 -0.5953992 0.8007934 0.06882083 -0.3547553 0.9324229 0.09015291 -0.9033606 0.4192997 0.094702 -0.8270786 0.5540512 0.07965624 -0.3635498 0.928163 0.08450853 -0.4954845 0.8644961 0.08710247 -0.3597325 0.9289811 0.08926808 -0.3568587 0.9298834 0.09283936 -0.9122489 0.3989773 0.09406089 -0.9146369 0.3931819 -0.3531633 -0.3863677 0.8520538 -0.2077443 -0.3378478 0.9179876 -0.2570669 -0.869596 0.4215677 -0.1483526 -0.4391371 0.886087 0.05529993 -0.5734776 0.8173527 0.0528894 -0.6230761 0.7803711 0.06638038 -0.6224496 0.7798398 0.06854534 -0.7184447 0.6921985 0.06711137 -0.7032812 0.707737 0.09018272 -0.4973938 0.8628247 0.09271806 -0.4973144 0.8626017 0.09506702 -0.4965156 0.8628062 0.09720468 -0.4949656 0.8634584 -0.3601034 -0.5290916 0.7683669 -0.2269077 -0.5009366 0.8352099 -0.2534304 -0.8776369 0.4068498 -0.2330147 -0.9301971 0.2836156 -0.152231 -0.5704699 0.8070873 0.04583954 -0.7932204 0.6072068 0.05716198 -0.7883656 0.6125459 0.056674 -0.8073531 0.5873407 0.05685722 -0.6676988 0.7422571 0.05374473 -0.7128731 0.6992309 0.05447673 -0.5266391 0.8483417 0.08301293 -0.6081004 0.7895081 0.09308302 -0.8214808 0.5625878 0.09555482 -0.6218849 0.777257 0.09787607 -0.6239411 0.7753179 0.09998124 -0.6252797 0.7739698 0.09219926 -0.9072212 0.4104256 0.1043134 -0.5209266 0.8472039 -0.2388132 -0.6497856 0.721628 -0.2467157 -0.8891716 0.3853636 -0.181223 -0.7022164 0.6885132 0.001648008 -0.7884613 0.6150822 0.05563688 -0.863547 0.50119 0.05203562 -0.8629373 0.5026247 0.05456751 -0.8805276 0.4708436 0.05591088 -0.8273717 0.558865 0.04599297 -0.7175455 0.6949915 0.05639898 -0.6209689 0.7818037 0.07065212 -0.7255653 0.6845169 0.08002012 -0.9449216 0.3173645 0.09323644 -0.7256576 0.6817098 0.09561681 -0.7307835 0.6758794 0.09769052 -0.7352578 0.6707106 0.09949225 -0.7390506 0.6662625 0.1011093 -0.7420381 0.6626888 0.1050779 -0.663734 0.7405511 -0.1047721 -0.9944962 3.6623e-4 -0.1236925 -0.9923171 0.002655088 0.05249369 -0.9270029 0.3713627 0.05069309 -0.9402491 0.3366927 0.05349946 -0.8968865 0.439013 0.05734485 -0.7101119 0.7017497 0.06979632 -0.7674548 0.6372924 0.09113001 -0.8154401 0.571623 0.1012616 -0.7864405 0.609309 -0.08157628 -0.9960064 -0.03628665 -0.09619468 -0.9953345 0.007477045 -0.08935892 -0.9937215 -0.06732439 -0.05450677 -0.9984879 -0.007141411 0.0483123 -0.9638968 0.2618572 0.05322581 -0.9132021 0.4040161 0.05591148 -0.8448684 0.5320446 0.07825106 -0.8687278 0.4890694 0.07831323 -0.9416513 0.3273531 0.08389699 -0.9378827 0.3366563 0.0993086 -0.9101055 0.4023007 -0.2499486 -0.884037 0.3949738 -0.1663596 -0.9860417 -0.006805717 -0.09778368 -0.9952023 -0.003296077 0.03799617 -0.998949 0.02563595 0.04730439 -0.9734945 0.2237651 0.07617551 -0.9682165 0.2382315 0.07770216 -0.965143 0.2499227 0.0856058 -0.9324775 0.350938 0.0877121 -0.9259824 0.3672373 0.09650313 -0.9137893 0.3945583 -0.226668 -0.9404876 0.2531894 -0.1474109 -0.7198719 -0.6782733 -0.1325171 -0.9910222 0.01773399 -0.07065057 -0.9975012 -2.74668e-4 -0.05230921 -0.9985444 -0.01315355 0.03363215 -0.9981924 0.04980736 0.0612207 -0.9938145 0.09265506 -0.1400822 -0.6862197 -0.7137784 -0.1100203 -0.9934186 0.03186166 -0.03029739 -0.999541 1.58937e-4 -0.03130161 -0.9995101 -2.20758e-4 0.05558186 -0.9984542 2.38615e-4 0.05984699 -0.9944801 0.08618462 -0.131489 -0.9913176 -3.5185e-4 -0.06628686 -0.9972025 -0.03454726 -0.02721381 -0.9996296 3.09381e-4 0.03779137 -0.9991644 0.01557433 0.05397534 -0.9985421 -4.42574e-4 0.05520051 -0.9984745 0.001301527 0.05565857 -0.9984496 8.12306e-4 -0.1229383 -0.9924141 7.14437e-4 -0.03035116 -0.9995393 2.42567e-4 0.05472773 -0.9985013 -1.41887e-4 0.0537045 -0.9985569 -3.8072e-4 0.05396765 -0.9985426 -3.15703e-4 0.05495536 -0.9984889 2.52389e-4 -0.1040738 -0.9945102 -0.01086974 0.03084856 -0.9993594 0.01814115 0.02710115 -0.9995993 0.008179128 0.0338245 -0.9994278 -1.25695e-5 0.05409002 -0.9985358 7.60483e-4 -0.03091233 -0.9995222 2.93482e-4 0.02548766 -0.9995589 0.01524424 0.02989321 -0.9995532 0 0.03665477 -0.9993281 -1.46865e-5 0.02987945 -0.9995536 -9.53981e-6 0.05362594 -0.9985611 1.16823e-4 0.05396616 -0.9985427 4.43027e-4 -0.01852494 -0.9997975 0.007873833 0.03383576 -0.9994274 -1.97953e-5 0.0367155 -0.9993258 -5.57775e-5 0.01144456 -0.9998013 -0.01632761 0.01803672 -0.9998353 -0.002044737 0.02145624 -0.9997526 0.005861043 0.025406 -0.99956 0.01530802 0.02998095 -0.99935 0.02002155 0.03619414 -0.9991542 0.01952254 0.0339533 -0.9993258 0.01397824 0 0 -1 0 0 -1 0.118748 -4.5778e-4 0.9929243 0.1088604 8.54525e-4 0.9940567 0.04751873 -3.35714e-4 0.9988703 0.188304 7.62982e-4 0.9821106 0.5681145 -1.83115e-4 0.8229495 0.6785666 -1.52597e-4 0.734539 0.5772414 1.52596e-4 0.8165735 0.4604704 1.83114e-4 0.8876751 0.862821 2.1363e-4 0.5055096 0.8542664 -1.52597e-4 0.5198357 0.9085792 -2.13633e-4 0.4177126 0.782842 1.83114e-4 0.6222207 0.9764242 -2.44152e-4 0.2158607 0.9604398 2.44154e-4 0.2784878 0.9482398 -2.44156e-4 0.317555 0.9231347 2.7467e-4 0.3844767 0.9938241 -2.74672e-4 0.1109674 0.9867113 3.66229e-4 0.1624834 0.9986422 -2.44152e-4 0.05209589 0.9959748 5.49335e-4 0.0896331 0.7752217 -1.52597e-4 0.6316893 0.6854837 1.22075e-4 0.728088 0.4405726 -3.66228e-4 0.8977169 0.3349808 3.66233e-4 0.942225 0.2802226 -6.10374e-4 0.9599349 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.3607233 -0.04587548 -0.005176246 0.3609769 -0.04565238 -0.004700362 0.3606892 -0.04575335 -0.004909157 0.3609696 -0.04586833 -0.005041778 0.3606715 -0.0456137 -0.004737734 0.3609672 -0.04594385 -0.005413591 0.3607493 -0.04590898 -0.005414187 0.3603299 -0.04570084 -0.005414187 0.3604257 -0.04572951 -0.005178391 0.3603112 -0.04546052 -0.004891037 0.3601953 -0.04549503 -0.005180537 0.3600434 -0.04525113 -0.005414068 0.3600617 -0.04519528 -0.005156755 0.3599821 -0.04493826 -0.005413949 -0.1734589 -0.115967 -0.009499967 -0.173727 -0.115363 -0.009499967 -0.215776 -0.116 -0.009499967 -0.1987619 -0.100545 -0.009499967 -0.1717863 -0.1137503 -0.009499967 -0.1988301 -0.1002877 -0.009499967 -0.199154 -0.101907 -0.009499967 -0.1993416 -0.1020918 -0.009499967 -0.172447 -0.113828 -0.009499967 -0.172803 -0.113968 -0.009499967 -0.1999718 -0.1025137 -0.009499967 -0.1726289 -0.113888 -0.009499967 -0.1996397 -0.1023164 -0.009499967 -0.1674759 -0.114695 -0.009499967 -0.171494 -0.11377 -0.009499967 -0.16793 -0.115586 -0.009499967 -0.172967 -0.114069 -0.009499967 -0.2033759 -0.103736 -0.009499967 -0.204058 -0.10403 -0.009499967 -0.20055 -0.10278 -0.009499967 -0.200294 -0.1026722 -0.009499967 -0.207931 -0.10625 -0.009499967 -0.173368 -0.114478 -0.009499967 -0.207319 -0.10583 -0.009499967 -0.20473 -0.104346 -0.009499967 -0.2118059 -0.109726 -0.009499967 -0.212294 -0.110293 -0.009499967 -0.1736529 -0.1150774 -0.009499967 -0.209688 -0.107632 -0.009499967 -0.210247 -0.108132 -0.009499967 -0.1734679 -0.114642 -0.009499967 -0.214806 -0.113993 -0.009499967 -0.2151499 -0.11465 -0.009499967 -0.213638 -0.112079 -0.009499967 -0.2132109 -0.1114709 -0.009499967 -0.216058 -0.116693 -0.009499967 -0.216318 -0.117397 -0.009499967 -0.173209 -0.116576 -0.009499967 -0.216552 -0.118101 -0.009499967 -0.172977 -0.117192 -0.009499967 -0.216763 -0.118814 -0.009499967 -0.172567 -0.118439 -0.009499967 -0.172763 -0.117812 -0.009499967 -0.172388 -0.1190699 -0.009499967 -0.216951 -0.119535 -0.009499967 -0.217117 -0.120263 -0.009499967 -0.172228 -0.119708 -0.009499967 -0.21726 -0.121 -0.009499967 -0.172086 -0.120351 -0.009499967 -0.171961 -0.121 -0.009499967 -0.215474 -0.11532 -0.009499967 -0.2144359 -0.11334 -0.009499967 -0.214046 -0.112702 -0.009499967 -0.212764 -0.110877 -0.009499967 -0.173553 -0.1148149 -0.009499967 -0.2113029 -0.109177 -0.009499967 -0.210783 -0.108646 -0.009499967 -0.209116 -0.107151 -0.009499967 -0.20853 -0.106691 -0.009499967 -0.206687 -0.105426 -0.009499967 -0.173251 -0.114326 -0.009499967 -0.206044 -0.105044 -0.009499967 -0.205392 -0.104684 -0.009499967 -0.201983 -0.103214 -0.009499967 -0.2026849 -0.103464 -0.009499967 -0.2012709 -0.102986 -0.009499967 -0.173117 -0.114189 -0.009499967 -0.202226 -0.09699088 -0.009499967 -0.2026799 -0.09788185 -0.009499967 -0.199116 -0.0996977 -0.009499967 -0.199036 -0.101766 -0.009499967 -0.172259 -0.113786 -0.009499967 -0.1989319 -0.101613 -0.009499967 -0.172069 -0.113762 -0.009499967 -0.198848 -0.101449 -0.009499967 -0.1987439 -0.101096 -0.009499967 -0.1987839 -0.101276 -0.009499967 -0.198728 -0.100912 -0.009499967 -0.1987349 -0.100727 -0.009499967 -0.1989781 -0.09994029 -0.009499967 -0.2380567 -0.1208143 -0.01987349 -0.2380217 -0.1204835 -0.02049064 -0.2395075 -0.1200256 -0.020536 -0.2392889 -0.1196158 -0.02105718 -0.2396624 -0.1202934 -0.01998603 -0.2402858 -0.1199511 -0.0195387 -0.2400867 -0.119845 -0.02012836 -0.2407985 -0.119297 -0.01925343 -0.2406097 -0.1196783 -0.01880288 -0.240819 -0.119307 -0.01880276 -0.2406801 -0.1192405 -0.01979678 -0.2386376 -0.1202837 -0.02069002 -0.239143 -0.120366 -0.02033698 -0.2389034 -0.1199606 -0.02094137 -0.238798 -0.1209295 -0.0188027 -0.2380946 -0.1209813 -0.01922458 -0.2388522 -0.1208394 -0.01948761 -0.2381194 -0.1210066 -0.01880258 -0.2394638 -0.1206986 -0.01880294 -0.2399051 -0.1195817 -0.02062803 -0.2385269 -0.120596 -0.02025049 -0.2404547 -0.1191321 -0.02033561 -0.2386895 -0.1193307 -0.02143466 -0.239023 -0.1189737 -0.02149486 -0.2379925 -0.1200522 -0.02100569 -0.2383502 -0.1196489 -0.02130395 -0.2387188 -0.1186324 -0.02167659 -0.2383006 -0.1189335 -0.02165251 -0.2379584 -0.1190862 -0.0216068 -0.2383809 -0.1181302 -0.02179193 -0.2379485 -0.1184505 -0.02177011 -0.237947 -0.11792 -0.02179801 -0.2392519 -0.1185517 -0.02154242 -0.2395865 -0.1192139 -0.02113467 -0.2391089 -0.1206335 -0.01986771 -0.2398847 -0.1188572 -0.02107328 -0.239843 -0.1203957 -0.01938235 -0.2402111 -0.120168 -0.0188027 -0.2402493 -0.1190332 -0.02065771 0.39 -0.144032 -0.000999987 0.415 -0.129584 -0.000999987 0.39 -0.127696 -0.000999987 0.415 -0.146919 -0.000999987 0.455 -0.04899948 -0.005236148 0.455 -0.0490151 -0.005386829 0.455 -0.04876726 -0.005038082 0.455 -0.04896128 -0.005089581 0.455 -0.04890137 -0.004950463 0.455 -0.04879796 -0.004789352 0.455 -0.04853647 -0.004678368 0.455 -0.04832285 -0.004307687 0.455 -0.0487225 -0.004707098 0.455 -0.04701435 -0.002999961 0.360977 -0.04393649 -0.002999961 0.360977 -0.04564446 -0.004707098 -0.200578 -0.0464558 -0.037 -0.200578 -0.04945659 -0.03999996 -0.200578 -0.0464558 -0.03999996 -0.200578 -0.04945659 -0.037 0.48 -0.074225 -0.002999961 0.48 -0.06471025 -0.002999961 0.455 -0.06471025 -0.002999961 0.455 -0.074225 -0.002999961 0.0818755 -0.09881556 -0.03860777 0.08041906 -0.1001399 -0.03394579 0.09254956 -0.08910858 -0.006037712 0.09276199 -0.0889154 -0.005638718 0.09331017 -0.08841687 -0.04039996 0.09314227 -0.08856958 -0.004799306 0.09331017 -0.08841687 -0.004358887 0.09295958 -0.08873575 -0.005225896 0.09208017 -0.08953547 -0.006794333 0.09232228 -0.08931529 -0.006422936 0.09155929 -0.09000915 -0.007482767 0.09182608 -0.08976656 -0.007147192 0.09098941 -0.09052747 -0.008100271 0.09127926 -0.09026378 -0.007801711 0.09037756 -0.09108388 -0.00863856 0.090689 -0.0908007 -0.008378982 0.08973067 -0.09167218 -0.009092032 0.09005808 -0.09137439 -0.008876264 0.0890522 -0.09228909 -0.009458184 0.08939439 -0.09197795 -0.009286582 0.0883513 -0.09292656 -0.009732186 0.08870488 -0.09260499 -0.00960648 0.08763426 -0.09357857 -0.009911358 0.08799386 -0.09325158 -0.009833991 0.08117288 -0.09945458 -0.03733766 0.08133226 -0.09930956 -0.03767246 0.08343786 -0.09739476 -0.04039996 0.08307325 -0.09772634 -0.04006159 0.08617657 -0.09490418 -0.009980797 0.08509278 -0.0958898 -0.00977683 0.08545178 -0.09556341 -0.009869396 0.08581238 -0.09523546 -0.009937465 0.08438795 -0.09653079 -0.009521663 0.08473718 -0.09621316 -0.009660482 0.08370357 -0.09715318 -0.009174346 0.08404296 -0.09684449 -0.009359538 0.08305037 -0.09774726 -0.008737564 0.08337348 -0.09745335 -0.00896728 0.082735 -0.09803396 -0.008485913 0.08243107 -0.09831041 -0.008215308 0.08213657 -0.09857815 -0.00792402 0.08185189 -0.09883707 -0.007612526 0.08158087 -0.0990836 -0.007284462 0.08132135 -0.09931957 -0.006937801 0.08107358 -0.09954488 -0.006572842 0.08084166 -0.0997557 -0.006194055 0.08062356 -0.09995406 -0.005799055 0.080419 -0.10014 -0.005387842 0.08150219 -0.099155 -0.03799575 0.08046799 -0.100096 -0.0347408 0.08051908 -0.100049 -0.03513199 0.08058875 -0.09998577 -0.03552025 0.08043467 -0.100126 -0.03434544 0.08077627 -0.0998153 -0.03627306 0.08067417 -0.09990805 -0.03590047 0.08102649 -0.09958767 -0.03699266 0.08089476 -0.09970748 -0.03663796 0.08168387 -0.09898978 -0.03830736 0.0822857 -0.09844255 -0.03917509 0.08207559 -0.09863358 -0.03889697 0.08261388 -0.09814417 -0.03957325 0.08690595 -0.0942409 -0.009994506 0.08654189 -0.09457206 -0.009999692 0.08727079 -0.09390908 -0.009965002 0.09331017 -0.08841687 -0.04039996 0.131638 -0.09321409 -0.04039996 0.128215 -0.0936644 -0.04039996 0.145298 -0.09117978 -0.04039996 0.148706 -0.09061288 -0.04039996 0.15211 -0.09002268 -0.04039996 0.138474 -0.09224361 -0.04039996 0.141888 -0.09172338 -0.04039996 0.135058 -0.09274047 -0.04039996 0.1247889 -0.09409129 -0.04039996 0.12136 -0.09449487 -0.04039996 0.117928 -0.09487509 -0.04039996 0.114493 -0.09523206 -0.04039996 0.111055 -0.09556567 -0.04039996 0.107613 -0.09587597 -0.04039996 0.104169 -0.09616285 -0.04039996 0.100722 -0.0964266 -0.04039996 0.09727096 -0.09666687 -0.04039996 0.09381729 -0.09688377 -0.04039996 0.09036058 -0.09707748 -0.04039996 0.08690077 -0.09724777 -0.04039996 0.08343786 -0.09739476 -0.04039996 0.08302146 -0.09942203 -0.005501329 0.08258086 -0.1001108 -0.004352331 0.08533447 -0.098374 -0.007161676 0.08500707 -0.09824818 -0.007090628 0.08437162 -0.09924978 -0.00633502 0.08352327 -0.1000208 -0.005261421 0.08301067 -0.1004865 -0.0043118 0.08415257 -0.0990253 -0.006345331 0.08340466 -0.09970539 -0.00541383 0.08639544 -0.09740841 -0.007709562 0.0859431 -0.09739691 -0.007627844 0.08736848 -0.09652364 -0.007962703 0.08693325 -0.0964964 -0.007941246 0.08201158 -0.09982907 -0.004500746 0.08247905 -0.09918916 -0.00573033 0.0879485 -0.09557318 -0.008021652 0.08836358 -0.09561884 -0.007992684 0.08341008 -0.0985341 -0.006627976 0.08379215 -0.09873801 -0.006442844 0.08430266 -0.09772241 -0.007406473 0.08464503 -0.09649425 -0.00878489 0.08356684 -0.09747475 -0.008170545 0.08729434 -0.09482896 -0.008471906 0.08661538 -0.09617024 -0.008062362 0.08764606 -0.09523296 -0.008143663 0.08895897 -0.09465426 -0.007866621 0.09238058 -0.09154266 -0.005083322 0.09242159 -0.09192836 -0.005325734 0.08993506 -0.09376657 -0.007480859 0.08996468 -0.09416282 -0.007553637 0.09081971 -0.09071594 -0.007933259 0.09028774 -0.09136253 -0.00789982 0.08622211 -0.09580397 -0.008387863 0.09284716 -0.08883798 -0.005465686 0.09248584 -0.08919996 -0.005700528 0.08923834 -0.09231692 -0.008600056 0.09355801 -0.08842211 -2.14446e-7 0.09352451 -0.08842498 -0.001396358 0.09207528 -0.08953988 -0.006801664 0.09087133 -0.09333813 -0.007002532 0.09084808 -0.09293627 -0.006875514 0.0884307 -0.09396839 -0.008217096 0.09035629 -0.09204447 -0.007259249 0.0893923 -0.09292101 -0.007899224 0.08966273 -0.0933988 -0.007594108 0.09058958 -0.09255629 -0.006979227 0.09257507 -0.08972561 -0.004274249 0.09308749 -0.08900815 -0.002999782 0.08867186 -0.09429991 -0.007986068 0.09197407 -0.09057354 -0.005365192 0.09196037 -0.09016036 -0.00559014 0.09122544 -0.09125399 -0.006406188 0.09167128 -0.0921877 -0.006068468 0.09170061 -0.09258395 -0.006250619 0.09301859 -0.0913853 -0.004249691 0.09295499 -0.09102028 -0.003949046 0.09336823 -0.08876347 -0.001526534 0.09302634 -0.08961647 -0.002846121 0.09315711 -0.09022134 -0.002738356 0.09329909 -0.08939325 -0.001448214 0.09347414 -0.09097099 -0.00305283 0.09337776 -0.09063577 -0.002698898 0.09363657 -0.09040045 -0.001369535 0.09342771 -0.09000563 -0.001391351 0.09375423 -0.09037637 2.19569e-7 0.09373188 -0.0907365 -0.001989841 0.09388172 -0.09060001 -9.15042e-4 0.09354698 -0.08999258 0 0.09391599 -0.09056937 0 0.09185719 -0.0897383 -0.007106304 0.09162956 -0.08994525 -0.007398366 0.09114778 -0.09038341 -0.007941663 0.0924822 -0.08916985 -0.006155908 0.0926702 -0.08899885 -0.005815744 0.09123337 -0.09050256 -0.006967723 0.09316718 -0.08854699 -0.004737198 0.09331017 -0.08841687 -0.004358887 0.09301286 -0.0886873 -0.005106151 0.0908941 -0.09061419 -0.0081923 0.09063339 -0.09085118 -0.008427619 0.08528047 -0.09683316 -0.00796765 0.08561009 -0.09708458 -0.007744431 0.0881161 -0.09333735 -0.009047985 0.08708637 -0.0945928 -0.008821427 0.08824622 -0.09366255 -0.008525371 0.08695352 -0.09439492 -0.009230017 0.08596998 -0.09560805 -0.008733034 0.08497709 -0.0966354 -0.008270263 0.08578515 -0.09545749 -0.009141385 0.08465969 -0.09794878 -0.007199347 0.08396214 -0.09755831 -0.007689118 0.08303558 -0.0984013 -0.006881892 0.08917576 -0.09488022 -0.007842063 0.08258175 -0.09837073 -0.007315874 0.08194452 -0.0991342 -0.006046593 0.08139503 -0.09975308 -0.00475955 0.08376926 -0.09712743 -0.00889188 0.08288246 -0.09789985 -0.008600413 0.08261638 -0.0981419 -0.008376061 0.08170247 -0.09902578 -0.006850719 0.08210575 -0.09860616 -0.007884263 0.08186167 -0.09882819 -0.007617115 0.08090114 -0.09984266 -0.005031824 0.08162695 -0.0990417 -0.007335662 0.08140081 -0.09924739 -0.007039904 0.08041638 -0.1001367 -0.005387842 0.0811848 -0.09944367 -0.006731986 0.08097916 -0.09963065 -0.006412088 0.0805965 -0.0999788 -0.005739569 0.0807833 -0.09980887 -0.006080627 0.08401107 -0.09687346 -0.009340941 0.0837199 -0.0971384 -0.009180843 0.08315515 -0.09765189 -0.008809447 0.08616316 -0.09495133 -0.009689927 0.08614879 -0.09492945 -0.009973645 0.08583641 -0.09521359 -0.009937882 0.08521509 -0.0957787 -0.009808778 0.08490908 -0.09605687 -0.009717941 0.08430659 -0.09660476 -0.009483814 0.08235728 -0.09837746 -0.008137106 0.08740329 -0.09378868 -0.00995475 0.08709079 -0.09407287 -0.009988009 0.08661192 -0.09450864 -0.009997665 0.08552527 -0.09549659 -0.009882509 0.08343487 -0.09739756 -0.009003698 0.08860737 -0.09272831 -0.009355425 0.08863317 -0.0926702 -0.009631812 0.08831244 -0.09296184 -0.009728074 0.08771228 -0.0935077 -0.009886085 0.08460599 -0.09633249 -0.00960952 0.08980977 -0.09160017 -0.009042978 0.08952325 -0.09186077 -0.009216964 0.08893448 -0.09239619 -0.009516775 0.08927106 -0.09260606 -0.008226692 0.09009039 -0.09134495 -0.008853375 0.09204715 -0.08976268 -0.005831301 0.09118038 -0.09086966 -0.006673514 0.08923161 -0.09212595 -0.009374797 0.0902751 -0.09169298 -0.007561028 0.09036499 -0.09109526 -0.008648216 0.09142518 -0.09179586 -0.006159603 0.09228396 -0.0893501 -0.00648427 0.09139287 -0.09016048 -0.007677137 0.09214514 -0.0911417 -0.005159318 0.09272813 -0.09061139 -0.004007577 0.09260469 -0.09017258 -0.004124939 0.09271222 -0.08915227 -0.00451976 0.09337323 -0.08841419 -0.003170192 0.09340488 -0.08947944 0 0.09341347 -0.08894115 0 -0.1382009 -0.0569269 -0.037 -0.142126 -0.05683469 -0.04627007 -0.1382009 -0.0569269 -0.04670029 -0.146048 -0.05674254 -0.04581636 -0.15388 -0.05655866 -0.04483854 -0.149966 -0.05665057 -0.04533928 -0.1616989 -0.0563752 -0.04376697 -0.157791 -0.05646687 -0.0443145 -0.169503 -0.05619198 -0.04260134 -0.165603 -0.05628347 -0.0431959 -0.177294 -0.05600905 -0.0413419 -0.1734 -0.05610048 -0.04198336 -0.18507 -0.05582648 -0.03998845 -0.181183 -0.05591768 -0.04067689 -0.1928319 -0.05564427 -0.03854119 -0.188952 -0.05573529 -0.03927659 -0.200579 -0.05546236 -0.037 -0.196707 -0.05555325 -0.03778225 -0.1382009 -0.0569269 -0.037 -0.1389639 -0.08944237 -0.0376175 -0.138976 -0.08993309 -0.037 -0.138952 -0.08893465 -0.03821706 -0.138927 -0.08786851 -0.03936219 -0.13894 -0.08840996 -0.03879857 -0.1389 -0.08673459 -0.04043525 -0.138914 -0.08730995 -0.03990775 -0.138872 -0.0855329 -0.04143649 -0.138887 -0.08614218 -0.04094487 -0.138842 -0.0842635 -0.04236567 -0.138858 -0.08490657 -0.04191005 -0.138812 -0.08294516 -0.04320657 -0.138827 -0.08361035 -0.04279714 -0.138779 -0.08157318 -0.04396355 -0.138796 -0.08226621 -0.04359537 -0.138476 -0.06867307 -0.04667729 -0.138712 -0.07869917 -0.04521036 -0.138729 -0.07943105 -0.04493367 -0.138417 -0.06614172 -0.04669308 -0.138746 -0.08015257 -0.0446344 -0.138763 -0.08086645 -0.04431104 -0.1385129 -0.07014214 -0.04669696 -0.1386229 -0.07492327 -0.04624265 -0.1386409 -0.07568866 -0.04608488 -0.138659 -0.07644778 -0.04590326 -0.138677 -0.07720446 -0.04569625 -0.138532 -0.07103258 -0.04667794 -0.138568 -0.07259297 -0.04657298 -0.1385869 -0.07337319 -0.04648625 -0.13855 -0.07181417 -0.04663717 -0.1386049 -0.07415145 -0.04637646 -0.138694 -0.07795697 -0.04546457 -0.1384491 -0.06749206 -0.04669141 -0.1383846 -0.06476837 -0.04668295 -0.1382005 -0.0569269 -0.04670023 -0.128203 -0.05716156 -0.037 -0.128203 -0.05716156 -0.04753112 -0.1284701 -0.06852692 -0.04751193 -0.128736 -0.07983726 -0.04588788 -0.1287519 -0.08054208 -0.04560226 -0.1286849 -0.07766318 -0.04661059 -0.1286669 -0.07692706 -0.04680478 -0.1285428 -0.07161009 -0.0474925 -0.128719 -0.07912117 -0.04615145 -0.128702 -0.07839459 -0.04639285 -0.128597 -0.07392299 -0.04732537 -0.128579 -0.07316517 -0.04740488 -0.12865 -0.07618618 -0.04697525 -0.128632 -0.07543617 -0.04711496 -0.128561 -0.07240676 -0.04746729 -0.128615 -0.07467991 -0.04722869 -0.128769 -0.08123856 -0.0452941 -0.128785 -0.08192676 -0.04496306 -0.128801 -0.08260691 -0.04460924 -0.128832 -0.08392196 -0.04384106 -0.128816 -0.08327156 -0.04423534 -0.128861 -0.08518707 -0.04298806 -0.128847 -0.08456045 -0.04342526 -0.12889 -0.08639806 -0.04205489 -0.128876 -0.08580189 -0.04252946 -0.128917 -0.08754307 -0.04105108 -0.128903 -0.08697795 -0.04156249 -0.128942 -0.0886287 -0.03997117 -0.12893 -0.08809328 -0.04052054 -0.128966 -0.08963745 -0.03883165 -0.1289539 -0.0891422 -0.03940939 -0.128988 -0.09057527 -0.03762698 -0.128977 -0.09011518 -0.03823757 -0.128998 -0.0910179 -0.037 0.02379649 -0.06073009 -0.037 0.01904767 -0.06061857 -0.04543495 0.02379649 -0.06073009 -0.04513365 0.01193779 -0.06045162 -0.04586046 -0.002310335 -0.06011712 -0.04661101 0.004800915 -0.06028407 -0.04625105 -0.01181018 -0.05989408 -0.04703849 -0.128203 -0.05716156 -0.037 -0.02130705 -0.0596711 -0.04740726 -0.030806 -0.05944812 -0.04771786 -0.04030686 -0.05922508 -0.04796993 -0.05456799 -0.05889028 -0.04823881 -0.04744338 -0.05905759 -0.04811918 -0.06169348 -0.05872297 -0.04832196 -0.06880694 -0.05855602 -0.04837584 -0.0830698 -0.0582211 -0.04838174 -0.0759443 -0.05838847 -0.04839348 -0.09257078 -0.05799812 -0.04831254 -0.1020718 -0.05777508 -0.04818493 -0.1115758 -0.05755186 -0.0479989 -0.1210638 -0.05732917 -0.04775488 -0.128203 -0.05716156 -0.04753118 0.02379649 -0.06073009 -0.037 0.02288687 -0.0994715 -0.0374673 0.0228855 -0.09953218 -0.037 0.02288889 -0.0993871 -0.03792846 0.02289456 -0.09914737 -0.03883236 0.02289146 -0.0992791 -0.03838348 0.02290236 -0.09881305 -0.03971189 0.02289819 -0.0989921 -0.03927516 0.02291226 -0.09839218 -0.04055035 0.02290707 -0.09861236 -0.0401386 0.02293777 -0.09730547 -0.04207456 0.02291798 -0.09815061 -0.04095119 0.02314716 -0.08838725 -0.04515516 0.02297908 -0.09554517 -0.04362016 0.02297008 -0.09592807 -0.04334837 0.0234844 -0.07402062 -0.04514396 0.02296149 -0.09629666 -0.04305708 0.02299809 -0.09473866 -0.0441038 0.02298837 -0.09514915 -0.04387158 0.023018 -0.0938878 -0.04450136 0.02312976 -0.08912777 -0.04516297 0.02302825 -0.09344977 -0.04466515 0.02300798 -0.094316 -0.04431515 0.02309489 -0.09060734 -0.04516452 0.0230602 -0.09209048 -0.045017 0.02311456 -0.08977568 -0.04515928 0.0230388 -0.0930019 -0.04480659 0.02308207 -0.09116005 -0.04513508 0.02307116 -0.0916239 -0.04508709 0.02304935 -0.0925498 -0.04492348 0.02295315 -0.09664839 -0.04274857 0.02294528 -0.09698408 -0.04242175 0.02293068 -0.09760677 -0.04171419 0.02292406 -0.09788811 -0.04134047 0.02379643 -0.06073009 -0.0451337 0.03379368 -0.06096476 -0.037 0.03379368 -0.06096476 -0.04481643 0.03292489 -0.09797388 -0.04126566 0.03337323 -0.07887572 -0.04482936 0.03293168 -0.09768289 -0.04163199 0.03293889 -0.09737515 -0.04198086 0.03294646 -0.0970509 -0.04231226 0.03295457 -0.09670668 -0.042629 0.03296297 -0.09634816 -0.04292637 0.03297179 -0.09597641 -0.04320394 0.03298085 -0.0955885 -0.04346346 0.03299027 -0.09518796 -0.04370266 0.03299987 -0.0947774 -0.0439195 0.03300976 -0.0943551 -0.04411464 0.03301995 -0.09392106 -0.04428809 0.03303027 -0.093481 -0.04443764 0.03310769 -0.09018611 -0.04483669 0.03304076 -0.09303486 -0.04456329 0.03305149 -0.09257805 -0.04466038 0.03306227 -0.09211939 -0.04473769 0.03308397 -0.09119486 -0.04481679 0.03307306 -0.09165889 -0.04479497 0.03291845 -0.09824359 -0.04088759 0.03291267 -0.09849339 -0.04049575 0.0329023 -0.0989331 -0.03967326 0.03290718 -0.098724 -0.04008978 0.03289407 -0.09928476 -0.03881227 0.03289794 -0.0991196 -0.03924816 0.03288799 -0.09954559 -0.03791874 0.03289067 -0.0994277 -0.03836739 0.03288406 -0.09971147 -0.037 0.03288567 -0.09964019 -0.03746294 0.1767539 -0.0643211 -0.037 0.1695881 -0.06415283 -0.03994405 0.157778 -0.06387555 -0.04049521 0.1767539 -0.0643211 -0.03959774 0.1434819 -0.06353992 -0.04112929 0.03379368 -0.06096476 -0.037 0.1290203 -0.06320041 -0.04173463 0.1171076 -0.06292068 -0.04220527 0.1076119 -0.06269776 -0.04256349 0.09824466 -0.06247794 -0.04290163 0.086277 -0.06219691 -0.04331237 0.07198059 -0.06186127 -0.04376959 0.06001222 -0.0615803 -0.04412442 0.05043315 -0.06135547 -0.04439115 0.04098755 -0.06113362 -0.04463875 0.03379368 -0.06096476 -0.04481649 0.176239 -0.08626818 -0.03962427 0.176257 -0.08548641 -0.0396226 0.176248 -0.08586847 -0.03963357 0.176218 -0.08717119 -0.0395388 0.176229 -0.08669656 -0.03959256 0.1762059 -0.0876947 -0.03946286 0.1762779 -0.08458822 -0.03963047 0.1761929 -0.0882107 -0.0393638 0.176182 -0.0887193 -0.03924149 0.1761699 -0.0892204 -0.03909587 0.176158 -0.08971399 -0.03892707 0.176147 -0.09020006 -0.03873497 0.176136 -0.09067881 -0.03851968 0.1763162 -0.08297538 -0.03961914 0.1767539 -0.0643211 -0.037 0.1767541 -0.0643211 -0.0395978 0.176136 -0.09067881 -0.037 -0.200578 -0.04945659 -0.037 0.226821 -0.05949068 -0.03999996 -0.200578 -0.04945659 -0.03999996 0.226821 -0.05949068 -0.037 -0.200578 -0.04945659 -0.03999996 0.226821 -0.05949068 -0.03999996 0.226821 -0.05648988 -0.03999996 -0.200578 -0.0464558 -0.03999996 0.360382 -0.04363405 -0.002999901 0.455 -0.04651415 -0.002999961 0.360296 -0.04352694 -0.002999961 0.360222 -0.04341149 -0.002999961 0.36059 -0.04381209 -0.002999961 0.360711 -0.04387629 -0.002999901 0.360977 -0.04393649 -0.002999961 0.36048 -0.04373019 -0.002999961 0.360841 -0.04391878 -0.002999901 0.455 -0.04701435 -0.002999961 0.3600749 -0.04522353 -0.005128145 0.3600251 -0.04340499 -0.003557682 0.36037 -0.04549485 -0.004856765 0.3603443 -0.04359221 -0.003000319 0.3599962 -0.04493784 -0.005414009 0.36 -0.04340416 -0.003881454 0.3601204 -0.04340767 -0.003210365 0.360222 -0.04341149 -0.002999961 0.3605417 -0.04378068 -0.003000915 0.360841 -0.04391878 -0.002999901 0.360711 -0.04387629 -0.002999901 0.3606916 -0.0456115 -0.004739999 0.3609766 -0.04564714 -0.004704415 0.360977 -0.04393649 -0.002999961 0.36 -0.04493767 -0.005414187 0.36 -0.04340416 -0.02599996 0.36 -0.04493767 -0.02599996 0.36 -0.04340416 -0.003881454 0.455 -0.04894 -0.004997014 0.360977 -0.04565173 -0.004700899 0.3609696 -0.04586774 -0.005040287 0.3609671 -0.04594278 -0.005414068 0.455 -0.04901653 -0.005414187 0.455 -0.0487225 -0.004707098 0.3605821 -0.04584896 -0.02599996 0.3609659 -0.04594659 -0.02599996 0.3609663 -0.04594302 -0.005414187 0.3602634 -0.04562532 -0.02599996 0.3604709 -0.04580289 -0.005414187 0.3600683 -0.04533827 -0.005414187 0.3600348 -0.04522651 -0.02599996 0.36 -0.04493767 -0.02599996 0.36 -0.04493767 -0.005414187 -0.2906644 -0.04956609 -1.51875e-6 -0.2905223 -0.04681527 -0.002836048 -0.2907611 -0.044779 -0.003542959 -0.2903772 -0.04380333 -0.005945265 -0.290289 -0.04199981 -0.00780642 -0.2906693 -0.04199987 -0.00589931 -0.2910971 -0.04609435 -0.001331865 -0.2911368 -0.04765969 0 -0.291479 -0.04334175 -0.00175178 -0.2918898 -0.04384887 0 -0.2909852 -0.04297721 -0.003886044 -0.2921581 -0.04200029 9.15291e-7 -0.2915509 -0.04574799 0 -0.2913829 -0.04200011 -0.002831459 -0.2904137 -0.05685043 0 -0.2902368 -0.05258512 -0.005774557 -0.2902442 -0.05327874 -0.004820942 -0.2901701 -0.05258059 -0.005857348 -0.2900004 -0.04794919 -0.01203751 -0.2899991 -0.04669821 -0.01282745 -0.29 -0.04580819 -0.01324629 -0.2899997 -0.04535073 -0.01342183 -0.2899998 -0.043935 -0.01381027 -0.29 -0.04297375 -0.01395207 -0.29 -0.04488527 -0.0135743 -0.2899999 -0.04199999 -0.01399993 -0.2902132 -0.05350613 -0.004220664 -0.2901388 -0.05079263 -0.008302867 -0.2903603 -0.05551558 -0.001447141 -0.2903294 -0.05413377 -0.003594696 -0.2902314 -0.05429363 -0.001874685 -0.2900622 -0.05254924 -0.004108071 -0.2901242 -0.05346882 0 -0.29 -0.05198764 -0.004489719 -0.2900007 -0.05199992 -0.003999173 -0.2899995 -0.05200004 0 -0.2904201 -0.05629485 -8.68351e-4 -0.2905751 -0.05871915 7.59376e-7 -0.2905295 -0.05759525 -3.56515e-4 -0.2905978 -0.05842584 -1.35791e-4 -0.2906562 -0.04956316 0 -0.2906402 -0.05940884 5.23386e-6 -0.2906169 -0.05786669 -2.12415e-4 -0.2906522 -0.05817145 3.38355e-7 -0.2904136 -0.05525952 -0.002201974 -0.2904815 -0.05621111 -0.001265466 -0.2904951 -0.05675894 -8.11989e-4 -0.2905428 -0.0566616 -8.78066e-4 -0.2904869 -0.0558511 -0.001556038 -0.2904414 -0.052073 -0.004050552 -0.290656 -0.0530591 0 -0.2904177 -0.05412316 -0.003275215 -0.2905637 -0.05753326 -4.17856e-4 -0.2900503 -0.05153316 -0.007454097 -0.29 -0.05141818 -0.007361233 -0.29 -0.05124145 -0.007820487 -0.29 -0.05157208 -0.006893873 -0.2900632 -0.05220144 -0.005860388 -0.29 -0.05189228 -0.005459785 -0.29 -0.05195176 -0.004976272 -0.2905802 -0.05691492 -6.12486e-4 -0.2899923 -0.05101799 -0.00833249 -0.29 -0.05180877 -0.005943953 -0.2905831 -0.05495476 -0.001096606 -0.2903124 -0.05276072 -0.00516808 -0.2901061 -0.05138015 -0.007751822 -0.2900074 -0.05049324 -0.009307086 -0.29 -0.05170196 -0.00642246 -0.29 -0.0487079 -0.01141619 -0.29 -0.04833447 -0.01173746 -0.29 -0.04906737 -0.01107525 -0.2900009 -0.04940581 -0.01072037 -0.29 -0.04972767 -0.01034665 -0.29 -0.05003207 -0.009956479 -0.29 -0.04754215 -0.0123232 -0.2902824 -0.0512017 -0.00660777 -0.29 -0.04712569 -0.01258605 -0.29 -0.04441189 -0.013704 -0.29 -0.04625815 -0.01304787 -0.29 -0.04345619 -0.01389288 -0.2900001 -0.04248803 -0.01398777 -0.2902904 -0.04199999 -0.007806718 -0.2408192 -0.1193071 -0.01880341 -0.253566 -0.09295046 -0.01902085 -0.2512309 -0.09393662 -0.02152174 -0.2391829 -0.1185181 -0.02155947 -0.253499 -0.09310156 -0.01882958 -0.2536214 -0.09277051 -0.01928395 -0.240795 -0.1192949 -0.01921635 -0.2406848 -0.1192429 -0.01974892 -0.253627 -0.09258979 -0.01962566 -0.253634 -0.09265935 -0.01948106 -0.2405149 -0.1191607 -0.02018249 -0.253568 -0.09248638 -0.01992315 -0.253606 -0.0925312 -0.01977366 -0.2402878 -0.119052 -0.0205903 -0.253256 -0.0924772 -0.02047467 -0.25344 -0.09244698 -0.02021408 -0.253354 -0.09245377 -0.02034926 -0.2529888 -0.0925883 -0.0207358 -0.25315 -0.09251511 -0.02058929 -0.2399688 -0.118898 -0.02098834 -0.2527533 -0.09272277 -0.02090787 -0.2522755 -0.09305471 -0.02116852 -0.2525144 -0.0928809 -0.02104985 -0.2395967 -0.1187185 -0.0213133 -0.2516909 -0.09352844 -0.02139323 -0.2520285 -0.09324818 -0.02127337 -0.2508322 -0.09431022 -0.02160871 -0.2504372 -0.09469336 -0.02167743 -0.2500256 -0.09510707 -0.02173453 -0.2495558 -0.09558904 -0.02177917 -0.2382853 -0.1180839 -0.02179753 -0.2386679 -0.1182685 -0.02174192 -0.2490347 -0.0961408 -0.02181082 -0.2379474 -0.1179202 -0.021797 -0.2484622 -0.09676003 -0.0218259 -0.2479175 -0.09736227 -0.02182072 -0.253512 -0.09245789 -0.02007108 -0.2379469 -0.1179178 -0.02180004 -0.2379928 -0.1200482 -0.02099734 -0.20147 -0.1201108 -0.01883119 -0.237948 -0.1184064 -0.02177232 -0.1421341 -0.1197897 -0.01578205 -0.2379593 -0.1190983 -0.02159291 -0.1989216 -0.1192979 -0.01926112 -0.1532242 -0.1180576 -0.01699292 -0.1535047 -0.1184815 -0.01696246 -0.1037206 -0.1191409 -0.01405018 -0.1037337 -0.119602 -0.01381498 -0.1037113 -0.1185569 -0.0142309 -0.1037091 -0.1182221 -0.01426881 -0.2379752 -0.1196404 -0.02130281 -0.1400354 -0.1207039 -0.01455545 -0.1438754 -0.1204597 -0.0151875 -0.1038205 -0.1208615 -0.01217198 -0.2380666 -0.1208595 -0.01970726 -0.2380152 -0.1203875 -0.02061051 -0.2380411 -0.1206763 -0.02015006 -0.2380937 -0.1209663 -0.01923477 -0.1038476 -0.1209756 -0.0116676 -0.1599079 -0.1210002 -0.01436144 -0.126245 -0.121 -0.01250267 -0.103868 -0.121 -0.01128286 -0.2045628 -0.1209995 -0.0168761 -0.238119 -0.121 -0.01880276 -0.1982138 -0.1188491 -0.01939415 -0.1949054 -0.1179683 -0.01933342 -0.1037812 -0.1205196 -0.01291728 -0.1037597 -0.1202005 -0.01331144 -0.1026369 -0.1199316 -0.01324713 -0.1030799 -0.1204037 -0.01290899 -0.1024029 -0.1203079 -0.01254099 -0.1031759 -0.1200435 -0.01337301 -0.1032792 -0.1206324 -0.01260864 -0.1037605 -0.120231 -0.01329708 -0.1031717 -0.1195642 -0.01375085 -0.1037405 -0.1197993 -0.01368862 -0.1037239 -0.1193095 -0.01398593 -0.1031206 -0.1191588 -0.01396125 -0.103713 -0.1187098 -0.01419901 -0.1037065 -0.1182273 -0.01429849 -0.1033959 -0.12085 -0.01209086 -0.1028909 -0.1207563 -0.01199722 -0.1022987 -0.1204782 -0.01193594 -0.1026031 -0.1207335 -0.01128321 -0.1022624 -0.1205419 -0.01128321 -0.1038456 -0.1209798 -0.01170212 -0.1032022 -0.1209324 -0.01128274 -0.1038674 -0.121012 -0.01128292 -0.1038193 -0.1208635 -0.01219159 -0.1037897 -0.1206245 -0.01275718 -0.1032073 -0.1209428 -0.01128286 -0.1038674 -0.1210108 0 -0.103868 -0.121 -0.01128286 -0.1028513 -0.12084 0 -0.1022605 -0.1205455 -0.01128286 -0.102266 -0.120536 0 -0.1737228 -0.1153611 0 -0.173727 -0.115363 -0.009499967 -0.1728915 -0.1173982 0 -0.1730465 -0.1169682 -0.009499967 -0.1722757 -0.1194619 -0.009499967 -0.1722485 -0.1195954 0 -0.171961 -0.121 0 -0.171961 -0.121 -0.009499967 -0.1730569 -0.1141333 0 -0.1731704 -0.1142203 -0.009499967 -0.1734292 -0.1145528 0 -0.1735759 -0.1148456 -0.009499967 -0.1737372 -0.1153604 0 -0.173727 -0.115363 -0.009499967 -0.1726627 -0.1138935 0 -0.1726209 -0.1138776 -0.009499967 -0.1720326 -0.1137501 0 -0.1721655 -0.1137703 -0.009499967 -0.1714932 -0.1137595 -0.009499967 -0.171494 -0.11377 0 -0.16793 -0.115586 0 -0.171494 -0.11377 -0.009499967 -0.171494 -0.11377 0 -0.16793 -0.115586 -0.009499967 -0.1674759 -0.114695 0 -0.16793 -0.115586 -0.009499967 -0.16793 -0.115586 0 -0.1674759 -0.114695 -0.009499967 -0.202226 -0.09699088 0 -0.1674759 -0.114695 -0.009499967 -0.1674759 -0.114695 0 -0.202226 -0.09699088 -0.009499967 -0.2026799 -0.09788185 0 -0.202226 -0.09699088 -0.009499967 -0.202226 -0.09699088 0 -0.2026799 -0.09788185 -0.009499967 -0.199116 -0.0996977 0 -0.2026799 -0.09788185 -0.009499967 -0.2026799 -0.09788185 0 -0.199116 -0.0996977 -0.009499967 -0.1988279 -0.1014217 0 -0.1988471 -0.1014657 -0.009499967 -0.1987145 -0.1008669 -0.009499967 -0.1987304 -0.1009979 0 -0.1987709 -0.1004621 0 -0.198872 -0.1001581 -0.009499967 -0.1991077 -0.09969288 0 -0.199116 -0.0996977 -0.009499967 -0.1990712 -0.1018155 0 -0.1992097 -0.1019788 -0.009499967 -0.1994417 -0.1021822 0 -0.1997942 -0.1024183 -0.009499967 -0.2000756 -0.1025716 0 -0.2005481 -0.1027846 -0.009499967 -0.20055 -0.10278 0 -0.2169811 -0.1196261 0 -0.2172695 -0.1209981 -0.009499967 -0.2166401 -0.1183371 -0.009499967 -0.216462 -0.1178119 0 -0.21726 -0.121 0 -0.2157469 -0.1159122 -0.009499967 -0.2158215 -0.1160874 0 -0.2148506 -0.1140589 0 -0.2134908 -0.111839 0 -0.2138046 -0.1123232 -0.009499967 -0.2147623 -0.113897 -0.009499967 -0.2127106 -0.1107958 -0.009499967 -0.2121081 -0.1100685 0 -0.2106032 -0.1084491 0 -0.2109677 -0.1088094 -0.009499967 -0.2088965 -0.1069717 0 -0.2093349 -0.1073279 -0.009499967 -0.2075397 -0.1059602 -0.009499967 -0.207403 -0.1058764 0 -0.204969 -0.1044485 -0.009499967 -0.2054703 -0.1047171 0 -0.2037836 -0.1039056 0 -0.2022476 -0.1032897 -0.009499967 -0.2020839 -0.1032402 0 -0.20055 -0.10278 0 -0.20055 -0.10278 -0.009499967 -0.126245 -0.121 -0.01250267 -0.171961 -0.121 -0.009499967 -0.1599086 -0.121 -0.0143615 -0.21726 -0.121 -0.009499967 -0.21726 -0.121 0 -0.238119 -0.121 0 -0.2045617 -0.121 -0.01687604 -0.238119 -0.121 -0.01880276 -0.103868 -0.121 -0.01128286 -0.103868 -0.121 0 -0.171961 -0.121 0 -0.240819 -0.119307 0 -0.240819 -0.119307 -0.01880276 -0.2404803 -0.1198757 -0.01880276 -0.2405115 -0.1198242 0 -0.2397485 -0.1205286 -0.01880276 -0.240032 -0.1203142 0 -0.2388564 -0.1209244 -0.01880276 -0.2387816 -0.1209286 0 -0.2394365 -0.1207045 0 -0.238119 -0.121 -0.01880276 -0.2381193 -0.1210066 0 -0.240819 -0.119307 0 -0.244219 -0.112282 -4.30583e-4 -0.244235 -0.112249 -8.56929e-4 -0.24647 -0.107629 -0.00713247 -0.246648 -0.10726 -0.007252752 -0.2408188 -0.1193069 -0.01880341 -0.250411 -0.09948408 -0.003311038 -0.2531423 -0.09383887 0 -0.250324 -0.09966325 -0.003688275 -0.244261 -0.112194 -0.001278996 -0.244213 -0.112293 0 -0.244298 -0.112118 -0.001696884 -0.244345 -0.11202 -0.002110481 -0.244403 -0.1119 -0.002519905 -0.244471 -0.111761 -0.002917826 -0.244548 -0.111601 -0.003306746 -0.244635 -0.11142 -0.003687322 -0.244731 -0.111222 -0.004053354 -0.244836 -0.111005 -0.004406213 -0.244951 -0.110768 -0.004746854 -0.245073 -0.110516 -0.00507009 -0.245485 -0.109665 -0.005938291 -0.2453399 -0.1099629 -0.005667328 -0.245202 -0.110248 -0.005376577 -0.245792 -0.109029 -0.006421864 -0.245635 -0.109354 -0.006189405 -0.245955 -0.108693 -0.006632566 -0.246294 -0.107992 -0.006988286 -0.253415 -0.09327667 -0.01804757 -0.253499 -0.09310156 -0.01882958 -0.247573 -0.10535 -0.007496893 -0.247386 -0.105736 -0.007496654 -0.253341 -0.09342908 -0.01726645 -0.2479439 -0.104583 -0.007423698 -0.247758 -0.104966 -0.007472515 -0.2531556 -0.09381121 -0.01305967 -0.2481279 -0.104202 -0.007350742 -0.248309 -0.103828 -0.007254064 -0.248488 -0.103457 -0.007133305 -0.2531391 -0.09384506 -0.01136672 -0.2490029 -0.102393 -0.006633996 -0.248836 -0.102739 -0.006823062 -0.248665 -0.103093 -0.00698924 -0.249323 -0.101733 -0.006192207 -0.249166 -0.102056 -0.006422936 -0.249619 -0.101121 -0.005668461 -0.249756 -0.100838 -0.005379974 -0.249474 -0.1014209 -0.005940377 -0.249886 -0.100569 -0.005072772 -0.250009 -0.100316 -0.004747927 -0.250227 -0.09986346 -0.004056572 -0.250122 -0.100081 -0.004410088 -0.250488 -0.09932398 -0.002921581 -0.250557 -0.0991832 -0.002520561 -0.250614 -0.09906458 -0.002114951 -0.250661 -0.09896659 -0.001700997 -0.250699 -0.09888941 -0.001278996 -0.250725 -0.09883475 -8.56929e-4 -0.250741 -0.09880179 -4.30584e-4 -0.250747 -0.09879046 0 -0.2531874 -0.09374552 -0.01489716 -0.253226 -0.09366589 -0.01570707 -0.253278 -0.09355878 -0.0164864 -0.247014 -0.106504 -0.00742346 -0.2471989 -0.106122 -0.007472097 -0.2468299 -0.106884 -0.007350146 -0.246122 -0.108348 -0.006820976 -0.2442319 -0.1122552 -8.76125e-4 -0.2041209 -0.09285736 -6.63844e-4 -0.204186 -0.09285068 -9.91838e-4 -0.244213 -0.112293 0 -0.2040603 -0.0928623 0 -0.2443448 -0.1120202 -0.002136647 -0.2046959 -0.09279805 -0.002218842 -0.204397 -0.09282886 -0.00162357 -0.2447306 -0.1112224 -0.004066884 -0.2445074 -0.1116855 -0.003115713 -0.2058385 -0.09267824 -0.003639817 -0.2053759 -0.0927267 -0.003157377 -0.2049633 -0.09276998 -0.002636253 -0.2068867 -0.09256535 -0.004500985 -0.207415 -0.09250712 -0.004854798 -0.2063496 -0.09262394 -0.004092514 -0.2451401 -0.1103763 -0.005256712 -0.2094464 -0.09227657 -0.005907952 -0.2079992 -0.09244203 -0.005200803 -0.2106943 -0.09212946 -0.006379783 -0.2460343 -0.1085292 -0.00672841 -0.2456396 -0.1093446 -0.006205976 -0.2465428 -0.1074779 -0.007200479 -0.2132517 -0.09181374 -0.007055461 -0.2119694 -0.09197455 -0.006760656 -0.2471818 -0.1061574 -0.007476747 -0.2145262 -0.09164983 -0.007271647 -0.2477471 -0.1049891 -0.007482945 -0.2161992 -0.09142768 -0.007450938 -0.2200779 -0.09088128 -0.007394492 -0.2185069 -0.09110772 -0.007500171 -0.2483959 -0.1036477 -0.007214784 -0.2212271 -0.09071165 -0.007254421 -0.2237876 -0.0903204 -0.006697833 -0.2224969 -0.09051978 -0.007023155 -0.2489989 -0.1024011 -0.006647706 -0.2250313 -0.09012377 -0.006283879 -0.2265266 -0.08988165 -0.005618155 -0.2495448 -0.1012748 -0.005832254 -0.2259087 -0.08998233 -0.005917131 -0.2276597 -0.08969455 -0.004954099 -0.2271131 -0.08978521 -0.005295693 -0.2287253 -0.08951538 -0.004136443 -0.2502744 -0.09976547 -0.003887772 -0.2500095 -0.1003144 -0.004758298 -0.2282168 -0.08960139 -0.004555881 -0.2291876 -0.08943641 -0.003692805 -0.2504926 -0.09931522 -0.002922177 -0.2296277 -0.08936184 -0.003190755 -0.2300177 -0.08929532 -0.002647578 -0.230256 -0.0892542 -0.002236306 -0.2304019 -0.08922898 -0.001937389 -0.25067 -0.09894835 -0.001653015 -0.23053 -0.08920717 -0.001629889 -0.2306472 -0.0891875 -0.001253306 -0.2507569 -0.09876912 -1.23041e-6 -0.23078 -0.08916485 -6.64394e-4 -0.2308353 -0.08915764 0 -0.2085644 -0.09237813 -0.005498766 -0.204536 -0.0928145 -0.001926243 -0.204279 -0.09284108 -0.001311361 0.08075189 -0.1002204 0 0.08063089 -0.1001674 -0.001568615 0.08041918 -0.10014 0 0.08093804 -0.1002808 -8.66098e-4 0.08062565 -0.100047 -0.004434823 0.08040773 -0.1001257 -0.005387485 0.08041894 -0.1001394 -0.003903687 0.08086478 -0.1001453 -0.002635657 0.0811389 -0.1000848 -0.003375887 0.08071225 -0.1000778 -0.003554701 0.08097451 -0.0999574 -0.004253447 0.08110028 -0.1002869 -0.001679539 0.08130443 -0.1005157 0 0.08136582 -0.1005329 -7.77671e-4 0.08185821 -0.1008234 -0.001695275 0.08189171 -0.1006502 -0.002293646 0.08156472 -0.1007598 2.13702e-7 0.08164358 -0.1007875 -8.46675e-4 0.08226799 -0.1008212 -0.0027408 0.0813992 -0.1003025 -0.002426981 0.081968 -0.1004252 -0.003067195 0.0830152 -0.1004818 -0.004306495 0.0825929 -0.1001191 -0.004350304 0.08232092 -0.1003379 -0.003710091 0.08247834 -0.1007754 -0.003199756 0.08151876 -0.1005418 -0.001585304 0.08268368 -0.1007028 -0.003637433 0.0804193 -0.1001366 -0.002574801 0.08157628 -0.1002052 -0.003204822 0.08172827 -0.1000323 -0.003914296 0.08140236 -0.09974366 -0.004751801 0.08210545 -0.0998665 -0.004472136 0.08134961 -0.09995645 -0.004076838 0.08083349 -0.09987294 -0.005076944 0.1027778 -0.1090694 -0.007724106 0.09013795 -0.0940051 -0.007476985 0.1110345 -0.1093977 2.38076e-7 0.09393221 -0.09055459 -1.91171e-6 0.09183484 -0.09246188 -0.006108701 0.1070734 -0.1092395 -0.006103932 0.1077589 -0.1092665 -0.005655407 0.1041346 -0.1091235 -0.007388114 0.1050447 -0.1091594 -0.007080256 0.08901798 -0.09502363 -0.007887244 0.10147 -0.1090177 -0.007917642 0.09978193 -0.1089515 -0.008010327 0.08819609 -0.09577101 -0.007999241 0.08719122 -0.09668487 -0.007940053 0.09811335 -0.1088858 -0.007910549 0.09684866 -0.1088357 -0.007719457 0.08592981 -0.0978319 -0.007511854 0.09575134 -0.1087923 -0.007455766 0.09480655 -0.1087549 -0.00715965 0.08475464 -0.09890067 -0.006711065 0.09393525 -0.1087207 -0.00681138 0.09321647 -0.1086916 -0.006467044 0.08385616 -0.09971779 -0.005726516 0.09253722 -0.1086654 -0.006084561 0.09189659 -0.10864 -0.005663156 0.09127068 -0.1086145 -0.005178689 0.08330535 -0.1002187 -0.004881501 0.09069287 -0.1085926 -0.004650473 0.08299654 -0.1004984 -0.004280447 0.09018695 -0.1085719 -0.004096806 0.08969962 -0.1085541 -0.003452003 0.08267199 -0.100707 -0.003609597 0.0893172 -0.1085384 -0.002807915 0.08241802 -0.1007953 -0.003077626 0.08207243 -0.1008366 -0.002286434 0.0890699 -0.108528 -0.002279162 0.08893269 -0.108523 -0.00191605 0.08182209 -0.1008185 -0.001572132 0.08881717 -0.108518 -0.00154376 0.08872735 -0.1085153 -0.001159071 0.08163481 -0.1007831 -7.83117e-4 0.08860659 -0.1085085 1.86785e-7 0.08156198 -0.100766 0 0.0910421 -0.0931828 -0.006863951 0.1057141 -0.1091856 -0.006808876 0.1064457 -0.1092147 -0.006458103 0.1083797 -0.1092916 -0.005172908 0.09262388 -0.09174442 -0.005002498 0.1089403 -0.109313 -0.004662036 0.09317624 -0.09124207 -0.003890275 0.1094726 -0.1093341 -0.004079401 0.1099203 -0.1093517 -0.003486394 0.0935437 -0.09090787 -0.002804696 0.110235 -0.109364 -0.002977132 0.110415 -0.109371 -0.002632498 0.09376841 -0.0907036 -0.001791179 0.110563 -0.109377 -0.00227499 0.110897 -0.109389 -0.001191377 0.1509522 -0.110902 -0.02799999 0.150979 -0.1108919 0 0.1505754 -0.1109675 0 0.1505752 -0.1109635 -0.02799999 0.1513209 -0.1106768 0 0.1512914 -0.1107049 -0.02799999 0.1515258 -0.1103755 -0.02799999 0.1515746 -0.1102637 0 0.1515973 -0.1097046 0 0.1516219 -0.1099897 -0.02799999 0.1515465 -0.1095893 -0.02799999 0.151325 -0.1092401 -0.02799999 0.151322 -0.1092427 0 0.0936833 -0.09025698 0 0.09382104 -0.09045904 0 0.2065293 -0.09151303 0 0.206778 -0.09155559 0 0.13963 -0.0976848 0 0.111037 -0.109396 0 0.151317 -0.109247 0 0.1515049 -0.109504 0 0.151422 -0.109368 0 0.151614 -0.109967 0 0.150575 -0.110957 0 0.1516 -0.110127 0 0.151566 -0.109652 0 0.151041 -0.110862 0 0.15118 -0.110783 0 0.151497 -0.110428 0 0.15141 -0.110563 0 0.150891 -0.1109189 0 0.150735 -0.110951 0 0.151304 -0.110682 0 0.15156 -0.110281 0 0.151603 -0.109808 0 0.093589 -0.09008157 0 0.09345036 -0.0896883 0 0.09351098 -0.08989149 0 0.09341198 -0.08947825 0 0.09339606 -0.08926355 0 0.09340345 -0.08904659 0 0.09343397 -0.08883351 0 0.0935626 -0.08842378 0 0.09348726 -0.08862507 0 0.207354 -0.0917887 0 0.207535 -0.09191048 0 0.207164 -0.09168869 0 0.206971 -0.09161078 0 0.2077 -0.0920512 0 0.20785 -0.09220975 0 0.207983 -0.09238386 0 0.208094 -0.09256941 0 0.208184 -0.09276419 0 0.2082509 -0.09296315 0 0.208296 -0.09315949 0 0.2083247 -0.09341478 0 0.2081609 -0.09955638 0 0.13963 -0.0976848 0 0.151317 -0.109247 0 0.151317 -0.109247 -0.02799999 0.13963 -0.0976848 -0.02799999 0.150575 -0.110957 -0.02799999 0.1515049 -0.109504 -0.02799999 0.151566 -0.109652 -0.02799999 0.151317 -0.109247 -0.02799999 0.151422 -0.109368 -0.02799999 0.151497 -0.110428 -0.02799999 0.15141 -0.110563 -0.02799999 0.151614 -0.109967 -0.02799999 0.1516 -0.110127 -0.02799999 0.150891 -0.1109189 -0.02799999 0.150735 -0.110951 -0.02799999 0.15118 -0.110783 -0.02799999 0.151041 -0.110862 -0.02799999 0.151304 -0.110682 -0.02799999 0.15156 -0.110281 -0.02799999 0.151603 -0.109808 -0.02799999 0.08520179 -0.108376 -0.02799999 0.13963 -0.0976848 -0.02799999 0.09820187 -0.0965535 -0.02799999 0.434379 -0.141104 -0.004999995 0.444082 -0.11221 -0.004999995 0.452655 -0.111406 -0.004999995 0.435507 -0.112996 -0.004999995 0.418354 -0.114514 -0.004999995 0.426932 -0.113764 -0.004999995 0.38341 -0.135217 -0.004999995 0.409775 -0.1152459 -0.004999995 0.392613 -0.116657 -0.004999995 0.401195 -0.115961 -0.004999995 0.375446 -0.117996 -0.004999995 0.38403 -0.117336 -0.004999995 0.358272 -0.119264 -0.004999995 0.36686 -0.118639 -0.004999995 0.341093 -0.12046 -0.004999995 0.349684 -0.119871 -0.004999995 0.48 -0.074225 -0.002999961 0.455 -0.074225 0 0.48 -0.074225 0 0.455 -0.074225 -0.002999961 0.4539177 -0.1108258 -0.004991233 0.4343793 -0.1411035 -0.005006492 0.4544018 -0.1106078 -0.004980802 0.4363085 -0.1416565 -0.004927992 0.4549015 -0.1103848 -0.004966497 0.4556168 -0.1100703 -0.004937648 0.4559769 -0.1099138 -0.004920065 0.4563607 -0.1097481 -0.004899442 0.4571857 -0.109398 -0.004844784 0.4378529 -0.1420977 -0.00475955 0.4577032 -0.1091812 -0.004805445 0.4586299 -0.1088006 -0.004721522 0.459145 -0.1085935 -0.004668533 0.4597867 -0.1083388 -0.004595935 0.4393367 -0.1425226 -0.004504621 0.4602333 -0.1081637 -0.00454086 0.4605883 -0.1080263 -0.004495203 0.4614315 -0.1077057 -0.004374861 0.4618077 -0.1075649 -0.004317402 0.4407603 -0.1429296 -0.004171133 0.462659 -0.1072525 -0.004177629 0.4631705 -0.1070686 -0.004086196 0.4672148 -0.1057122 -0.003153383 0.4437317 -0.1437796 -0.003181099 0.4666793 -0.1058816 -0.003300011 0.4422665 -0.1433601 -0.003723144 0.4640949 -0.106744 -0.003908991 0.4658902 -0.1061375 -0.003503799 0.4645839 -0.1065765 -0.003807663 0.4653448 -0.1063187 -0.003635704 0.467917 -0.1054946 -0.002949953 0.4450599 -0.1441598 -0.002597689 0.4684823 -0.1053239 -0.002778172 0.469381 -0.1050601 -0.002485454 0.4698165 -0.1049366 -0.002336978 0.446132 -0.144466 -0.002055287 0.4703685 -0.1047785 -0.002139449 0.4706925 -0.1046839 -0.002018272 0.4471768 -0.144765 -0.001466989 0.471352 -0.1044948 -0.00176239 0.4717504 -0.1043819 -0.001601219 0.4722193 -0.1042504 -0.001405298 0.4729033 -0.1040623 -0.001104295 0.4483852 -0.1451109 -6.95726e-4 0.4732794 -0.1039606 -9.32451e-4 0.4736381 -0.1038641 -7.63954e-4 0.4739287 -0.103787 -6.23929e-4 0.4744236 -0.1036577 -3.78132e-4 0.4747617 -0.1035705 -2.04913e-4 0.449355 -0.145388 0 0.4751502 -0.1034717 -2.05167e-7 0.4533399 -0.1110895 -0.004998564 0.452921 -0.1112822 -0.005000293 0.452655 -0.111406 -0.004999995 0.437767 -0.1461369 -0.003585338 0.437998 -0.14485 -0.004143536 0.4444222 -0.1439773 -0.00288999 0.4460321 -0.1444389 -0.002124905 0.442059 -0.144587 -0.003479301 0.445696 -0.145572 -0.00186342 0.4424934 -0.1434261 -0.003658354 0.4339796 -0.1445637 -0.00438404 0.4341058 -0.1434738 -0.004715144 0.438202 -0.143541 -0.004503667 0.4342545 -0.1421817 -0.004950106 0.4408009 -0.1429412 -0.004161059 0.4387596 -0.1423581 -0.00462681 0.4371768 -0.1419034 -0.004841566 0.4343794 -0.1411033 -0.005025923 0.445361 -0.146711 -0.001438021 0.44831 -0.146697 0 0.447999 -0.146989 0 0.448602 -0.146391 0 0.4480182 -0.1450048 -9.41002e-4 0.449124 -0.1457369 0 0.448873 -0.146071 0 0.447669 -0.147267 0 0.441794 -0.145812 -0.003074765 0.449355 -0.145388 0 0.444961 -0.147805 -8.65046e-4 0.447334 -0.1475239 0 0.433853 -0.1456567 -0.003892183 0.441481 -0.147001 -0.002496838 0.437514 -0.147357 -0.002829253 0.4337062 -0.1469352 -0.00311774 0.4453004 -0.1486555 4.24089e-6 0.4447152 -0.1488964 -4.93527e-6 0.441125 -0.148115 -0.001748085 0.4440954 -0.1491055 -1.31768e-6 0.440733 -0.149118 -8.41735e-4 0.4433497 -0.1493185 0 0.4424836 -0.1495196 0 0.437246 -0.148465 -0.001888334 0.4335561 -0.1482275 -0.00198239 0.4416091 -0.1496784 0 0.4407907 -0.1497899 0 0.4399414 -0.1498723 1.70429e-6 0.436973 -0.149422 -7.88715e-4 0.4390836 -0.1499292 0 0.438002 -0.1499629 -1.48218e-7 0.4334636 -0.1490352 -0.001027405 0.4365792 -0.1499484 -2.50963e-7 0.435096 -0.1498687 7.45052e-7 0.4333837 -0.1497181 -4.14896e-6 0.4468363 -0.1478618 -1.47865e-7 0.4460843 -0.1482923 -3.30003e-7 0.415 -0.147267 -5.09898e-4 0.415 -0.129584 -0.000999987 0.415 -0.146919 -0.000999987 0.415 -0.129584 0 0.415 -0.147584 0 0.415 -0.129584 0 0.39 -0.127696 0 0.39 -0.127696 -0.000999987 0.415 -0.129584 -0.000999987 0.39 -0.127696 -0.000999987 0.39 -0.127696 0 0.39 -0.144379 -5.09898e-4 0.39 -0.144032 -0.000999987 0.39 -0.1446959 0 0.4150006 -0.1469245 -0.001004159 0.4334584 -0.1490812 -9.84759e-4 0.3900004 -0.144038 -0.001004576 0.3825483 -0.1426786 -0.001617133 0.39 -0.1446959 0 0.3824137 -0.14384 -1.23997e-5 0.415 -0.147584 0 0.433385 -0.149707 0 0.3826985 -0.1413738 -0.002867043 0.4336104 -0.1477603 -0.002443909 0.433794 -0.1461699 -0.003619909 0.4339697 -0.1446485 -0.0043509 0.382838 -0.1401715 -0.00367093 0.3829945 -0.1388168 -0.004336416 0.3831567 -0.1374108 -0.004756033 0.4341515 -0.1430783 -0.004815518 0.3832924 -0.1362336 -0.004954874 0.4343791 -0.1411044 -0.005018889 0.38341 -0.135217 -0.004999995 0.345842 -0.136834 -7.40719e-4 0.3447159 -0.136074 -0.001009345 0.347636 -0.136828 -0.001126945 0.3834095 -0.1352178 -0.005025923 0.3484639 -0.1359882 -0.001794993 0.3503767 -0.1368168 -0.001676857 0.3521915 -0.1359058 -0.002481341 0.3540577 -0.136799 -0.002334296 0.3559231 -0.1358242 -0.00307399 0.3578419 -0.1367781 -0.002921581 0.3595413 -0.1357436 -0.003563344 0.3515677 -0.1376146 -0.0013749 0.3578372 -0.1377543 -0.002371966 0.347742 -0.1380259 0 0.3448563 -0.1373117 -5.20088e-6 0.3553258 -0.1385556 -0.001353204 0.362787 -0.135672 -0.003934264 0.36173 -0.1367542 -0.003437399 0.342314 -0.136124 -4.38502e-4 0.342357 -0.13665 0 0.365598 -0.1356105 -0.004209995 0.3656621 -0.1367276 -0.003874838 0.3615626 -0.1387918 -0.002236664 0.340568 -0.1361629 0 0.3616362 -0.1377959 -0.002904415 0.3696104 -0.1355212 -0.004525959 0.3696938 -0.1366967 -0.004239797 0.3737803 -0.1354294 -0.004765987 0.37378 -0.1366611 -0.004529058 0.369442 -0.139012 -0.003148198 0.3695771 -0.1378724 -0.00377804 0.3654752 -0.138904 -0.002724647 0.3734678 -0.1402716 -0.002745151 0.3735576 -0.1391215 -0.003513813 0.3790422 -0.1392571 -0.003896713 0.3828598 -0.1399818 -0.00378251 0.3790559 -0.1365943 -0.004794716 0.3830492 -0.1383448 -0.004504382 0.3831835 -0.1371775 -0.004811108 0.3801187 -0.1405742 -0.003202378 0.3778278 -0.1379336 -0.004377961 0.3827171 -0.1412134 -0.00298202 0.3791185 -0.1416882 -0.002197027 0.3715983 -0.1411902 -0.001658141 0.3824942 -0.1431484 -0.00102657 0.3781878 -0.1425756 -0.001085221 0.3795536 -0.1435321 4.49041e-6 0.3824145 -0.1438321 -7.50994e-6 0.349424 -0.137641 -9.0189e-4 0.3507081 -0.1387272 2.42235e-6 0.353064 -0.13853 -9.08162e-4 0.3542502 -0.1395149 1.55388e-6 0.356764 -0.139486 -7.45053e-4 0.3599633 -0.1396613 -0.001207411 0.3576388 -0.1402207 -2.8012e-6 0.360402 -0.140748 0 0.3632972 -0.140624 -8.17686e-4 0.3654552 -0.1399055 -0.001943647 0.3631494 -0.1412483 -1.02421e-6 0.3655896 -0.137837 -0.003377437 0.3668037 -0.1418572 2.13727e-7 0.3704532 -0.1424093 0 0.3776913 -0.1353433 -0.004912793 0.3736453 -0.1379041 -0.004111111 0.3825874 -0.1423373 -0.001983642 0.373196 -0.142785 0 0.3759308 -0.1431309 1.34966e-7 0.3323798 -0.119357 -0.00496906 0.341093 -0.12046 -0.004999995 0.38341 -0.135217 -0.004999995 0.3775101 -0.1353479 -0.004921913 0.3216735 -0.117986 -0.004698276 0.3714898 -0.13548 -0.004645347 0.3143995 -0.1170465 -0.00439763 0.3677968 -0.1355617 -0.004394233 0.3634962 -0.1356565 -0.004010498 0.3076063 -0.1161621 -0.004019677 0.3595308 -0.1357443 -0.003563225 0.300686 -0.1152557 -0.003542721 0.355934 -0.1358241 -0.003075957 0.2935502 -0.1143137 -0.002950906 0.3521993 -0.1359057 -0.002482891 0.2869232 -0.1134326 -0.002309322 0.3484673 -0.1359884 -0.001795947 0.2800441 -0.1125119 -0.001549065 0.3448916 -0.1360672 -0.001043915 0.2730074 -0.1115629 -6.7107e-4 0.342314 -0.136124 -4.38502e-4 0.268131 -0.1109009 0 0.340568 -0.1361629 0 0.2203301 -0.09388643 -3.33561e-7 0.2201623 -0.09988403 -2.08764e-7 0.2201704 -0.09388202 -0.00139898 0.2198022 -0.09987425 -0.002038598 0.220062 -0.09988135 -0.001104533 0.2193317 -0.09986138 -0.003065705 0.2196269 -0.09386724 -0.002832412 0.2188652 -0.09384644 -0.003929615 0.2185095 -0.09983897 -0.004141032 0.2178753 -0.09381943 -0.004852592 0.217487 -0.09981101 -0.005009591 0.2165272 -0.0937826 -0.005595982 0.2161047 -0.09977328 -0.00569117 0.2152312 -0.09374719 -0.005938589 0.2147853 -0.09973722 -0.005974948 0.2138118 -0.09971064 -0.00599265 0.2142853 -0.09372138 -0.006002604 0.2128711 -0.09968495 -0.005868136 0.2133134 -0.0936948 -0.005922377 0.2121969 -0.09366434 -0.005618929 0.2117744 -0.09965503 -0.005514264 0.210764 -0.09962743 -0.004955947 0.2111648 -0.09363615 -0.005110144 0.210402 -0.09361529 -0.004544258 0.2093748 -0.09958946 -0.003632128 0.2100154 -0.09960699 -0.004341959 0.2097157 -0.09359657 -0.003854274 0.2087696 -0.09957295 -0.002651393 0.2091697 -0.09358167 -0.003076255 0.2087358 -0.09356975 -0.00220406 0.2083094 -0.09956037 -0.001392126 0.2083772 -0.09355998 -8.99783e-4 0.2081509 -0.09955608 -3.33704e-7 0.208325 -0.0935586 0 0.20863 -0.09321945 -0.001958012 0.208386 -0.09321278 -9.92569e-4 0.2107438 -0.09362447 -0.004818677 0.210249 -0.09326368 -0.004436671 0.2082521 -0.09270149 -0.001031637 0.2081473 -0.09264624 0 0.2092005 -0.09358251 -0.003148853 0.2095558 -0.09310364 -0.003707051 0.20903 -0.09323036 -0.002870142 0.2086897 -0.09356862 -0.002071201 0.2083853 -0.09356039 -9.61324e-4 0.208325 -0.0935586 0 0.2083161 -0.09326392 2.28592e-7 0.210003 -0.0936042 -0.00417298 0.2093424 -0.09243381 -0.003907561 0.2089129 -0.09272593 -0.002943933 0.2085785 -0.09214484 -0.003138661 0.2096269 -0.091641 -0.00586903 0.21191 -0.0933091 -0.005522429 0.2127972 -0.09368073 -0.005819201 0.212852 -0.09333479 -0.005845844 0.2104847 -0.09179699 -0.006002902 0.2113029 -0.09166955 -0.007008135 0.212832 -0.09283196 -0.00599265 0.2118665 -0.0928049 -0.005662024 0.2099789 -0.0923177 -0.004758596 0.2107697 -0.09220474 -0.005513906 0.2109689 -0.09278142 -0.005175888 0.2117255 -0.09223002 -0.006030738 0.2130133 -0.09171676 -0.007552146 0.2126429 -0.09185576 -0.006940841 0.2169229 -0.09379345 -0.005410432 0.2167448 -0.09330135 -0.00554955 0.215008 -0.09177076 -0.007626533 0.2138091 -0.09188741 -0.007131278 0.2149296 -0.09373909 -0.005977153 0.2157968 -0.09328281 -0.005868315 0.21483 -0.09338879 -0.006009757 0.2138215 -0.09322047 -0.006028592 0.2148584 -0.09288799 -0.006159305 0.2159186 -0.09261333 -0.006160318 0.218415 -0.09348666 -0.004436671 0.2179353 -0.09382092 -0.004806578 0.216911 -0.09264063 -0.005818545 0.2166862 -0.09183394 -0.007187724 0.2172704 -0.0919817 -0.00654006 0.2190113 -0.09188073 -0.006114244 0.217629 -0.09346526 -0.005048394 0.2179669 -0.09240031 -0.005505561 0.2215024 -0.09203803 -0.00176984 0.2218163 -0.09195715 -0.001896321 0.2192352 -0.09203571 -0.005244374 0.2188218 -0.09242475 -0.004836618 0.2206742 -0.09207499 -0.003380596 0.222174 -0.09193611 -0.001778304 0.2217659 -0.0919249 -0.003059625 0.2207452 -0.09192812 -0.004276573 0.2208491 -0.09225428 -0.002210378 0.220341 -0.09188598 -0.005329132 0.2197059 -0.09186869 -0.005964756 0.219365 -0.09185928 -0.006253242 0.2218447 -0.09197783 0 0.2188829 -0.09384679 -0.003908336 0.219089 -0.09350508 -0.003703892 0.2200965 -0.09388005 -0.001675546 0.220033 -0.09353089 -0.001958012 0.2195663 -0.09386587 -0.002933025 0.2196339 -0.09351998 -0.002870142 0.2201905 -0.09303325 -0.002004027 0.2206135 -0.09275436 -0.001039087 0.2206433 -0.092835 0 0.2202991 -0.09340554 -0.001000702 0.2204108 -0.09333389 0 0.2203195 -0.09388607 -6.69056e-7 0.2202915 -0.09388494 -6.07273e-4 0.2211076 -0.09227311 -0.001117885 0.2210997 -0.09234565 0 0.221149 -0.09190809 -0.00425446 0.2177281 -0.0929653 -0.005172908 0.221925 -0.09192925 -0.002641975 0.222324 -0.0919401 -8.97431e-4 0.222261 -0.09193837 -0.001339912 0.2200326 -0.09205722 -0.004372119 0.222361 -0.09194117 -4.50783e-4 0.2206299 -0.09189391 -0.004987537 0.2183061 -0.0920102 -0.005973875 0.21706 -0.09226447 -0.006148874 0.222374 -0.09194147 0 0.2149124 -0.09231775 -0.006558001 0.2138342 -0.09255641 -0.006334722 0.2182469 -0.09182876 -0.007000625 0.21702 -0.09179526 -0.007550179 0.2160453 -0.09376937 -0.005754888 0.2149904 -0.09191966 -0.007126867 0.2127539 -0.09225827 -0.006382286 0.215719 -0.0917598 -0.007886409 0.214379 -0.0917232 -0.007999837 0.213945 -0.09371215 -0.005991697 0.211525 -0.0918253 -0.006561398 0.2101631 -0.09275972 -0.004549384 0.2097399 -0.09195053 -0.005050361 0.211035 -0.0932852 -0.005048394 0.2115449 -0.0936464 -0.00532639 0.209068 -0.0920462 -0.004124045 0.2081399 -0.09213119 -0.002145469 0.2085019 -0.09271115 -0.002010941 0.2087463 -0.09174895 -0.004416048 0.2078596 -0.09211361 -0.00108397 0.2080966 -0.09173178 -0.003427505 0.2076324 -0.09197252 0 0.2078968 -0.09157663 -0.00411278 0.2078559 -0.09154498 -0.004630506 0.207607 -0.09153831 -0.004258096 0.207378 -0.09153199 -0.003870189 0.207173 -0.09152638 -0.003472447 0.2069079 -0.09155124 -0.001742005 0.20699 -0.09152138 -0.003063499 0.206829 -0.09151697 -0.002642571 0.2073131 -0.09170687 -0.001190662 0.2070658 -0.09164202 0 0.2066929 -0.09151327 -0.002216219 0.2065809 -0.09151017 -0.001782298 0.206493 -0.09150779 -0.00134021 0.2063812 -0.09148973 -1.8371e-7 0.206431 -0.09150606 -8.97431e-4 0.206393 -0.09150511 -4.50783e-4 0.2076169 -0.09171783 -0.002350091 0.209393 -0.091587 -0.006255924 0.208416 -0.0915603 -0.00533235 0.210511 -0.09161746 -0.007002711 0.208723 -0.0915687 -0.005657792 0.2081249 -0.09155237 -0.004988431 0.211738 -0.09165108 -0.00755167 0.2097499 -0.09159678 -0.006525218 0.209049 -0.09157758 -0.00596565 0.2130399 -0.0916866 -0.007887184 0.2109079 -0.09162837 -0.007208228 0.210123 -0.09160697 -0.006774246 0.212164 -0.0916627 -0.007687628 0.211318 -0.09163957 -0.007391333 0.21381 -0.09217566 -0.006691455 0.213483 -0.0916987 -0.007949769 0.212599 -0.09167456 -0.007799565 0.2160617 -0.09212392 -0.006636798 0.214826 -0.09173536 -0.00798732 0.21393 -0.09171086 -0.00798732 0.216157 -0.09177178 -0.007799208 0.215274 -0.09174758 -0.007949352 0.217438 -0.0918067 -0.007390737 0.216592 -0.09178358 -0.007686674 0.221376 -0.09191429 -0.003869414 0.218632 -0.09183925 -0.006773412 0.217848 -0.09181785 -0.007206797 0.2185328 -0.09298717 -0.00454545 0.219006 -0.09184956 -0.006523191 0.2192225 -0.09300714 -0.003794193 0.2195587 -0.09244376 -0.004036009 0.220033 -0.09187757 -0.005655288 0.2197809 -0.09302198 -0.002938866 0.2201524 -0.09245955 -0.00312525 0.2208999 -0.0919013 -0.004627585 0.220473 -0.09260427 -0.00210011 0.221583 -0.09191989 -0.003469049 0.222062 -0.09193295 -0.002212524 0.48 -0.0491237 -0.0215559 0.48 -0.05229657 -0.02188044 0.48 -0.04975199 -0.02166557 0.48 -0.04849857 -0.02142339 0.48 -0.04787957 -0.02126896 0.48 -0.04665988 -0.02089309 0.48 -0.04606068 -0.02067375 0.48 -0.05346739 -0.02189302 0.48 -0.05038505 -0.02175295 0.48 -0.05102145 -0.02181798 0.48 -0.05165797 -0.02186036 0.48 -0.04726696 -0.02109265 0.48 -0.04546838 -0.02043497 0.48 -0.04488307 -0.02017676 0.48 -0.04430896 -0.01989787 0.48 -0.05469119 -0.02188277 0.48 -0.05670845 -0.00898683 0.48 -0.056225 -0.008999943 0.48 -0.05718797 -0.008948266 0.48 -0.07150638 -0.01893395 0.48 -0.07096385 -0.01927077 0.48 -0.07401239 -0.01696306 0.48 -0.07354027 -0.01739215 0.48 -0.05813515 -0.008794844 0.48 -0.05906516 -0.008540034 0.48 -0.05951654 -0.008376359 0.48 -0.07612645 -0.01457458 0.48 -0.0757395 -0.01508134 0.48 -0.07717716 -0.0129745 0.48 -0.05996018 -0.008188128 0.48 -0.06039375 -0.007976233 0.48 -0.07778197 -0.01184839 0.48 -0.06081324 -0.007742404 0.48 -0.07805269 -0.01127058 0.48 -0.07446998 -0.01651668 0.48 -0.07533305 -0.01557576 0.48 -0.05860298 -0.008679986 0.48 -0.06121969 -0.02188265 0.48 -0.06984835 -0.01989108 0.48 -0.06927537 -0.02017354 0.48 -0.07255077 -0.01820069 0.48 -0.05766355 -0.008884251 0.48 -0.0730533 -0.01780438 0.48 -0.06749606 -0.02088099 0.48 -0.068098 -0.02066749 0.48 -0.06869298 -0.0204333 0.48 -0.06250429 -0.02184146 0.48 -0.06688886 -0.02107524 0.48 -0.06627607 -0.02125418 0.48 -0.06565839 -0.02141004 0.48 -0.06440538 -0.02164769 0.48 -0.06503528 -0.02154189 0.48 -0.06313997 -0.02179819 0.48 -0.06377369 -0.02173405 0.48 -0.06186777 -0.0218721 0.48 -0.07041138 -0.01958894 0.48 -0.07490968 -0.01605445 0.48 -0.0764954 -0.0140537 0.48 -0.07684576 -0.01351976 0.48 -0.07748985 -0.0124166 0.48 -0.06122136 -0.007485508 0.48 -0.0557518 -0.008987367 0.48 -0.07830286 -0.01068228 0.48 -0.06161516 -0.007207334 0.48 -0.07853245 -0.01008689 0.48 -0.06199198 -0.00690931 0.48 -0.07874137 -0.009483635 0.48 -0.04265278 -0.01893585 0.48 -0.04212397 -0.01857727 0.48 -0.05528247 -0.008950412 0.48 -0.06235408 -0.006590306 0.48 -0.04160857 -0.01820039 0.48 -0.0789296 -0.00887227 0.48 -0.05481708 -0.008889198 0.48 -0.04110777 -0.01780569 0.48 -0.06269788 -0.006253004 0.48 -0.04061967 -0.0173915 0.48 -0.07909357 -0.008255898 0.48 -0.04014766 -0.01696097 0.48 -0.0396921 -0.01651459 0.48 -0.06302237 -0.005898475 0.48 -0.05435168 -0.008802711 0.48 -0.07923495 -0.00763303 0.48 -0.0633291 -0.00552541 0.48 -0.0793544 -0.007004559 0.48 -0.074225 -0.002999961 0.48 -0.06361418 -0.00513792 0.48 -0.03925186 -0.01605135 0.48 -0.0388295 -0.0155735 0.48 -0.06387799 -0.004735887 0.48 -0.05389398 -0.0086928 0.48 -0.0641213 -0.004318296 0.48 -0.03842449 -0.01507985 0.48 -0.03803688 -0.01457065 0.48 -0.06434047 -0.003890693 0.48 -0.06453669 -0.003451406 0.48 -0.05344378 -0.008559465 0.48 -0.03766858 -0.01404935 0.48 -0.05299764 -0.008401274 0.48 -0.07945376 -0.006374299 0.48 -0.06471025 -0.002999961 0.48 -0.07953208 -0.005740225 0.48 -0.03731936 -0.01351499 0.48 -0.03698939 -0.01296848 0.48 -0.05256277 -0.008221149 0.48 -0.07958745 -0.005103707 0.48 -0.03667908 -0.01241159 0.48 -0.0521391 -0.00801903 0.48 -0.07961738 -0.004466772 0.48 -0.03638696 -0.01184278 0.48 -0.07962387 -0.003782868 0.48 -0.03611534 -0.01126426 0.48 -0.05172318 -0.007793009 0.48 -0.0513218 -0.00754702 0.48 -0.07961297 -0.002311527 0.48 -0.05093485 -0.007281124 0.48 -0.03586578 -0.01067745 0.48 -0.03563809 -0.01008027 0.48 -0.05055946 -0.006992816 0.48 -0.03543227 -0.009476482 0.48 -0.074225 0 0.48 -0.07958817 0 0.48 -0.04953539 -0.006020426 0.48 -0.04986095 -0.006363928 0.48 -0.03508549 -0.008248925 0.48 -0.03494489 -0.007627189 0.48 -0.04867589 -0.004899859 0.48 -0.03473365 -0.006368756 0.48 -0.03465855 -0.005735516 0.48 -0.04922956 -0.0056625 0.48 -0.03482747 -0.007000565 0.48 -0.04894375 -0.005290031 0.48 -0.03524816 -0.008866548 0.48 -0.05020159 -0.006687045 0.48 -0.0431928 -0.01927566 0.48 -0.04374516 -0.01959699 0.48 -0.07203561 -0.01857739 0.48 -0.04842996 -0.004498422 0.48 -0.0345903 -0.004879891 0.48 -0.04820585 -0.004085898 0.48 -0.04800236 -0.003658592 0.48 -0.03454488 -0.003627598 0.48 -0.04782217 -0.003223657 0.48 -0.04766547 -0.002781093 0.48 -0.04753124 -0.002327203 0.48 -0.04742139 -0.001869499 0.48 -0.0473358 -0.001407861 0.48 -0.03457576 0 0.48 -0.04727447 -9.42459e-4 0.48 -0.04722499 0 0.48 -0.04723757 -4.73155e-4 0.48 -0.04729384 -0.001224279 0.455 -0.04727464 -0.001070976 0.48 -0.04722499 0 0.455 -0.04767209 -0.002847194 0.48 -0.04773408 -0.003028392 0.455 -0.04841113 -0.004493653 0.48 -0.04841995 -0.004496693 0.455 -0.04947036 -0.00597006 0.48 -0.04906964 -0.005463898 0.48 -0.04999017 -0.00651139 0.455 -0.05083936 -0.007229328 0.48 -0.05229741 -0.008114397 0.48 -0.05109989 -0.007401764 0.455 -0.0524398 -0.008181691 0.48 -0.05406236 -0.00875169 0.455 -0.05420678 -0.008785963 0.455 -0.05582392 -0.008998811 0.48 -0.05570071 -0.008992493 0.455 -0.0572502 -0.008949637 0.48 -0.05713069 -0.008962452 0.48 -0.05832886 -0.008753478 0.455 -0.05841153 -0.008733212 0.455 -0.05957353 -0.008362591 0.48 -0.05946111 -0.008406758 0.455 -0.06086754 -0.007719576 0.48 -0.06076341 -0.007781326 0.48 -0.06177133 -0.007091522 0.455 -0.06204295 -0.006877303 0.48 -0.06266057 -0.006303191 0.455 -0.06289148 -0.006050407 0.48 -0.06358504 -0.005193829 0.455 -0.06365376 -0.005095124 0.48 -0.06432038 -0.003951132 0.455 -0.06437236 -0.003842771 0.48 -0.06471025 -0.002999961 0.455 -0.06471025 -0.002999961 0.455 -0.04722499 0 0.455 -0.04793208 -0.003496587 0.455 -0.04701435 -0.002999961 0.455 -0.04811686 -0.003905773 0.455 -0.04727005 -8.99183e-4 0.455 -0.04651415 0 0.455 -0.04651415 -0.002999961 0.455 -0.04732578 -0.00134319 0.455 -0.04750329 -0.002220153 0.455 -0.04740345 -0.001783549 0.455 -0.04776847 -0.00308007 0.455 -0.04762506 -0.002653062 0.455 -0.04832285 -0.004307687 0.455 -0.0472365 -4.51443e-4 0.455 -0.04722499 0 0.337 -0.02487236 -0.01499998 0.337 -0.04265129 0 0.337 -0.02487236 0 0.337 -0.04265129 -0.01499998 0.3379992 -0.02386265 0 0.3379995 -0.02386635 -0.01499998 0.3375239 -0.02398401 0 0.3374891 -0.02399539 -0.01499998 0.3371118 -0.02439612 -0.01499998 0.3371234 -0.02436107 0 0.33699 -0.02487158 -0.01499998 0.3369938 -0.02487188 0 0.363 -0.02387237 0 0.338 -0.02387237 -0.01499998 0.338 -0.02387237 0 0.363 -0.02387237 -0.01499998 0.48 -0.07961624 -0.003450691 0.4799999 -0.07958751 0 0.5099999 -0.07799947 0 0.5099999 -0.07798415 -0.001895785 0.4800005 -0.07957071 -0.005031526 0.5100001 -0.07779079 -0.003957569 0.4800006 -0.07935529 -0.006989538 0.4799998 -0.07818394 -0.01098096 0.487498 -0.07831937 -0.008833944 0.487498 -0.07717186 -0.01158219 0.487498 -0.0755409 -0.01417249 0.4799998 -0.07700425 -0.01327896 0.51 -0.07613945 -0.009232997 0.5024726 -0.07631343 -0.01034247 0.5099998 -0.07498335 -0.0112847 0.5025067 -0.07461374 -0.01303476 0.487498 -0.07350099 -0.01644796 0.48 -0.07471054 -0.01627284 0.5099999 -0.07290047 -0.01396328 0.5025096 -0.07248449 -0.0154016 0.4800001 -0.07233369 -0.01837122 0.48 -0.07353746 -0.01740807 0.487497 -0.07110786 -0.0183475 0.51 -0.07169747 -0.01513797 0.5024889 -0.06998664 -0.01737403 0.5099999 -0.07037925 -0.01622301 0.487497 -0.06844139 -0.01981258 0.4799998 -0.06775552 -0.02081811 0.5100001 -0.06872612 -0.01732224 0.5024487 -0.067209 -0.01888769 0.4875826 -0.06583321 -0.02073824 0.5100003 -0.06650465 -0.01845777 0.48 -0.06598496 -0.02135276 0.502499 -0.06451129 -0.01982927 0.4799997 -0.06433027 -0.02168118 0.5100002 -0.06398153 -0.0193414 0.5100002 -0.06169688 -0.01981151 0.4799999 -0.06231433 -0.02188009 0.5099999 -0.05967062 -0.01999676 0.4799999 -0.05280077 -0.02188187 0.4917265 -0.05275475 -0.02113056 0.4799998 -0.04623371 -0.0207408 0.4800003 -0.04770606 -0.02121812 0.4800003 -0.04978758 -0.02166426 0.4799999 -0.05074429 -0.02177459 0.502497 -0.04407548 -0.01738029 0.5100001 -0.04674476 -0.01812052 0.51 -0.04499322 -0.01716798 0.5099998 -0.04867309 -0.01893776 0.5022298 -0.04682844 -0.01890128 0.4799999 -0.04137748 -0.01802349 0.48764 -0.04064601 -0.0164414 0.48 -0.03989857 -0.01674085 0.4877204 -0.04305213 -0.01833951 0.5099998 -0.04306083 -0.01578783 0.502497 -0.04157108 -0.01540738 0.51 -0.041803 -0.01467174 0.4800003 -0.03826272 -0.0149033 0.4876304 -0.0386008 -0.01416218 0.502497 -0.03943818 -0.01303738 0.5099999 -0.04062759 -0.01343721 0.48 -0.03681474 -0.01270079 0.4876964 -0.03697031 -0.01156055 0.51 -0.03865444 -0.01070046 0.51 -0.03958696 -0.01211547 0.502497 -0.03773778 -0.01033806 0.4799999 -0.03573685 -0.01039981 0.487713 -0.03582298 -0.00880593 0.48 -0.03514933 -0.008583664 0.5100001 -0.03782743 -0.009135246 0.51 -0.03707236 -0.007315635 0.502497 -0.03654986 -0.007481753 0.4800001 -0.03482717 -0.007162392 0.4880335 -0.03520423 -0.006191194 0.48 -0.03459465 -0.005396664 0.51 -0.03624582 -0.004114687 0.5099999 -0.03643184 -0.005028486 0.4799998 -0.03454345 -0.004600882 0.4990905 -0.0354883 -0.002657473 0.5100001 -0.03600007 -0.001564145 0.4799998 -0.0345776 0 0.5099995 -0.03601098 0 0.4800003 -0.04267621 -0.01896005 0.487492 -0.04569107 -0.01981258 0.502497 -0.04953944 -0.01982927 0.48 -0.04437667 -0.01992624 0.5099999 -0.050933 -0.01957798 0.5100001 -0.05244308 -0.01984304 0.5100001 -0.05423974 -0.01999962 0.4800001 -0.06963038 -0.02001345 0.48 -0.07096236 -0.01928979 0.51 -0.07400393 -0.01266157 0.48 -0.07574337 -0.01508861 0.5024417 -0.07750189 -0.007493317 0.5100001 -0.07689595 -0.00740242 0.5099998 -0.07750409 -0.005400776 0.4799999 -0.07901996 -0.008533418 0.411237 -0.03536736 -0.01099997 0.406237 -0.03536736 0 0.406237 -0.03536736 -0.01099997 0.411237 -0.03536736 0 0.411237 -0.03536736 0 0.411237 -0.03536736 -0.01099997 0.411237 -0.04336738 -0.01099997 0.411237 -0.04336738 0 0.406237 -0.03536736 -0.01099997 0.371237 -0.02918457 -0.01099997 0.411237 -0.03536736 -0.01099997 0.373439 -0.03774607 -0.01099997 0.371237 -0.03718459 -0.01099997 0.4157165 -0.04355251 -0.01099997 0.411237 -0.04336738 -0.01099997 0.386614 -0.04056185 -0.01099997 0.384423 -0.04015845 -0.01099997 0.4216876 -0.04376041 -0.01099997 0.4276375 -0.04392552 -0.01099997 0.4336231 -0.04404932 -0.01099997 0.4395909 -0.04413044 -0.01099997 0.468035 -0.03543728 -0.01099997 0.444107 -0.04416257 -0.01099997 0.4486026 -0.04417318 -0.01099997 0.4545632 -0.04414862 -0.01099997 0.45906 -0.04410105 -0.01099997 0.4635478 -0.04403227 -0.01099997 0.468035 -0.04393726 -0.01099997 0.377839 -0.03878998 -0.01099997 0.37564 -0.0382812 -0.01099997 0.382231 -0.0397287 -0.01099997 0.380036 -0.03927248 -0.01099997 0.388802 -0.04093897 -0.01099997 0.390989 -0.04128974 -0.01099997 0.393173 -0.04161429 -0.01099997 0.395356 -0.04191237 -0.01099997 0.397536 -0.04218417 -0.01099997 0.399714 -0.04242956 -0.01099997 0.40189 -0.04264867 -0.01099997 0.404064 -0.04284149 -0.01099997 0.406237 -0.04300785 -0.01099997 0.406237 -0.03536736 -0.01099997 0.406237 -0.04300785 0 0.406237 -0.04300785 -0.01099997 0.406237 -0.03536736 0 0.468035 -0.04393726 -0.01099997 0.468035 -0.03543728 -0.01099997 0.468035 -0.03543728 -0.01999998 0.468035 -0.04393726 -0.01999998 0.371237 -0.02918457 -0.01999998 0.371237 -0.03718459 -0.01099997 0.371237 -0.03718459 -0.01999998 0.371237 -0.02918457 -0.01099997 0.468035 -0.03543728 -0.01099997 0.371237 -0.02918457 -0.01099997 0.371237 -0.02918457 -0.01999998 0.468035 -0.03543728 -0.01999998 -0.1557724 -0.01787996 -0.012497 -0.1661582 -0.01665312 -0.01235979 -0.156778 -0.009632825 -0.008761525 -0.144771 -0.009646356 -0.008778572 -0.1465199 -0.01095539 -0.009932398 -0.1581494 -0.01065903 -0.009696245 -0.1588617 -0.01119214 -0.0101071 -0.1603299 -0.01229089 -0.01082187 -0.147933 -0.01201295 -0.01065725 -0.1518806 -0.01496738 -0.01198351 -0.1643447 -0.01529568 -0.01207673 -0.1629849 -0.01427805 -0.01174885 -0.1490231 -0.01282888 -0.01112031 -0.161101 -0.01286834 -0.01113557 -0.1620168 -0.01355338 -0.01146125 -0.1536039 -0.01625746 -0.01229268 -0.1683487 -0.01829254 -0.01251214 -0.158286 -0.01976162 -0.0124486 -0.1703698 -0.01980507 -0.01243907 -0.171755 -0.02084165 -0.0122922 -0.1597787 -0.02087861 -0.01228308 -0.1612073 -0.02194803 -0.0120334 -0.1732684 -0.0219748 -0.01202589 -0.1746056 -0.0229749 -0.0116927 -0.1623755 -0.02282202 -0.01174765 -0.1633427 -0.02354609 -0.01146012 -0.1757955 -0.02386587 -0.01131534 -0.1642596 -0.02423191 -0.01113384 -0.1766684 -0.0245192 -0.01098328 -0.1650229 -0.02480351 -0.01082324 -0.1774238 -0.02508443 -0.01065683 -0.1657676 -0.02536094 -0.01048099 -0.1780908 -0.02558374 -0.01033425 -0.1664949 -0.02590513 -0.01010674 -0.1788316 -0.02613818 -0.009934902 -0.1672092 -0.02643972 -0.009694695 -0.1678819 -0.02694338 -0.009262621 -0.179531 -0.02666169 -0.009511649 -0.180091 -0.02708059 -0.009136915 -0.180585 -0.02745038 -0.008778572 -0.168578 -0.02746397 -0.008761465 -0.1690739 -0.02783507 -0.008366107 -0.18128 -0.02797037 -0.00821799 -0.1695631 -0.02820122 -0.00794053 -0.1818516 -0.02839887 -0.007699787 -0.170031 -0.02855128 -0.007496058 -0.1825187 -0.02889704 -0.007016956 -0.1705108 -0.02891087 -0.006990611 -0.1710774 -0.0293346 -0.006318747 -0.1831003 -0.02933305 -0.006325364 -0.183491 -0.02962505 -0.005801856 -0.171581 -0.02971196 -0.005622625 -0.183743 -0.02981418 -0.005424082 -0.1839799 -0.02999138 -0.005032539 -0.171953 -0.02998989 -0.005032539 -0.172178 -0.03015828 -0.004628956 -0.184203 -0.0301584 -0.004623353 -0.184409 -0.03031235 -0.004202604 -0.172387 -0.03031468 -0.004212379 -0.184597 -0.03045284 -0.003771543 -0.172581 -0.03046005 -0.003782868 -0.1727519 -0.03058665 -0.003333926 -0.18476 -0.03057509 -0.003326773 -0.1851537 -0.03086817 -0.001939833 -0.173131 -0.03087139 -0.001939475 -0.185237 -0.03093236 -0.001460969 -0.1732127 -0.03093278 -0.001456737 -0.1853926 -0.03104835 0 -0.173367 -0.03104835 0 -0.1503511 -0.01382303 -0.01157522 -0.1595881 -0.01173567 -0.01048082 -0.1472694 -0.01151627 -0.01033645 -0.1458264 -0.01043611 -0.009512543 -0.1574745 -0.01015365 -0.009262859 -0.145265 -0.01001626 -0.009136915 -0.156282 -0.009261727 -0.008366107 -0.1440767 -0.009126961 -0.008218646 -0.143504 -0.008697628 -0.007699429 -0.1557931 -0.008895754 -0.007940769 -0.1553249 -0.008545458 -0.007496058 -0.1548706 -0.008205413 -0.00701934 -0.1428378 -0.008200168 -0.007017612 -0.1542787 -0.007762253 -0.006318926 -0.1422552 -0.007763445 -0.006324827 -0.1537748 -0.007384717 -0.005622506 -0.1416119 -0.007282555 -0.005424082 -0.141865 -0.00747168 -0.005801856 -0.153403 -0.00710684 -0.005032539 -0.141376 -0.00710541 -0.005032539 -0.153178 -0.006938517 -0.004628956 -0.141153 -0.006938397 -0.004623353 -0.152969 -0.006782114 -0.004212379 -0.152775 -0.006636679 -0.003782868 -0.140947 -0.006784379 -0.004202604 -0.140759 -0.00664395 -0.003771543 -0.1526041 -0.006510078 -0.003333926 -0.140596 -0.006521701 -0.003326773 -0.1402023 -0.006228625 -0.001939892 -0.152225 -0.006225466 -0.001939475 -0.1521433 -0.006164014 -0.001456737 -0.1401194 -0.006165087 -0.001468956 -0.151989 -0.006048381 0 -0.139963 -0.006048381 0 -0.152002 -0.006058514 -4.48597e-4 -0.151989 -0.006048381 0 -0.151383 -0.005595147 0 -0.1520349 -0.006082832 -8.91371e-4 -0.1834731 -0.02961218 -0.005814909 -0.188 -0.03299999 -0.04199999 -0.1551826 -0.008438944 -0.007357835 -0.151383 -0.005595147 -0.04199999 -0.1557365 -0.008853435 -0.007892966 -0.152157 -0.006174087 -0.001759409 -0.152086 -0.006121397 -0.001328289 -0.152355 -0.006322145 -0.002604186 -0.1522459 -0.006241023 -0.002184748 -0.152482 -0.006417393 -0.003017842 -0.15279 -0.006647706 -0.003824055 -0.152628 -0.006526887 -0.003425717 -0.15315 -0.006917119 -0.004584848 -0.152962 -0.00677675 -0.00420916 -0.1537043 -0.007332026 -0.005522966 -0.153352 -0.007068753 -0.004951059 -0.154024 -0.00757122 -0.005984961 -0.1546742 -0.00805819 -0.006800532 -0.154268 -0.007753908 -0.00630778 -0.156182 -0.009186387 -0.008284926 -0.1566118 -0.009508073 -0.008636653 -0.1572578 -0.009991586 -0.009114265 -0.1578554 -0.01043897 -0.009515762 -0.1585326 -0.01094621 -0.009923934 -0.1591513 -0.01140898 -0.01026308 -0.1598229 -0.01191139 -0.01059383 -0.1608045 -0.01264625 -0.01102083 -0.160316 -0.01228058 -0.01081609 -0.1615108 -0.01317459 -0.01128756 -0.1621746 -0.01367181 -0.0115115 -0.1628976 -0.01421248 -0.01172548 -0.1635723 -0.01471787 -0.0119006 -0.1644594 -0.01538163 -0.01209497 -0.1653163 -0.01602292 -0.01224374 -0.1660268 -0.01655465 -0.01234132 -0.1669094 -0.01721525 -0.01243102 -0.1679834 -0.01801913 -0.01249086 -0.168868 -0.01868104 -0.01249992 -0.1697611 -0.01934951 -0.01247608 -0.1708218 -0.0201435 -0.01239937 -0.1718853 -0.0209394 -0.01227009 -0.1727597 -0.02159416 -0.01212263 -0.1734421 -0.02210456 -0.01198315 -0.1741448 -0.02263039 -0.01181417 -0.1748411 -0.02315163 -0.01162141 -0.175534 -0.02367037 -0.01140201 -0.1762273 -0.02418863 -0.01115536 -0.1769118 -0.02470135 -0.01088047 -0.1775885 -0.02520799 -0.01057881 -0.178218 -0.02567899 -0.01026666 -0.1789071 -0.02619433 -0.009889662 -0.1798191 -0.02687722 -0.009320557 -0.179356 -0.02653038 -0.009618759 -0.1804423 -0.02734392 -0.008882701 -0.1810454 -0.02779465 -0.008410632 -0.1816553 -0.02825152 -0.007881343 -0.1821967 -0.02865666 -0.007352232 -0.1827571 -0.02907603 -0.006740689 -0.183108 -0.02933847 -0.006307482 -0.188 -0.03299999 0 -0.183812 -0.0298652 -0.005307435 -0.1842229 -0.03017318 -0.004587948 -0.184023 -0.03002369 -0.004952967 -0.184589 -0.0304473 -0.00382632 -0.184412 -0.03031438 -0.004212379 -0.184893 -0.03067427 -0.003027319 -0.18475 -0.0305677 -0.003431141 -0.185132 -0.03085345 -0.002191245 -0.18502 -0.03076958 -0.002614021 -0.185297 -0.03097665 -0.001329898 -0.185226 -0.0309242 -0.001761317 -0.18538 -0.03103876 -4.49268e-4 -0.185348 -0.03101485 -8.92581e-4 -0.185392 -0.03104835 0 -0.07699996 -0.01322466 0 -0.07699996 -0.01372468 0 -0.07699996 -0.01372468 -0.03849995 -0.07699996 -0.01322466 -0.03849995 0.226821 -0.05648988 -0.037 -0.200578 -0.0464558 -0.03999996 0.226821 -0.05648988 -0.03999996 -0.200578 -0.0464558 -0.037 -0.188 -0.04199999 0 -0.292158 -0.04199999 0 -0.2918813 -0.04199999 -9.71552e-4 -0.2299275 -0.04199999 -0.03179425 -0.2914004 -0.04199999 -0.002776086 -0.2909824 -0.04199999 -0.004507482 -0.2905809 -0.04199999 -0.006330013 -0.2902899 -0.04199999 -0.007807612 -0.2899998 -0.04199999 -0.01400017 -0.2886131 -0.04199999 -0.0155794 -0.2874653 -0.04199999 -0.01680529 -0.289451 -0.04199999 -0.01463758 -0.2850911 -0.04199999 -0.01913636 -0.2497845 -0.04199999 -0.02937853 -0.2862764 -0.04199999 -0.01800572 -0.281571 -0.04199999 -0.02210736 -0.2569288 -0.04199999 -0.02889364 -0.282229 -0.04199999 -0.0216003 -0.2527133 -0.04199999 -0.02914988 -0.282878 -0.04199999 -0.02108079 -0.2587903 -0.04199999 -0.02880638 -0.278854 -0.04199999 -0.02398985 -0.280228 -0.04199999 -0.0230841 -0.279543 -0.04199999 -0.02355355 -0.277457 -0.04199999 -0.02480018 -0.276748 -0.04199999 -0.02517604 -0.261551 -0.04199999 -0.02862727 -0.278159 -0.04199999 -0.02440476 -0.2603539 -0.04199999 -0.02871328 -0.2628512 -0.04199999 -0.02854597 -0.264026 -0.04199999 -0.02844518 -0.276032 -0.04199999 -0.02553248 -0.2651262 -0.04199999 -0.02832967 -0.269737 -0.04199999 -0.02761769 -0.268929 -0.04199999 -0.02778404 -0.2673163 -0.04199999 -0.02805227 -0.273771 -0.04199999 -0.02647274 -0.274545 -0.04199999 -0.02618116 -0.270541 -0.04199999 -0.02743047 -0.272177 -0.04199999 -0.02699339 -0.271358 -0.04199999 -0.02722227 -0.275304 -0.04199999 -0.02586865 -0.268118 -0.04199999 -0.02792966 -0.272981 -0.04199999 -0.02674347 -0.280904 -0.04199999 -0.02260196 -0.2837437 -0.04199999 -0.02035135 -0.2460478 -0.04199999 -0.02971941 -0.2436594 -0.04199999 -0.02997142 -0.2404828 -0.04199999 -0.03033989 -0.2370858 -0.04199999 -0.03077048 -0.2335708 -0.04199999 -0.03125458 -0.2257881 -0.04199999 -0.03244626 -0.2213252 -0.04199999 -0.03319042 -0.2168772 -0.04199999 -0.0339691 -0.2122159 -0.04199999 -0.03481274 -0.188 -0.04199999 -0.037 -0.2070285 -0.04199999 -0.03577727 -0.2005756 -0.04199999 -0.037 -0.114755 -0.09546965 -0.003882408 -0.1158002 -0.09563076 0 -0.1263357 -0.0593959 -0.04766166 -0.121532 -0.05974203 -0.04796308 -0.2765932 -0.04284441 -0.02526521 -0.2791849 -0.04200047 -0.02379524 -0.1407245 -0.06966865 -0.04645365 -0.1572939 -0.0716449 -0.04436618 -0.1621253 -0.07421338 -0.04329723 -0.2683746 -0.04317426 -0.0278663 -0.147784 -0.06927585 -0.04568684 -0.1550943 -0.06900286 -0.04475212 -0.1620932 -0.06883001 -0.04376125 -0.2725983 -0.04258108 -0.02686858 -0.268104 -0.04199987 -0.02793937 -0.1383959 -0.06523299 -0.04668176 -0.1407434 -0.05861186 -0.04645162 -0.2639697 -0.04235053 -0.02843523 -0.1455201 -0.05844295 -0.04594177 -0.2683659 -0.05270379 -0.0278663 -0.2725799 -0.05243474 -0.02684754 -0.1523586 -0.05832135 -0.04512023 -0.2639595 -0.05472594 -0.0284354 -0.2594321 -0.05671125 -0.0287562 -0.2586553 -0.07704311 -0.01973664 -0.263952 -0.07504028 -0.01932245 -0.263951 -0.077035 -0.01668739 -0.1382009 -0.05692714 -0.04670089 -0.259429 -0.0812444 -0.01199829 -0.25484 -0.08138829 -0.01523178 -0.259429 -0.08012199 -0.01458936 -0.2221196 -0.04199999 -0.03305494 -0.2107733 -0.04199999 -0.03507691 -0.16216 -0.07683813 -0.04263943 -0.1670292 -0.07930278 -0.04096132 -0.1717023 -0.07405495 -0.04178762 -0.1717642 -0.07668459 -0.0411241 -0.138588 -0.07343453 -0.04647755 -0.140726 -0.07237386 -0.04636245 -0.1671982 -0.08405369 -0.0382803 -0.1671016 -0.08174395 -0.03975236 -0.1767808 -0.0839411 -0.03666436 -0.1525571 -0.07446438 -0.04463368 -0.1768083 -0.0861001 -0.03493791 -0.1767069 -0.08162242 -0.03814727 -0.1766655 -0.0791707 -0.03936141 -0.1672533 -0.0862075 -0.03656554 -0.1768506 -0.08806437 -0.03297746 -0.191032 -0.09081548 -0.02594536 -0.1910363 -0.09198856 -0.02352958 -0.1816383 -0.0911802 -0.02763867 -0.1957905 -0.08747661 -0.02946704 -0.1957798 -0.08913439 -0.02735459 -0.1768776 -0.08980429 -0.03081524 -0.1816505 -0.0923897 -0.02518177 -0.2005609 -0.09020954 -0.02422899 -0.1910393 -0.09288805 -0.02102577 -0.1957525 -0.09318798 -0.01771533 -0.1864296 -0.09376573 -0.01922035 -0.181667 -0.09332126 -0.0226258 -0.1957345 -0.09352791 -0.0151847 -0.1721727 -0.0926069 -0.02684366 -0.172129 -0.09137302 -0.02932095 -0.1981258 -0.09340804 -0.01231759 -0.1864374 -0.09412151 -0.01660406 -0.1885797 -0.09408384 -0.002077519 -0.186428 -0.0942083 -0.01401156 -0.1837932 -0.09432655 -0.002174973 -0.2107216 -0.09212607 -0.006385922 -0.2101054 -0.09219956 -0.006167232 -0.2079892 -0.09244209 -0.007332682 -0.2074176 -0.092507 -0.004856586 -0.2029578 -0.09296953 -0.006091058 -0.2085723 -0.09237742 -0.005502879 -0.2091642 -0.09230941 -0.005782008 -0.2068848 -0.09256565 -0.004499673 -0.204536 -0.0928145 -0.001926243 -0.2029858 -0.09297108 -0.00184518 -0.2046959 -0.09279805 -0.002218842 -0.205272 -0.09273809 -0.003033101 -0.205491 -0.09271508 -0.003283441 -0.204397 -0.09282886 -0.00162357 -0.1992689 -0.09303116 0 -0.2041203 -0.09285742 -6.60562e-4 -0.20406 -0.09286379 0 -0.204279 -0.09284108 -0.001311361 -0.204186 -0.09285068 -9.91838e-4 -0.194477 -0.09319657 0 -0.1790036 -0.09451532 -0.002280294 -0.1715198 -0.09395861 -9.98107e-7 -0.174215 -0.09465801 -0.002392232 -0.1888455 -0.09338945 -1.33186e-7 -0.08633887 -0.096206 -0.02876508 0.03301173 -0.09971344 0 0.05398148 -0.1000786 -0.005059003 -0.08450084 -0.09513825 -0.03610283 -0.0745508 -0.09606963 -0.03498482 -0.1142146 -0.08772951 -0.04272949 -0.1140615 -0.08939248 -0.04113405 -0.1240808 -0.07624673 -0.04736089 -0.1286205 -0.07492834 -0.04720008 -0.09440797 -0.09295922 -0.03906381 -0.09492707 -0.09042739 -0.04232442 -0.09504288 -0.08895599 -0.04374009 -0.1137672 -0.09089845 -0.03938072 -0.1143459 -0.07962948 -0.04726821 -0.1245422 -0.07868993 -0.04669952 -0.125272 -0.08096271 -0.04578626 -0.09471178 -0.09176498 -0.04076611 -0.1143274 -0.08591103 -0.0441547 -0.1143241 -0.08396083 -0.0453841 -0.1143743 -0.07727855 -0.04787397 -0.1000156 -0.08515787 -0.0459975 -0.1047254 -0.08275794 -0.04682254 -0.114328 -0.08186036 -0.04643344 -0.1047501 -0.08063542 -0.04762423 -0.126336 -0.07353335 -0.04756855 -0.1262862 -0.07085835 -0.04766458 -0.1285572 -0.07222032 -0.04749011 -0.1000064 -0.07406163 -0.04877322 -0.1096057 -0.07276242 -0.0485183 -0.1095555 -0.07540047 -0.04842358 -0.1191548 -0.07426971 -0.04800611 -0.1191937 -0.07160252 -0.04809862 -0.1283739 -0.06442409 -0.0475189 -0.1145375 -0.06032067 -0.04832398 -0.1282029 -0.05716156 -0.04752904 -0.123452 -0.05727308 -0.04768246 -0.09410876 -0.09585469 -0.03060883 -0.2267515 -0.06579196 -0.03229391 -0.2220045 -0.06644743 -0.03307825 -0.25484 -0.07997369 -0.01769167 -0.2479591 -0.08015149 -0.02074706 -0.259433 -0.06404221 -0.02781879 -0.251652 -0.06722325 -0.02821737 -0.25189 -0.0645523 -0.02881121 -0.2544969 -0.04199993 -0.02903234 -0.2501993 -0.04199999 -0.02934283 -0.2594405 -0.04275047 -0.0287559 -0.2641457 -0.04200005 -0.02844822 -0.07925456 -0.09642559 -0.004414618 -0.270474 -0.04200011 -0.02745127 -0.280521 -0.04199987 -0.02288639 -0.268365 -0.05484277 -0.02781099 -0.272595 -0.05728989 -0.02612018 -0.272596 -0.05492329 -0.02658659 -0.276607 -0.0548889 -0.024598 -0.04711478 -0.09748536 -0.004523456 -0.05842286 -0.09708666 0 -0.06639266 -0.09683865 -0.004350602 -0.06679284 -0.09687209 0 -0.02253311 -0.09703022 -0.04054117 -0.2839279 -0.04199969 -0.02020186 -0.268361 -0.06227868 -0.02622139 -0.268362 -0.05964267 -0.02704596 -0.272594 -0.05982655 -0.02535438 -0.006744027 -0.08994358 -0.04616034 0.00624603 -0.09231263 -0.04534298 -0.263959 -0.05695939 -0.02837496 -0.272593 -0.06250667 -0.02421939 -0.26836 -0.06502979 -0.02501904 0.01807612 -0.06262165 -0.04532581 0.02342236 -0.0766651 -0.04514604 0.01555323 -0.08945894 -0.04540932 -0.00400418 -0.08807826 -0.04615885 -0.263958 -0.05935806 -0.02809798 -0.268363 -0.05715805 -0.02755558 -0.263954 -0.07006305 -0.02378785 -0.268358 -0.06781578 -0.02338725 -0.268357 -0.07051509 -0.02131247 0.02374935 -0.06273603 -0.0451349 -0.263956 -0.06457889 -0.02668297 -0.263955 -0.06732547 -0.02543979 -0.259433 -0.06146359 -0.02839505 -0.263957 -0.06190758 -0.02755206 -0.2405193 -0.04199993 -0.03033399 -0.263953 -0.07267916 -0.02172809 -0.259431 -0.07204347 -0.02400708 -0.2587368 -0.07484799 -0.02199399 -0.26395 -0.07860988 -0.01396399 -0.25943 -0.07862597 -0.01718574 0.02379649 -0.06073009 -0.04513365 -0.263949 -0.07977408 -0.01126718 -0.263948 -0.08057528 -0.008674919 -0.2590829 -0.06700313 -0.02687382 -0.2481665 -0.07107812 -0.02752041 0.01326394 -0.06247705 -0.04549455 0.008450806 -0.06780159 -0.04567068 -0.01392185 -0.09056657 -0.04617971 0.02309584 -0.09057128 -0.0451588 -0.00400561 -0.09256225 -0.04538601 -0.01352095 -0.0926966 -0.04533702 -0.003747522 -0.09426987 -0.04448652 -0.01810371 -0.0940259 -0.04441875 0.02306431 -0.09191834 -0.04506134 0.01697969 -0.09175652 -0.04523116 0.02303481 -0.09317386 -0.04476195 -0.01789343 -0.09612059 -0.04232996 -0.01795816 -0.09548288 -0.04308694 -0.03731566 -0.09341841 -0.04417836 -0.03741407 -0.09247666 -0.04494959 -0.01802563 -0.0947867 -0.04378128 -0.03723621 -0.09427893 -0.04333263 -0.01783341 -0.0967015 -0.04150199 -0.03707069 -0.09577792 -0.04139143 -0.02242398 -0.0975117 -0.03947335 -0.03168225 -0.09758824 -0.03788477 -0.06766819 -0.09679287 -0.0309413 -0.04177385 -0.09758049 0 -0.007427036 -0.09878492 -0.03530436 -0.01011425 -0.09870648 -0.005419492 -0.00478053 -0.09876847 0 0.009601593 -0.09925413 0 0.006561934 -0.09918123 -0.004892051 0.08041918 -0.1001381 0 0.07310146 -0.1001628 -0.004863917 0.1762185 -0.08715039 -0.03953772 0.1698616 -0.08917218 -0.03953039 0.06577467 -0.1001571 -0.03408598 0.05434602 -0.1000828 -0.03463101 0.03310382 -0.09034758 -0.04483628 0.04274553 -0.0677179 -0.04454523 0.03756773 -0.09241777 -0.04457718 0.03300869 -0.09441214 -0.04410809 0.05883115 -0.09368282 -0.04367715 0.05864101 -0.09247839 -0.04396724 0.05884718 -0.09461325 -0.0433312 0.05167919 -0.09539985 -0.04315507 0.04476195 -0.09603303 -0.04294764 0.07108759 -0.09020739 -0.04373288 0.05890136 -0.09607845 -0.04251807 0.03379362 -0.06096476 -0.04481643 0.06846243 -0.09531658 -0.04265701 -0.2479488 -0.07368332 -0.02625715 -0.2531865 -0.07441985 -0.02426683 0.04554486 -0.06124067 -0.04452401 0.04717797 -0.09665197 -0.04243886 0.05884879 -0.09727042 -0.04157012 0.05409985 -0.09776198 -0.04119479 0.07558977 -0.09716898 -0.04101192 0.06847029 -0.09777837 -0.04070031 0.06847381 -0.09666454 -0.04175496 0.08683842 -0.09724837 -0.04039746 0.087507 -0.09640955 -0.04108905 0.09726226 -0.09666419 -0.04039525 0.09381729 -0.09688377 -0.04039996 0.09247672 -0.09559255 -0.04143142 0.1108955 -0.09558528 -0.04040741 0.107613 -0.09587597 -0.04039996 0.1068136 -0.09437513 -0.04138177 -0.247911 -0.07825905 -0.02281171 -0.2432971 -0.07737952 -0.02511334 0.117928 -0.09487509 -0.04039996 0.1236342 -0.09372508 -0.04072409 0.1145049 -0.09523195 -0.04040169 -0.2334672 -0.07740736 -0.02788263 -0.238686 -0.07376265 -0.02849763 0.1067702 -0.09347045 -0.04181277 -0.2413457 -0.07053923 -0.02913987 -0.2387136 -0.06857502 -0.03012275 0.1269197 -0.0926814 -0.04102003 -0.238717 -0.06600618 -0.03047204 -0.2170168 -0.04199999 -0.03394412 -0.2293348 -0.06793719 -0.03179746 0.1383346 -0.09209334 -0.04055613 0.1260077 -0.09158647 -0.04145371 0.138294 -0.0909819 -0.0409435 -0.2314839 -0.06500035 -0.03156197 -0.2361992 -0.06405961 -0.03089159 0.141888 -0.09172338 -0.04039996 0.1645668 -0.0903626 -0.03950154 0.171503 -0.09055227 -0.03892958 0.168536 -0.08565938 -0.03999584 0.1762402 -0.08621984 -0.03960144 0.1763132 -0.08309268 -0.03961926 0.150111 -0.08677583 -0.04084765 -0.2005773 -0.04199999 -0.03699862 0.1767536 -0.0643211 -0.0395978 0.17664 -0.06917387 -0.03960329 0.1764998 -0.07516008 -0.0396102 0.1523786 -0.0888316 -0.04063624 0.176411 -0.07895207 -0.03961449 0.1521217 -0.09002095 -0.0404005 0.1761747 -0.08899182 -0.0391646 0.1761519 -0.08998829 -0.03882443 0.176136 -0.09067881 -0.03851968 0.1495257 -0.09048259 -0.04041892 0.08343786 -0.09739476 -0.04039996 0.08318567 -0.09762674 -0.04017078 0.04218858 -0.09994083 -0.03508073 0.04218173 -0.09983366 -0.0369715 0.03299152 -0.0951398 -0.04374122 0.07396554 -0.1000598 -0.03555399 0.05887985 -0.09826284 -0.04045945 0.04239547 -0.09714668 -0.04209506 0.05891704 -0.09909713 -0.03913754 0.06377714 -0.0994808 -0.03815263 0.05908817 -0.100024 -0.0362873 0.04252374 -0.09764707 -0.04157721 0.08117204 -0.0994631 -0.03733849 0.07612705 -0.0991131 -0.03838723 0.05415141 -0.09866374 -0.04000109 0.04940736 -0.09968417 -0.03783708 0.0423808 -0.09810745 -0.04102265 0.04255175 -0.09892159 -0.03973996 0.04241108 -0.09853661 -0.04040652 0.0820744 -0.09863722 -0.03889679 0.0685141 -0.09871584 -0.03945833 0.04488569 -0.09930884 -0.03891211 0.07496452 -0.09823632 -0.03984773 0.08096003 -0.0996477 -0.03682547 0.08067417 -0.09990805 -0.03590047 0.08046799 -0.100096 -0.0347408 0.08051908 -0.100049 -0.03513199 0.04066205 -0.09991812 -0.005177259 0.06442797 -0.100148 -0.004865527 0.06178838 -0.1000454 0 0.02185273 -0.09956085 -0.00498563 -2.94891e-4 -0.09889042 -0.03748208 -0.005771994 -0.09809738 -0.03971093 -0.005670487 -0.09845542 -0.03865945 -0.07625353 -0.09664911 0 -0.08717906 -0.09638488 0 -0.09986555 -0.0958271 -0.004262864 -0.124444 -0.09527641 -0.003594875 -0.1255111 -0.09535819 0 -0.1349909 -0.09508585 0 -0.1338472 -0.09512507 -0.002720057 -0.146468 -0.09474366 0 -0.141659 -0.09488767 0 -0.1430518 -0.0950151 -0.003035247 -0.1512759 -0.09459775 0 -0.1503053 -0.09496158 -0.00300908 -0.1550895 -0.0949288 -0.002882301 -0.1598712 -0.09488999 -0.002755999 -0.156083 -0.09444987 0 -0.1646489 -0.09483736 -0.002631306 -0.165691 -0.09414827 0 -0.160887 -0.09430009 0 -0.1694319 -0.09476268 -0.002509772 -0.205065 -0.09275978 -0.00277239 -0.204873 -0.09277975 -0.00250107 -0.2058408 -0.09267807 -0.003642201 -0.2063493 -0.09262365 -0.004091858 -0.1981499 -0.0934084 -0.001909792 -0.1933437 -0.09377902 -0.01299852 -0.2456184 -0.08621644 0 -0.2503843 -0.08512741 0 -0.2079996 -0.09244221 -0.00520128 -0.209632 -0.09225499 -0.005981266 -0.2113487 -0.09205037 -0.006583988 -0.2119898 -0.09197181 -0.0067631 -0.1933653 -0.09377843 -0.001989603 -0.2127804 -0.09187316 -0.006955325 -0.2115552 -0.09202003 -0.01021474 -0.176943 -0.09458917 -0.01543754 -0.2137553 -0.09174948 -0.007148623 -0.214583 -0.09164214 -0.007277131 -0.2153998 -0.09153437 -0.007376492 -0.1645423 -0.09435832 -0.02289474 -0.1769411 -0.09449857 -0.01810848 -0.164667 -0.09475284 -0.02010917 -0.2053111 -0.09265977 -0.01377594 -0.2162353 -0.09142214 -0.007446646 -0.2175645 -0.09123468 -0.009499192 -0.2168788 -0.0913344 -0.007480442 -0.1721866 -0.09356522 -0.02425843 -0.1769294 -0.09412556 -0.02079671 -0.2175614 -0.09124004 -0.0074988 -0.2052991 -0.0927388 -0.01131588 -0.1673787 -0.08991903 -0.03246343 -0.1673358 -0.08817178 -0.03461539 -0.2183678 -0.09112751 -0.007495582 -0.2191982 -0.09100872 -0.007461607 -0.2218367 -0.09061664 -0.008857429 -0.2200303 -0.09088838 -0.00739932 -0.2208476 -0.09076786 -0.007305622 -0.2227917 -0.09047406 -0.006954431 -0.2214921 -0.09067231 -0.007210493 -0.2322124 -0.0888915 -0.007173001 -0.2275029 -0.08971333 -0.007848381 -0.2221517 -0.09057176 -0.00709176 -0.2246845 -0.09017872 -0.006406962 -0.2234348 -0.0903759 -0.006793677 -0.2240608 -0.09027731 -0.006612956 -0.2683233 -0.07946896 -3.11493e-4 -0.2639563 -0.08137243 -0.001931786 -0.2455903 -0.08621138 -0.005325376 -0.2502541 -0.08514922 -0.004507541 -0.2267927 -0.08983862 -0.005476951 -0.272591 -0.07689684 -2.16139e-4 -0.2639272 -0.08137065 -4.36933e-4 -0.2634559 -0.08152163 1.19426e-7 -0.2732453 -0.07640326 6.49655e-7 -0.2712298 -0.07778787 -2.36218e-7 -0.2593982 -0.08282995 2.96267e-7 -0.254761 -0.08405894 0 -0.2411605 -0.08717352 0 -0.232105 -0.08893084 0 -0.2304019 -0.08922898 -0.001937389 -0.23053 -0.08920717 -0.001629889 -0.2365091 -0.08810722 0 -0.23078 -0.08916485 -6.64394e-4 -0.2306472 -0.08918708 -0.001254081 -0.2308361 -0.0891568 0 -0.2409055 -0.08721107 -0.006103098 -0.2361991 -0.08815008 -0.006852447 -0.2693846 -0.07890158 0 -0.2661093 -0.08046638 -4.40616e-7 -0.2766376 -0.073484 -2.29325e-4 -0.2804242 -0.06917923 -3.49488e-4 -0.2751462 -0.07486212 8.38606e-7 -0.2776748 -0.07244831 -7.04501e-7 -0.279299 -0.07061159 -2.86809e-7 -0.2809033 -0.06860834 0 -0.2826865 -0.06606715 5.61617e-7 -0.2839179 -0.06411093 -5.51184e-4 -0.2871179 -0.05836439 -7.73181e-4 -0.2900027 -0.05200117 -7.48042e-4 -0.2845514 -0.06312114 0 -0.2866621 -0.05932968 0 -0.2885591 -0.05536895 0 -0.2900095 -0.05200386 1.62171e-7 -0.2279144 -0.0896517 -0.004778981 -0.227367 -0.08974307 -0.005142748 -0.2548831 -0.08402931 -0.003646373 -0.2594472 -0.0828278 -0.002753973 -0.2262184 -0.08993196 -0.005771815 -0.225763 -0.09000599 -0.005981087 -0.268348 -0.07941615 -0.003203392 -0.272587 -0.07685595 -0.002724468 -0.2252976 -0.09008091 -0.006176948 -0.268349 -0.07917016 -0.005490541 -0.263947 -0.08107221 -0.00622332 -0.259428 -0.08277738 -0.004805326 -0.263946 -0.08132225 -0.003929913 -0.259428 -0.08252459 -0.007076323 -0.2531368 -0.08441174 -0.006089806 -0.2531177 -0.08415836 -0.008325994 -0.259429 -0.08202958 -0.00948143 -0.25484 -0.08323496 -0.01032239 -0.268356 -0.07297146 -0.01885366 -0.272592 -0.06794929 -0.02062439 -0.272591 -0.07041847 -0.01819294 -0.276609 -0.06233614 -0.02142798 -0.276609 -0.05974447 -0.02287465 -0.280374 -0.059035 -0.01968765 -0.2900063 -0.04200029 -0.01400572 -0.2871311 -0.04309356 -0.01715648 -0.2885445 -0.04199999 -0.01565629 -0.2735999 -0.04199993 -0.0265544 -0.276606 -0.05271005 -0.02501356 -0.268354 -0.07504808 -0.01614189 -0.2520239 -0.06200402 -0.02912026 -0.250217 -0.06022989 -0.02934205 -0.2455684 -0.06168973 -0.02977257 -0.245568 -0.06413215 -0.02969646 -0.25484 -0.08246707 -0.01275527 -0.2589573 -0.06973004 -0.02560591 -0.2479588 -0.08176946 -0.0185399 -0.2408953 -0.06296318 -0.03029209 -0.245568 -0.0666725 -0.02935916 -0.22843 -0.08956497 -0.004387795 -0.229717 -0.08934628 -0.003073632 -0.230256 -0.0892542 -0.002236306 -0.02929288 -0.09808582 -0.03432506 -0.29 -0.05198734 -0.004492163 -0.2899973 -0.05199873 -0.003994286 -0.2871537 -0.05818814 -0.003709733 -0.2289376 -0.08947932 -0.003941595 -0.2294024 -0.08940011 -0.003459334 -0.229911 -0.08931308 -0.002804636 -0.230092 -0.08928215 -0.002525269 -0.1415798 -0.09502691 -0.02092915 -0.1588702 -0.09490126 -0.01824575 -0.1243531 -0.09527111 -0.02354502 -0.1053008 -0.09568434 -0.02627325 -0.1288492 -0.08465886 -0.04336929 -0.126338 -0.08519858 -0.04328435 0.008960783 -0.09924715 -0.03559976 0.03083002 -0.09974581 -0.03541123 0.02014034 -0.09952056 -0.03565675 0.08041906 -0.10014 -0.03394526 0.08043467 -0.100126 -0.03434544 0.07579159 -0.100158 -0.03356659 -0.29 -0.05195105 -0.004980981 -0.287129 -0.05789208 -0.006148993 -0.29 -0.05189108 -0.005466461 -0.29 -0.05170005 -0.006427466 -0.276615 -0.07321161 -0.0046947 -0.280397 -0.06911396 -0.002815604 -0.276615 -0.07344168 -0.002589643 0.02288544 -0.09953314 -0.03699982 0.02288645 -0.09949016 -0.03743797 -0.29 -0.05180746 -0.005948662 -0.268351 -0.0786755 -0.007955133 -0.272588 -0.0761314 -0.007374167 -0.272587 -0.0766164 -0.004955708 -0.1675994 -0.09479951 -0.01688104 -0.1195578 -0.09413534 -0.03232765 -0.29 -0.0515691 -0.006901979 -0.29 -0.0508185 -0.008711695 -0.287102 -0.05644327 -0.009899556 -0.29 -0.05057615 -0.009138762 -0.287106 -0.05720239 -0.008332848 -0.29 -0.0510388 -0.008274614 -0.276613 -0.07198005 -0.009443938 -0.280391 -0.06846517 -0.006789743 -0.276614 -0.07274699 -0.006983041 -0.04591655 -0.09740781 -0.03542727 0.03289014 -0.09945344 -0.03830838 -0.29 -0.05123835 -0.007824778 -0.29 -0.05141538 -0.007366776 -0.2839127 -0.0639072 -0.004267454 -0.29 -0.05031317 -0.009554088 -0.287099 -0.05544477 -0.01144087 -0.2432498 -0.08666503 -0.007899582 -0.2243705 -0.09016329 -0.01096189 -0.2148663 -0.09153634 -0.01238018 -0.2338331 -0.08853965 -0.009481847 -0.2005578 -0.09219872 -0.01944029 -0.2053279 -0.09233707 -0.01621687 -0.1399191 -0.09493499 -0.02408874 -0.1200692 -0.09524106 -0.02707004 -0.1103499 -0.09503418 -0.0310235 0.01069015 -0.09735941 -0.0418632 0.0106433 -0.09782034 -0.04119968 -0.02151584 -0.09823232 -0.03683477 0.01039654 -0.09892028 -0.03873986 0.03288382 -0.09971928 -0.03700029 0.06845843 -0.09981155 -0.03701245 -0.29 -0.04940956 -0.01071476 -0.287095 -0.05422377 -0.01287835 -0.29 -0.04907238 -0.01106995 -0.280394 -0.06889748 -0.004720211 -0.276612 -0.06926697 -0.0146926 -0.280385 -0.06670808 -0.01135057 -0.276612 -0.0708394 -0.01204377 -0.268352 -0.07786709 -0.01058346 -0.2432868 -0.08639258 -0.01010411 -0.2148799 -0.09123045 -0.01473534 -0.2338641 -0.08825832 -0.01170885 -0.2005641 -0.09133595 -0.0218752 -0.2244108 -0.089868 -0.01324057 -0.1604806 -0.0936892 -0.02628093 -0.1600165 -0.09270882 -0.02894729 -0.1359595 -0.09455013 -0.02749282 -0.1043485 -0.09361267 -0.036336 -0.1131697 -0.09223932 -0.03749078 -0.05052137 -0.09691888 -0.03683173 -0.01779448 -0.09806299 -0.03839093 0.01056861 -0.09859871 -0.03968471 0.01041752 -0.09822648 -0.04048377 0.03290021 -0.09902411 -0.03951752 0.08077627 -0.0998153 -0.03627306 0.08058875 -0.09998577 -0.03552025 -0.29 -0.0500316 -0.009954512 -0.283898 -0.0634135 -0.006747424 -0.29 -0.04795938 -0.0120331 -0.287091 -0.05283987 -0.01413267 -0.29 -0.04755747 -0.01231676 -0.280388 -0.06775635 -0.009011149 -0.272589 -0.0753321 -0.009968757 -0.268353 -0.0766769 -0.01334095 -0.2479016 -0.08488923 -0.01156854 -0.2385796 -0.08685672 -0.01318049 -0.2101229 -0.09124755 -0.01787418 -0.2196639 -0.09003907 -0.01631873 -0.2291667 -0.08857315 -0.01475799 -0.1595196 -0.09146076 -0.03148198 -0.1389765 -0.08993756 -0.03700298 -0.1391925 -0.09163314 -0.03444653 -0.138596 -0.09381878 -0.02972847 -0.1289837 -0.09038281 -0.03790152 -0.12634 -0.09186166 -0.03608906 -0.07977849 -0.0945487 -0.03830134 -0.06045866 -0.09604185 -0.03785437 -0.0415098 -0.09678161 -0.03884744 -0.005852282 -0.09767943 -0.04062288 0.02289515 -0.09912401 -0.03895694 -0.29 -0.04972988 -0.01034206 -0.283893 -0.06278455 -0.008648574 -0.287088 -0.05137449 -0.01515215 -0.27259 -0.07414507 -0.01270568 -0.2479228 -0.08413261 -0.0139026 -0.2386017 -0.08610367 -0.01545071 -0.2101219 -0.09042406 -0.0202372 -0.2196951 -0.08924543 -0.01861649 -0.229189 -0.08780664 -0.01702183 -0.1546983 -0.08997601 -0.03453463 -0.138947 -0.08873379 -0.03847622 -0.1406462 -0.08847963 -0.03849077 -0.1379362 -0.09284609 -0.03232878 -0.1289492 -0.08892846 -0.03966635 -0.06083488 -0.09535717 -0.03940367 -0.05627226 -0.09479874 -0.04097837 -0.04172557 -0.0962044 -0.04014414 -0.003606498 -0.09564125 -0.04340559 -0.003558039 -0.0973013 -0.04141169 0.02291125 -0.09843587 -0.04049086 0.03292161 -0.09811109 -0.04110258 0.08238738 -0.09835004 -0.03930491 0.08141881 -0.0992307 -0.03784525 -0.29 -0.04834538 -0.01173114 -0.29 -0.0487169 -0.01140958 -0.283889 -0.06186658 -0.01063305 -0.276611 -0.06725847 -0.01724797 -0.280382 -0.0652731 -0.01372277 -0.27259 -0.07251 -0.01549476 -0.2479422 -0.08309644 -0.01624298 -0.2386336 -0.08509314 -0.01768904 -0.2196952 -0.08820998 -0.02084875 -0.2101401 -0.08934372 -0.02252131 -0.2291883 -0.08679902 -0.01923328 -0.1863928 -0.08956182 -0.02909475 -0.1863854 -0.08785128 -0.03124386 -0.1535089 -0.08633649 -0.03868496 -0.1576184 -0.08416825 -0.03975039 -0.1578146 -0.08823829 -0.03613656 -0.1389055 -0.08694779 -0.04025352 -0.1289089 -0.08719933 -0.04138451 -0.07540124 -0.09383577 -0.04021638 -0.03716534 -0.09506446 -0.04240673 0.01066863 -0.09632879 -0.04300868 0.01048487 -0.09573668 -0.0435217 -0.003578007 -0.09679549 -0.04213488 0.08176946 -0.09891194 -0.03844797 -0.29 -0.04714286 -0.01257979 -0.283885 -0.06062829 -0.01262456 -0.29 -0.04490357 -0.01357215 -0.2870912 -0.0478326 -0.0166887 -0.29 -0.04443114 -0.01370286 -0.27661 -0.0648964 -0.01953738 -0.28038 -0.06345248 -0.01599848 -0.2386195 -0.08383876 -0.01986098 -0.2053609 -0.08845835 -0.02557539 -0.2149309 -0.08751648 -0.02382725 -0.229192 -0.0855534 -0.02135431 -0.2053704 -0.08686983 -0.02763867 -0.1957966 -0.08558923 -0.03139936 -0.22201 -0.0866239 -0.02257245 -0.1388506 -0.0845859 -0.04215091 -0.1388942 -0.08652216 -0.04063916 -0.134114 -0.09047728 -0.037 -0.128998 -0.0910179 -0.037 -0.1288094 -0.0829395 -0.04444295 -0.0755819 -0.09280323 -0.04168993 -0.05637741 -0.09393203 -0.04221546 -0.003618955 -0.09498512 -0.04396647 -0.003581285 -0.09624379 -0.04279619 0.01054143 -0.09686732 -0.04245418 0.02292984 -0.09764111 -0.04168307 -0.287084 -0.0499078 -0.0159288 -0.29 -0.04627686 -0.01304244 -0.29 -0.04671645 -0.01282137 -0.28388 -0.05907827 -0.01451605 -0.2870836 -0.04535627 -0.01715087 -0.29 -0.0439527 -0.01381015 -0.2803342 -0.04279696 -0.02302181 -0.2386296 -0.08232474 -0.02193158 -0.2291861 -0.08407646 -0.02336657 -0.21248 -0.08623999 -0.02629995 -0.2196713 -0.08544433 -0.02499037 -0.1388068 -0.08273774 -0.04335415 -0.140727 -0.08236396 -0.04329454 -0.1288831 -0.08610653 -0.04229307 -0.07572114 -0.0916531 -0.04303395 -0.05648833 -0.09296965 -0.04334259 0.03294664 -0.09704381 -0.04232972 0.08283746 -0.09794056 -0.03981971 -0.29 -0.04537099 -0.01341766 -0.29 -0.04582828 -0.01324129 -0.283876 -0.05728775 -0.01618725 -0.280377 -0.06132584 -0.01802498 -0.280368 -0.05450946 -0.02184998 -0.276608 -0.05723994 -0.02390849 -0.2385949 -0.08056259 -0.02387905 -0.2291804 -0.08235782 -0.0252543 -0.210162 -0.08468371 -0.02862393 -0.2196895 -0.08370995 -0.02686208 -0.20292 -0.08520716 -0.03001564 -0.1863065 -0.08146172 -0.03641855 -0.18634 -0.08377224 -0.03493195 -0.1863789 -0.08591145 -0.03319746 -0.1574963 -0.08188587 -0.04120576 -0.1479191 -0.08210653 -0.04247742 -0.1387489 -0.08027487 -0.04459464 -0.07583343 -0.09038847 -0.04425442 -0.05659687 -0.09191328 -0.0443685 -0.29 -0.04346746 -0.01389437 -0.283872 -0.05537235 -0.01755177 -0.272593 -0.06525576 -0.02265095 -0.259434 -0.05901229 -0.02869087 -0.2338571 -0.07953125 -0.0262956 -0.2244414 -0.08111524 -0.02776068 -0.2053833 -0.083009 -0.03125965 -0.1981066 -0.08113187 -0.03416764 -0.2149418 -0.08224624 -0.02944308 -0.1957813 -0.08349144 -0.03312784 -0.1574336 -0.0794683 -0.04240077 -0.1387265 -0.0793218 -0.04497712 -0.1386843 -0.07752728 -0.04560899 -0.141923 -0.07755708 -0.04521113 -0.1525765 -0.07707077 -0.04398071 -0.148028 -0.08434444 -0.04105198 -0.0951277 -0.08734774 -0.04500991 -0.07592642 -0.08900612 -0.04535424 -0.05667936 -0.09076017 -0.04529786 -0.04233276 -0.09097325 -0.04578673 0.02300053 -0.09463101 -0.04417586 0.01293963 -0.09368067 -0.04474294 0.005938291 -0.09410989 -0.04459857 0.01305425 -0.0951997 -0.04391402 0.02297455 -0.09573614 -0.0434916 0.02295261 -0.09667289 -0.04273641 0.03297239 -0.0959481 -0.04323339 0.09036058 -0.09707748 -0.04039996 -0.283867 -0.0534507 -0.01858758 -0.280371 -0.0567283 -0.02095198 -0.2196584 -0.07952421 -0.03010588 -0.2101356 -0.08043783 -0.03185093 -0.190818 -0.07635986 -0.03773581 -0.1885498 -0.07897526 -0.03722059 -0.1386328 -0.07533973 -0.04617142 -0.1478593 -0.07973015 -0.04365396 -0.1287676 -0.08118635 -0.04532766 -0.1286589 -0.07657605 -0.04689311 -0.08082056 -0.08701163 -0.04632002 -0.06158018 -0.08900088 -0.04620975 -0.02305346 -0.0927807 -0.04517173 0.03306806 -0.09187299 -0.04478442 0.07326626 -0.09596979 -0.04207283 0.100722 -0.0964266 -0.04039996 0.104169 -0.09616285 -0.04039996 -0.29 -0.04249238 -0.01398885 -0.283863 -0.05160397 -0.01932346 -0.254842 -0.05856907 -0.02900952 -0.2239493 -0.076599 -0.03062927 -0.2100843 -0.07802522 -0.03311419 -0.2004674 -0.0785889 -0.0349465 -0.1427969 -0.07494145 -0.04576724 -0.1287114 -0.07878959 -0.04628008 -0.09514075 -0.08374142 -0.04706114 -0.08553743 -0.0847941 -0.04716628 -0.08555978 -0.08291697 -0.04789322 -0.07128435 -0.08643561 -0.04712098 -0.05207562 -0.08868813 -0.04672712 -0.03281712 -0.09083276 -0.04608917 0.03303003 -0.09349781 -0.04444622 0.08770704 -0.09494906 -0.04205256 0.12136 -0.09449487 -0.04039996 -0.2871198 -0.04199981 -0.01716482 -0.2838161 -0.04303562 -0.02029663 -0.283859 -0.04987525 -0.0198127 -0.2826924 -0.04200005 -0.02123481 -0.280365 -0.05243396 -0.02244597 -0.2293568 -0.07314473 -0.03076529 -0.2143678 -0.0751546 -0.03328406 -0.189124 -0.07113492 -0.03908336 -0.1939868 -0.07368296 -0.03779816 -0.2003328 -0.07604533 -0.03592801 -0.1763957 -0.07131451 -0.04136353 -0.1813067 -0.0739175 -0.04013478 -0.1813647 -0.07654589 -0.03946971 -0.1385015 -0.069772 -0.04666543 -0.09514611 -0.08174049 -0.04782676 -0.07593888 -0.08414804 -0.04784059 -0.06176519 -0.08600848 -0.04758995 -0.05226778 -0.08568751 -0.04778134 -0.04256713 -0.08847993 -0.0469805 -0.02333974 -0.09072756 -0.04620105 0.07810848 -0.09433287 -0.04276323 0.092583 -0.09394329 -0.04230338 0.1247889 -0.09409129 -0.04039996 0.128215 -0.0936644 -0.04039996 0.131638 -0.09321409 -0.04039996 -0.29 -0.04298138 -0.0139538 -0.283854 -0.04827517 -0.02010679 -0.280362 -0.05051565 -0.0228036 -0.2771038 -0.04199993 -0.0249933 -0.2293335 -0.07053679 -0.03143668 -0.2173635 -0.07224863 -0.03341549 -0.1047745 -0.07838934 -0.04821175 -0.0951668 -0.07960933 -0.04839402 -0.08556842 -0.08090978 -0.04843831 -0.07141739 -0.08292275 -0.04830056 -0.0331279 -0.08830296 -0.04702895 0.07813692 -0.0933547 -0.04311782 0.1018217 -0.0926131 -0.042364 0.135058 -0.09274047 -0.04039996 0.138474 -0.09224361 -0.04039996 -0.2838424 -0.04658991 -0.02027356 -0.2765952 -0.0504294 -0.02524513 -0.2803653 -0.04836046 -0.02300304 -0.2314386 -0.04199999 -0.03156584 -0.2359512 -0.04199993 -0.03092223 -0.2199598 -0.06929069 -0.03333914 -0.2098949 -0.07025289 -0.03515297 -0.1810851 -0.06857824 -0.04062986 -0.1909615 -0.06843638 -0.03882348 -0.1668585 -0.07144564 -0.04294013 -0.1716097 -0.06868785 -0.04226028 -0.1477662 -0.07198405 -0.04559862 -0.09994858 -0.0766648 -0.04867571 -0.09033793 -0.0780335 -0.04878032 -0.08070081 -0.07948064 -0.04875504 -0.06662172 -0.08167141 -0.04853194 -0.04753631 -0.08463579 -0.04792934 -0.02860915 -0.0873624 -0.04713672 0.08342105 -0.09196323 -0.04325085 0.1065462 -0.09109908 -0.0424875 0.1258071 -0.09022736 -0.04175961 0.1309183 -0.0877974 -0.04167032 0.145298 -0.09117978 -0.04039996 -0.2591783 -0.04199987 -0.02878129 -0.245455 -0.04199993 -0.02978062 -0.2268198 -0.04199999 -0.03228092 -0.2153949 -0.0671783 -0.03423339 -0.2067514 -0.06782644 -0.03583097 -0.09269249 -0.07513028 -0.04886335 -0.08559656 -0.07620656 -0.04888498 -0.07600444 -0.07771849 -0.04880529 -0.06638902 -0.07926666 -0.04862278 -0.05679267 -0.08081394 -0.04835581 -0.04724681 -0.08232522 -0.04802387 -0.03471106 -0.08424037 -0.04751908 0.09392422 -0.08944553 -0.04303771 0.1116762 -0.0887047 -0.04242062 -0.1810455 -0.05805945 -0.04063737 -0.1621694 -0.05814445 -0.04374963 -0.1048806 -0.06121766 -0.04866319 -0.09750008 -0.06195956 -0.0488103 0.09268808 -0.06716108 -0.04308015 -0.2755843 -0.04199934 -0.02573889 -0.2005798 -0.05546241 -0.03700208 -0.1910781 -0.05800366 -0.03880023 -0.1679025 -0.05622977 -0.04285693 -0.1742256 -0.05812901 -0.04181861 -0.06380212 -0.06179082 -0.04855597 -0.0926885 -0.05895406 -0.04886335 -0.08787655 -0.05940097 -0.04888296 -0.0830633 -0.0598616 -0.04887127 -0.07824903 -0.06033349 -0.04883044 -0.07343417 -0.06081408 -0.04876279 -0.06861841 -0.06130069 -0.04867058 -0.05898517 -0.06228178 -0.0484212 -0.05203747 -0.06217205 -0.0481975 -0.04287195 -0.06374895 -0.04785513 -0.03186833 -0.06484371 -0.047396 -0.007987856 -0.06690388 -0.04633396 0.001995801 -0.0674557 -0.04591864 -0.1929447 -0.05564153 -0.03852373 -0.1797086 -0.05595237 -0.04094654 -0.1522206 -0.05659747 -0.04507136 -0.117747 -0.05740749 -0.04784429 -0.1068513 -0.05766248 -0.04810094 -0.09497416 -0.05794262 -0.04828196 0.07595729 -0.06872332 -0.04359138 0.121095 -0.06301432 -0.04205644 0.1415106 -0.0634936 -0.04121905 0.1639699 -0.06402093 -0.0402134 -0.09019589 -0.05805385 -0.04833346 -0.08544528 -0.05816537 -0.04836809 -0.08069467 -0.05827689 -0.04838806 -0.0759443 -0.05838847 -0.04839348 -0.07119399 -0.05849999 -0.04838418 -0.06644368 -0.05861145 -0.04836034 -0.06169348 -0.05872297 -0.04832196 -0.05455529 -0.05889058 -0.04823791 -0.04508453 -0.0591129 -0.04807406 -0.03565013 -0.05933439 -0.04785311 -0.02629649 -0.05955398 -0.0475772 -0.01114749 -0.05990916 -0.04701155 0.002893745 -0.06023931 -0.04635274 0.07192236 -0.0618599 -0.04377615 0.009549915 -0.06039559 -0.04599356 0.01429885 -0.06050705 -0.04572159 0.01904767 -0.06061857 -0.04543495 0.1002152 -0.06252419 -0.04283428 0.455 -0.05670845 -0.00898683 0.455 -0.08023166 -0.01130259 0.455 -0.08039987 -0.01069396 0.455 -0.06302237 -0.005898475 0.455 -0.056225 -0.008999943 0.455 -0.06164783 -0.02344751 0.455 -0.05813515 -0.008794844 0.455 -0.06286174 -0.02346283 0.455 -0.05906516 -0.008540034 0.455 -0.05860298 -0.008679986 0.455 -0.05951654 -0.008376359 0.455 -0.06669586 -0.02319198 0.455 -0.05766355 -0.008884251 0.455 -0.06199198 -0.00690931 0.455 -0.07841998 -0.01532888 0.455 -0.07873988 -0.01478415 0.455 -0.05718797 -0.008948266 0.455 -0.05575859 -0.008987724 0.455 -0.05091154 -0.02344739 0.455 -0.05529588 -0.008951842 0.455 -0.05483686 -0.008892297 0.455 -0.06607127 -0.0232923 0.455 -0.06544327 -0.02337008 0.455 -0.0648142 -0.02342069 0.455 -0.06793445 -0.02293056 0.455 -0.06731605 -0.02307105 0.455 -0.06975066 -0.02237927 0.455 -0.06915128 -0.02258515 0.455 -0.06854647 -0.02276879 0.455 -0.07092159 -0.02190357 0.455 -0.05996018 -0.008188128 0.455 -0.07034099 -0.02215194 0.455 -0.05437785 -0.008808255 0.455 -0.0714944 -0.02163267 0.455 -0.07260549 -0.02103108 0.455 -0.0731461 -0.02069979 0.455 -0.07205569 -0.0213418 0.455 -0.07367247 -0.02034926 0.455 -0.06039375 -0.007976233 0.455 -0.07418495 -0.01997959 0.455 -0.07468497 -0.0195893 0.455 -0.0751686 -0.01918178 0.455 -0.06081324 -0.007742404 0.455 -0.07608866 -0.01831376 0.455 -0.07652306 -0.01785498 0.455 -0.07563626 -0.01875674 0.455 -0.06122136 -0.007485508 0.455 -0.05392628 -0.008701384 0.455 -0.04998242 -0.02342754 0.455 -0.07694047 -0.01737999 0.455 -0.07734096 -0.01688826 0.455 -0.06161516 -0.007207334 0.455 -0.07772117 -0.01638305 0.455 -0.07808077 -0.01586306 0.455 -0.05348199 -0.008571803 0.455 -0.07904195 -0.01422828 0.455 -0.07932496 -0.01366186 0.455 -0.06235408 -0.006590306 0.455 -0.05304145 -0.008417963 0.455 -0.05261164 -0.008242726 0.455 -0.04901546 -0.02338826 0.455 -0.07958549 -0.01308625 0.455 -0.05219268 -0.00804615 0.455 -0.0641213 -0.004318296 0.455 -0.06387799 -0.004735887 0.455 -0.074225 -0.002999961 0.455 -0.05178117 -0.007826209 0.455 -0.06269788 -0.006253004 0.455 -0.07982355 -0.01249957 0.455 -0.05138367 -0.007586836 0.455 -0.08003908 -0.011904 0.455 -0.05099999 -0.007327914 0.455 -0.05062729 -0.007047176 0.455 -0.05027139 -0.006749331 0.455 -0.0499323 -0.006434381 0.455 -0.04960978 -0.006102263 0.455 -0.04930406 -0.005753099 0.455 -0.04901522 -0.005387008 0.455 -0.08054566 -0.01007997 0.455 -0.08067095 -0.009462237 0.455 -0.06361418 -0.00513792 0.455 -0.08077645 -0.008839547 0.455 -0.06411534 -0.0234493 0.455 -0.0633291 -0.00552541 0.455 -0.08086097 -0.008213698 0.455 -0.08092349 -0.007585823 0.455 -0.08095717 -0.006808698 0.455 -0.06434047 -0.003890693 0.455 -0.08097487 -0.005629241 0.455 -0.06453669 -0.003451406 0.455 -0.06471025 -0.002999961 0.455 -0.0809319 0 0.455 -0.074225 0 0.15211 -0.09002268 -0.04039996 0.09331017 -0.08841687 -0.004358887 0.176136 -0.09067881 -0.037 0.16198 -0.09029215 -0.03969866 0.166785 -0.0904234 -0.03932255 0.171503 -0.09055227 -0.03892958 0.157088 -0.09015858 -0.04005777 0.09331017 -0.08841687 -0.04039996 0.176136 -0.09067881 -0.03851968 0.186132 -0.0909518 -0.037 0.1971358 -0.09125232 -0.03631931 0.1931443 -0.09114336 -0.03678524 0.1891326 -0.09103375 -0.03722965 0.2011517 -0.09136188 -0.03582483 0.186132 -0.0909518 -0.03754657 0.2051336 -0.09147071 -0.03530728 0.2250782 -0.09201532 -0.03219085 0.213483 -0.0916987 -0.007949769 0.218632 -0.09183925 -0.006773412 0.219006 -0.09184956 -0.006523191 0.2499769 -0.09269529 0 0.2499769 -0.09269529 -0.02384978 0.2362495 -0.09232038 -0.02983278 0.21393 -0.09171086 -0.00798732 0.217848 -0.09181785 -0.007206797 0.217438 -0.0918067 -0.007390737 0.2197059 -0.09186869 -0.005964756 0.219365 -0.09185928 -0.006253242 0.2217659 -0.0919249 -0.003059625 0.221925 -0.09192925 -0.002641975 0.220341 -0.09188598 -0.005329132 0.2206299 -0.09189391 -0.004987537 0.2182469 -0.09182876 -0.007000625 0.222062 -0.09193295 -0.002212524 0.2429585 -0.0925036 -0.02794784 0.2376282 -0.09235811 -0.02948701 0.2389294 -0.09239357 -0.02914428 0.2471831 -0.092619 -0.02627778 0.246459 -0.09259915 -0.02661907 0.2489894 -0.09266841 -0.02518111 0.2482852 -0.09264916 -0.02566915 0.2497455 -0.09268885 -0.02441161 0.24987 -0.09269237 -0.02418845 0.2495293 -0.09268307 -0.02468919 0.249934 -0.09269416 -0.02402305 0.2492681 -0.09267592 -0.02494829 0.248691 -0.0926603 -0.02540057 0.2477241 -0.09263384 -0.02599501 0.245822 -0.09258186 -0.02689397 0.24518 -0.09256428 -0.02715319 0.2442616 -0.09253925 -0.02749907 0.2416055 -0.09246671 -0.02837705 0.240262 -0.09242993 -0.0287739 0.214379 -0.0917232 -0.007999837 0.21702 -0.09179526 -0.007550179 0.216157 -0.09177178 -0.007799208 0.215719 -0.0917598 -0.007886409 0.220033 -0.09187757 -0.005655288 0.221376 -0.09191429 -0.003869414 0.221583 -0.09191989 -0.003469049 0.2208999 -0.0919013 -0.004627585 0.222324 -0.0919401 -8.97431e-4 0.222361 -0.09194117 -4.50783e-4 0.222174 -0.09193611 -0.001778304 0.222261 -0.09193837 -0.001339912 0.221149 -0.09190809 -0.00425446 0.231898 -0.09220159 -0.03083056 0.229929 -0.09214776 -0.03124499 0.222374 -0.09194147 0 0.212599 -0.09167456 -0.007799565 0.2130399 -0.0916866 -0.007887184 0.212164 -0.0916627 -0.007687628 0.211738 -0.09165108 -0.00755167 0.211318 -0.09163957 -0.007391333 0.216592 -0.09178358 -0.007686674 0.214826 -0.09173536 -0.00798732 0.215274 -0.09174758 -0.007949352 0.234379 -0.09226936 -0.03027844 0.227957 -0.092094 -0.03164106 0.2210916 -0.09190648 -0.03289932 0.2171149 -0.09179782 -0.03355747 0.2131446 -0.0916894 -0.03417307 0.2091627 -0.09158068 -0.0347535 0.2109079 -0.09162837 -0.007208228 0.210511 -0.09161746 -0.007002711 0.210123 -0.09160697 -0.006774246 0.2097499 -0.09159678 -0.006525218 0.209393 -0.091587 -0.006255924 0.209049 -0.09157758 -0.00596565 0.208723 -0.0915687 -0.005657792 0.208416 -0.0915603 -0.00533235 0.2081249 -0.09155237 -0.004988431 0.2078559 -0.09154498 -0.004630506 0.207607 -0.09153831 -0.004258096 0.207378 -0.09153199 -0.003870189 0.207173 -0.09152638 -0.003472447 0.20699 -0.09152138 -0.003063499 0.09336125 -0.08841836 -0.003423511 0.206829 -0.09151697 -0.002642571 0.2066929 -0.09151327 -0.002216219 0.2065809 -0.09151017 -0.001782298 0.09349495 -0.08842229 -0.001755237 0.0935412 -0.08842349 -8.79866e-4 0.206493 -0.09150779 -0.00134021 0.206393 -0.09150511 -4.50783e-4 0.206431 -0.09150606 -8.97431e-4 0.0935626 -0.08842378 0 0.20638 -0.09150469 0 0.186213 -0.08749568 -0.03888487 0.1867516 -0.06455576 -0.03910237 0.186752 -0.06455576 -0.037 0.1862986 -0.08384907 -0.03912508 0.186238 -0.08643651 -0.03904139 0.1862249 -0.08696538 -0.03897255 0.18625 -0.08591079 -0.03909325 0.186201 -0.08801227 -0.03876447 0.186262 -0.08539021 -0.03912079 0.1861889 -0.08852446 -0.03861999 0.186177 -0.08903205 -0.03845119 0.186165 -0.08952909 -0.03825938 0.186154 -0.09001296 -0.03804498 0.186143 -0.09048718 -0.0378074 0.186132 -0.0909518 -0.03754657 0.186132 -0.0909518 -0.037 0.200843 -0.06488668 -0.03838139 0.186752 -0.06455576 -0.037 0.186752 -0.06455576 -0.03910237 0.214199 -0.06520026 -0.03768056 0.226821 -0.0654965 -0.037 0.186752 -0.06455576 -0.037 0.226821 -0.0654965 -0.037 0.226821 -0.05949068 -0.037 -0.1382009 -0.0569269 -0.037 -0.2005783 -0.04945659 -0.037 -0.134114 -0.09047728 -0.037 -0.128998 -0.0910179 -0.037 -0.128203 -0.05716156 -0.037 -0.200579 -0.05546236 -0.037 -0.138976 -0.08993309 -0.037 0.03379368 -0.06096476 -0.037 0.0228855 -0.09953218 -0.037 0.02796369 -0.09962975 -0.037 0.02379649 -0.06073009 -0.037 0.03288406 -0.09971147 -0.037 0.176136 -0.09067881 -0.037 0.186132 -0.0909518 -0.037 0.1767539 -0.0643211 -0.037 0.226821 -0.05949068 -0.037 0.226821 -0.05648988 -0.03999996 0.226821 -0.05949068 -0.03999996 0.226821 -0.05648988 -0.037 0.226821 -0.05048829 -0.037 0.213117 -0.05016648 -0.03773736 0.187104 -0.04955577 -0.037 0.199878 -0.04985564 -0.0384323 0.187104 -0.04955577 -0.03908467 0.187637 -0.02685117 -0.03904455 0.187615 -0.02738755 -0.03906154 0.1876609 -0.02580159 -0.03893685 0.187649 -0.02632576 -0.03900259 0.1875705 -0.0296961 -0.0390613 0.1875852 -0.02865773 -0.03907603 0.187674 -0.02527898 -0.0388478 0.187686 -0.02476328 -0.03873509 0.187698 -0.02425479 -0.03859895 0.18771 -0.02374875 -0.03843826 0.187332 -0.03982895 -0.03907322 0.187721 -0.0232529 -0.03825479 0.1877329 -0.02276796 -0.03804886 0.187104 -0.04955577 -0.037 0.187744 -0.02229386 -0.03782039 0.1871041 -0.04955577 -0.03908473 0.187755 -0.02183079 -0.03756946 0.187765 -0.02137869 -0.03729599 0.187776 -0.02093738 -0.037 0.29 -0.02712118 -0.02999997 0.29 -0.02679258 -0.02968138 0.29 -0.02597606 -0.02999997 0.29 -0.02597606 0 0.29 -0.02647608 -0.02935117 0.29 -0.02647608 0 0.295 -0.02647608 -0.02862 0.29 -0.02647608 0 0.29 -0.02647608 -0.02935117 0.295 -0.02647608 0 0.295 -0.04127627 0 0.295 -0.04127627 -0.03315812 0.295 -0.03762876 -0.03315681 0.295 -0.03661143 -0.03314524 0.295 -0.03520387 -0.03310728 0.295 -0.03406006 -0.03295606 0.295 -0.03461009 -0.03304004 0.295 -0.03296917 -0.03272205 0.295 -0.03351157 -0.03285127 0.295 -0.03243619 -0.03256589 0.295 -0.02647608 0 0.295 -0.03190904 -0.03238546 0.295 -0.03138798 -0.0321809 0.295 -0.03087908 -0.03195744 0.295 -0.03037995 -0.03171324 0.295 -0.02989006 -0.03144764 0.295 -0.02941089 -0.03116118 0.295 -0.02894759 -0.03085595 0.295 -0.02849668 -0.03053057 0.295 -0.02805817 -0.03018516 0.295 -0.027637 -0.02982139 0.295 -0.02723395 -0.02943968 0.295 -0.026847 -0.0290392 0.295 -0.02647608 -0.02862 0.314874 -0.04192686 -0.004635632 0.334 -0.04255306 -0.01499998 0.315193 -0.04193735 -0.004493296 0.455 -0.04651415 -0.002999961 0.455 -0.04651415 0 0.360222 -0.04341149 -0.002999961 0.312133 -0.04183715 -0.004924178 0.311791 -0.04182595 -0.00485146 0.308012 -0.04170227 -3.50216e-4 0.295 -0.04127627 0 0.308049 -0.04170346 -6.96429e-4 0.30811 -0.04170548 -0.001040756 0.309171 -0.04174017 -0.003214716 0.309404 -0.04174786 -0.003474056 0.36 -0.04340416 -0.02599996 0.328607 -0.04237645 -0.03119146 0.345409 -0.04292654 -0.03018468 0.37901 -0.04402649 -0.02812385 0.395809 -0.04457646 -0.02706974 0.412608 -0.04512637 -0.02599996 0.36221 -0.04347658 -0.02916216 0.31421 -0.04190516 -0.00485146 0.31387 -0.04189407 -0.004923701 0.314546 -0.04191619 -0.004754722 0.317988 -0.0420289 -3.50216e-4 0.317951 -0.04202765 -6.96429e-4 0.334 -0.04255306 0 0.308302 -0.04171174 -0.001710712 0.308194 -0.04170829 -0.001379132 0.308 -0.04170185 0 0.317046 -0.04199796 -0.002937972 0.316831 -0.04199099 -0.003213286 0.316598 -0.04198336 -0.003472149 0.308433 -0.04171609 -0.002034842 0.308585 -0.0417211 -0.002347469 0.316079 -0.04196637 -0.003939092 0.316346 -0.04197508 -0.003715515 0.308761 -0.04172676 -0.002650737 0.308955 -0.0417332 -0.002939462 0.309655 -0.04175609 -0.003715932 0.309923 -0.04176485 -0.00394082 0.315501 -0.04194748 -0.004329502 0.310501 -0.04178375 -0.004330694 0.310204 -0.04177409 -0.004145324 0.311128 -0.04180425 -0.004636168 0.310809 -0.04179388 -0.004494309 0.295 -0.04127627 -0.03315764 0.311456 -0.0418151 -0.004755556 0.312478 -0.04184848 -0.004972636 0.311804 -0.04182636 -0.03218245 0.312827 -0.04185986 -0.004996836 0.313523 -0.04188269 -0.004972398 0.313175 -0.04187124 -0.004996836 0.315796 -0.04195708 -0.004144787 0.317241 -0.04200434 -0.002648472 0.337 -0.04265129 -0.01499998 0.3600039 -0.04340428 -0.003738343 0.337 -0.04265129 0 0.360037 -0.04340535 -0.003503262 0.360083 -0.0434069 -0.003322005 0.317415 -0.04201006 -0.002347052 0.317699 -0.04201936 -0.001709699 0.317568 -0.04201507 -0.002032339 0.317891 -0.04202568 -0.00103861 0.317807 -0.04202288 -0.001376807 0.318 -0.04202926 0 0.360145 -0.04340887 -0.003153383 0.360967 -0.04593718 -0.02599996 0.4135289 -0.04586666 -0.02599996 0.360666 -0.04588025 -0.02599996 0.360526 -0.04581797 -0.02599996 0.360814 -0.04592037 -0.02599996 0.360396 -0.04573488 -0.02599996 0.360183 -0.04551458 -0.02599996 0.360281 -0.04563295 -0.02599996 0.413949 -0.04767167 -0.02599996 0.4139497 -0.04673737 -0.02599996 0.413936 -0.04658406 -0.02599996 0.413836 -0.04629075 -0.02599996 0.413897 -0.04643368 -0.02599996 0.4137273 -0.0461086 -0.02599996 0.4132934 -0.04563897 -0.02599996 0.4130539 -0.04544126 -0.02599996 0.4126147 -0.04512703 -0.02599996 0.360104 -0.04538267 -0.02599996 0.360012 -0.04509097 -0.02599996 0.360047 -0.04524028 -0.02599996 0.36 -0.04493767 -0.02599996 0.36 -0.04340416 -0.02599996 0.360967 -0.04593718 -0.005414187 0.360967 -0.04593718 -0.02599996 0.413949 -0.04767167 -0.02599996 0.427635 -0.04811966 -0.02515727 0.441318 -0.04856759 -0.02428668 0.455 -0.04901546 -0.005414187 0.455 -0.04901546 -0.02338826 0.285347 -0.02647608 -0.02999997 0.29 -0.02597606 -0.02999997 0.275 -0.02597606 -0.02999997 0.275 -0.02647608 -0.02999997 0.29 -0.02712118 -0.02999997 0.275 -0.02647608 -0.02999997 0.280212 -0.02647608 -0.03068405 0.285347 -0.02647608 -0.02999997 0.275 -0.02647608 -0.03134715 0.275 -0.02597606 -0.02999997 0.29 -0.02597606 -0.02999997 0.29 -0.02597606 0 0.275 -0.02597606 0 0.363 -0.01887422 0 0.363 -0.02387237 0 0.363 -0.0188561 -0.008881151 0.363 -0.02387237 -0.01499998 0.363 -0.01882779 -0.01499998 0.337 -0.02487236 -0.01499998 0.334 -0.04255306 -0.01499998 0.337 -0.04265129 -0.01499998 0.337012 -0.02471596 -0.01499998 0.334 -0.01688188 -0.01499998 0.337109 -0.02441835 -0.01499998 0.337049 -0.02456337 -0.01499998 0.337293 -0.02416527 -0.01499998 0.337191 -0.0242846 -0.01499998 0.337546 -0.02398139 -0.01499998 0.337412 -0.02406334 -0.01499998 0.337844 -0.02388465 -0.01499998 0.337691 -0.02392137 -0.01499998 0.338 -0.02387237 -0.01499998 0.363 -0.01882779 -0.01499998 0.363 -0.02387237 -0.01499998 0.334 -0.04255306 -0.01499998 0.334 -0.01688188 -0.01499998 0.3340001 -0.01689869 -0.009301006 0.3340001 -0.01691001 0 0.334 -0.04255306 0 0.334 -0.01690888 0 0.318 -0.01582509 0 0.318 -0.04202926 0 0.334 -0.04255306 0 0.3080646 -0.01515424 -8.17835e-4 0.3079903 -0.04170161 -3.42235e-7 0.3080775 -0.04170441 -8.90832e-4 0.3079941 -0.01514929 -2.09566e-7 0.3083009 -0.04171174 -0.00173068 0.3082618 -0.01516759 -0.001620113 0.3086822 -0.01519542 -0.00253582 0.3087596 -0.04172676 -0.002664148 0.3092887 -0.04174405 -0.003354728 0.3092846 -0.01523542 -0.003357887 0.3099157 -0.04176461 -0.003945112 0.3099024 -0.01527667 -0.003928065 0.3107584 -0.01533401 -0.004485428 0.3109413 -0.04179817 -0.004572689 0.3116992 -0.01539731 -0.004829406 0.3121016 -0.04183614 -0.004926323 0.3130005 -0.04186552 -0.005003809 0.3125002 -0.01545113 -0.004978775 0.3140797 -0.04190093 -0.004897058 0.3132971 -0.01550477 -0.004993736 0.3152154 -0.04193812 -0.004490852 0.3143219 -0.01557397 -0.004840075 0.3155443 -0.01565706 -0.00431931 0.31636 -0.01571267 -0.00370723 0.3160903 -0.04196673 -0.003940284 0.3167173 -0.04198729 -0.003348529 0.3170426 -0.01575928 -0.002966165 0.3173348 -0.04200744 -0.002521038 0.3176888 -0.01580363 -0.001776397 0.3178571 -0.04202455 -0.001247584 0.3179363 -0.01582068 -8.09254e-4 0.3180098 -0.04202955 -3.44069e-7 0.3180059 -0.01582556 -2.10326e-7 0.283 -0.02147608 0 0.275 -0.02147608 0 0.275 -0.02597606 0 0.283 -0.01347607 0 0.295 -0.02647608 0 0.308 -0.01514977 0 0.295 -0.04127627 0 0.308 -0.04170185 0 0.29 -0.02597606 0 0.29 -0.02647608 0 -0.137223 0.002923011 -0.03299999 -0.139964 0.002951383 -0.03299999 -0.139964 0.002951443 0 -0.137223 0.002923369 0 -0.137223 0.002855181 -0.03299999 -0.137223 0.002923309 -0.03299999 -0.137223 0.002906441 -0.02886068 -0.137223 0.002918183 -0.02591657 -0.137223 0.002921879 -0.02483928 -0.137223 0.002923309 -0.03299999 -0.1401 0.002849698 -0.03299999 -0.139964 0.002951443 -0.03299999 -0.137223 0.002855181 -0.03299999 -0.151383 -0.005595147 -0.04199999 -0.144243 -2.50947e-4 -0.0424239 -0.144602 -5.19653e-4 -0.04284149 -0.151383 -0.005595147 0 -0.1399639 0.002951383 0 -0.1401849 0.002785801 -0.03360235 -0.1401 0.002849698 -0.03299999 -0.140289 0.002707958 -0.03419715 -0.139964 0.002951443 -0.03299999 -0.140412 0.002616107 -0.03478437 -0.1405529 0.002510249 -0.03536379 -0.140713 0.002390325 -0.03593558 -0.140892 0.002256453 -0.03649979 -0.14109 0.002108514 -0.03705626 -0.141306 0.001946628 -0.03760504 -0.141539 0.001772284 -0.03814375 -0.141786 0.001587808 -0.03866887 -0.142048 0.001391112 -0.03918349 -0.142328 0.001182138 -0.03968775 -0.1426219 9.61572e-4 -0.04018098 -0.1429229 7.36974e-4 -0.04065555 -0.143235 5.03371e-4 -0.04111647 -0.143559 2.60762e-4 -0.04156374 -0.143895 9.14807e-6 -0.04199737 -0.144972 -7.97095e-4 -0.04324889 -0.1455415 -0.001222908 -0.04383498 -0.146126 -0.001660764 -0.04439246 -0.1467035 -0.002092957 -0.04490637 -0.1475583 -0.002732634 -0.04559695 -0.1483314 -0.003310978 -0.0461713 -0.1492003 -0.003961324 -0.04675817 -0.150041 -0.004590749 -0.04727995 -0.1508946 -0.005229473 -0.04776108 -0.151576 -0.005739331 -0.04811519 -0.1522624 -0.006253242 -0.04845041 -0.1532073 -0.00696063 -0.0488727 -0.1541679 -0.007679104 -0.04926085 -0.1551568 -0.008418977 -0.04962021 -0.1560807 -0.009111464 -0.04992389 -0.157027 -0.009819269 -0.05019879 -0.157738 -0.0103513 -0.05038547 -0.1584553 -0.01088821 -0.05055832 -0.1594356 -0.01162177 -0.05076599 -0.1603777 -0.01232695 -0.05093812 -0.161366 -0.01306688 -0.05108958 -0.1622872 -0.01375621 -0.0512064 -0.1632205 -0.01445418 -0.05129855 -0.1641705 -0.0151655 -0.05136883 -0.1653673 -0.01606088 -0.05142414 -0.1665765 -0.01696628 -0.05143952 -0.1675546 -0.01769834 -0.05142551 -0.1685166 -0.01841807 -0.05138862 -0.169488 -0.01914519 -0.05132728 -0.1704488 -0.01986426 -0.05124378 -0.1716641 -0.02077347 -0.05110675 -0.1727084 -0.02155584 -0.05095791 -0.188 -0.03299999 -0.04199999 -0.1748654 -0.02316981 -0.05059903 -0.1818936 -0.02842974 -0.04939746 -0.188 -0.03299999 -0.04834491 -0.2493395 -0.04199999 -0.03875225 -0.24383 -0.04199999 -0.03950995 -0.242803 -0.04199999 -0.03964257 -0.236698 -0.04199999 -0.04050457 -0.232645 -0.04199999 -0.04110735 -0.230597 -0.04199999 -0.04139286 -0.238237 -0.04199999 -0.0402981 -0.224499 -0.04199999 -0.04230725 -0.221469 -0.04199999 -0.04278957 -0.218406 -0.04199999 -0.04324799 -0.227056 -0.04199999 -0.04193788 -0.212317 -0.04199999 -0.04421496 -0.210303 -0.04199999 -0.04455649 -0.206232 -0.04199999 -0.04520809 -0.215885 -0.04199999 -0.04366236 -0.1936501 -0.04199999 -0.04734975 -0.20015 -0.04199999 -0.04622757 -0.199147 -0.04199999 -0.04640829 -0.204724 -0.04199999 -0.04547178 -0.2550258 -0.04199999 -0.03799575 -0.255026 -0.03299999 -0.03799736 -0.2468181 -0.03299999 -0.03909391 -0.2277652 -0.04199999 -0.0418244 -0.2415665 -0.04199999 -0.03982383 -0.2290537 -0.03299999 -0.04162538 -0.2083209 -0.04199999 -0.04486596 -0.2067432 -0.03299999 -0.04512476 -0.1879996 -0.03299999 -0.0483427 -0.187999 -0.04199999 -0.04833972 -0.273685 -0.03299999 -0.03442209 -0.277903 -0.03299999 -0.03276908 -0.272349 -0.03299999 -0.03482466 -0.188 -0.03299999 0 -0.204724 -0.03299999 -0.04547178 -0.210303 -0.03299999 -0.04455649 -0.279983 -0.03299999 -0.0316714 -0.279298 -0.03299999 -0.03205406 -0.278605 -0.03299999 -0.03241997 -0.270996 -0.03299999 -0.03520607 -0.281325 -0.03299999 -0.03085565 -0.281982 -0.03299999 -0.03042006 -0.280659 -0.03299999 -0.03127199 -0.282627 -0.03299999 -0.02996206 -0.268241 -0.03299999 -0.035905 -0.269627 -0.03299999 -0.03556615 -0.263985 -0.03299999 -0.03679388 -0.284502 -0.03299999 -0.0284723 -0.262533 -0.03299999 -0.03704756 -0.283262 -0.03299999 -0.02948474 -0.283887 -0.03299999 -0.02898818 -0.266839 -0.03299999 -0.03622257 -0.261065 -0.03299999 -0.03728008 -0.285105 -0.03299999 -0.0279327 -0.285696 -0.03299999 -0.02736866 -0.258078 -0.03299999 -0.03768128 -0.25958 -0.03299999 -0.03749126 -0.255026 -0.03299999 -0.03799736 -0.25656 -0.03299999 -0.03784996 -0.286845 -0.03299999 -0.02617466 -0.287402 -0.03299999 -0.0255447 -0.286276 -0.03299999 -0.02678269 -0.288478 -0.03299999 -0.02420198 -0.288997 -0.03299999 -0.02349275 -0.287946 -0.03299999 -0.02488636 -0.2900008 -0.03299999 -0.0219987 -0.249427 -0.03299999 -0.03874307 -0.289505 -0.03299999 -0.02275878 -0.232645 -0.03299999 -0.04110735 -0.238237 -0.03299999 -0.0402981 -0.24383 -0.03299999 -0.03950995 -0.3000016 -0.03299999 0 -0.227056 -0.03299999 -0.04193788 -0.188 -0.03299999 -0.04834479 -0.193572 -0.03299999 -0.04736596 -0.221469 -0.03299999 -0.04278957 -0.199147 -0.03299999 -0.04640829 -0.215885 -0.03299999 -0.04366236 -0.26542 -0.03299999 -0.03651875 -0.276472 -0.03299999 -0.03341698 -0.277192 -0.03299999 -0.03310149 -0.275004 -0.03299999 -0.03399819 -0.275743 -0.03299999 -0.03371578 -0.2826644 -0.04199999 -0.02994656 -0.282261 -0.03299999 -0.03022897 -0.2803858 -0.04199999 -0.03146642 -0.280732 -0.03299999 -0.03123539 -0.2782983 -0.03299999 -0.03258723 -0.2773137 -0.04199999 -0.03305733 -0.2750094 -0.03299999 -0.03401219 -0.2750049 -0.04199999 -0.03400057 -0.2841268 -0.04199999 -0.02880632 -0.2839359 -0.03299999 -0.02895849 -0.285352 -0.03299999 -0.02770513 -0.2859248 -0.04199999 -0.02716255 -0.2871331 -0.03299999 -0.02587676 -0.2878179 -0.04199999 -0.02506989 -0.2886897 -0.03299999 -0.02392232 -0.2900115 -0.04199999 -0.02200752 -0.290005 -0.03299999 -0.02200323 -0.2928094 -0.03738659 -0.01594847 -0.3001834 -0.0387184 -1.83864e-7 -0.3001003 -0.04029428 3.97243e-7 -0.2899894 -0.03300011 -0.02199512 -0.2984498 -0.04365348 -0.002978801 -0.299974 -0.04179739 5.31249e-7 -0.2959292 -0.03299999 -0.008961617 -0.2955285 -0.0357272 -0.01005297 -0.300198 -0.03669941 1.18474e-6 -0.2997167 -0.04379791 8.18301e-7 -0.3001247 -0.03462588 4.85955e-7 -0.298413 -0.03568381 -0.003828942 -0.3000047 -0.03299969 -2.13456e-6 -0.296419 -0.04172611 -0.007938981 -0.2963162 -0.04435288 -0.007760167 -0.2980772 -0.0462132 -0.002998173 -0.2960965 -0.04704141 -0.007601559 -0.2993686 -0.04575824 4.80695e-7 -0.2975966 -0.04876619 -0.002934515 -0.2953147 -0.05244159 -0.006902694 -0.2957308 -0.04978758 -0.007382571 -0.2936778 -0.05351573 -0.01090419 -0.2900068 -0.06183338 -0.01541906 -0.29 -0.06229335 -0.01488816 -0.29 -0.06680566 -0.004781424 -0.2903882 -0.06590527 -0.005816102 -0.29 -0.06669676 -0.005468666 -0.2919968 -0.0613926 -0.008365213 -0.2916443 -0.0598846 -0.0117985 -0.29 -0.06356328 -0.01320886 -0.2900072 -0.06394475 -0.0126295 -0.29 -0.06315737 -0.01378726 -0.29 -0.06622511 -0.007510721 -0.2904879 -0.06473207 -0.008831381 -0.295341 -0.05784225 0 -0.2948318 -0.05818378 -0.001686632 -0.297036 -0.05125319 -0.00274074 -0.2987496 -0.04845649 3.66878e-7 -0.2955937 -0.05603903 -0.002228379 -0.2964009 -0.05366516 -0.002405703 -0.2981573 -0.05057448 0 -0.2964775 -0.05527365 -3.11109e-7 -0.2945932 -0.0593636 4.22172e-7 -0.292886 -0.06235152 -8.99122e-4 -0.292522 -0.06209009 -0.004370212 -0.2936113 -0.05958342 -0.004525303 -0.291717 -0.06441169 -3.53719e-4 -0.2931412 -0.06208199 0 -0.2912229 -0.06519675 5.31964e-7 -0.290601 -0.06612956 0 -0.2942314 -0.05738884 -0.005495548 -0.2947947 -0.05499792 -0.006316065 -0.29 -0.06656366 -0.006152629 -0.29 -0.06601959 -0.00818485 -0.29 -0.06579196 -0.008844852 -0.29 -0.06698757 -0.002700269 -0.29 -0.06699997 -0.001999974 -0.29 -0.06689047 -0.004090964 -0.2900006 -0.06700038 0 -0.29 -0.06695115 -0.003397226 -0.29 -0.0655409 -0.009497582 -0.29 -0.06640648 -0.006833314 -0.29 -0.06496858 -0.01078134 -0.29 -0.06526648 -0.0101431 -0.29 -0.06430906 -0.01201909 -0.2933279 -0.05618041 -0.009920299 -0.2939679 -0.05068957 -0.01162105 -0.2918426 -0.05738472 -0.01356786 -0.29 -0.06085175 -0.01642668 -0.29 -0.06134998 -0.01593089 -0.294227 -0.04775339 -0.01197409 -0.2920666 -0.05456614 -0.01484727 -0.2900059 -0.05926865 -0.0177977 -0.29 -0.0598095 -0.01735937 -0.2922107 -0.05158239 -0.01584982 -0.29 -0.05869847 -0.01822179 -0.29 -0.05812597 -0.01861965 -0.2943546 -0.04490244 -0.01217895 -0.2975484 -0.05243897 0 -0.29 -0.05570107 -0.02000808 -0.2900058 -0.05633658 -0.01968932 -0.29 -0.0550704 -0.02029949 -0.2923557 -0.048469 -0.01635044 -0.2972643 -0.03862738 -0.006333708 -0.29088 -0.05227249 -0.01904755 -0.29 -0.05442929 -0.02056896 -0.2927935 -0.04433995 -0.01577895 -0.29 -0.05178558 -0.02141916 -0.29 -0.05245405 -0.02124208 -0.290935 -0.04901456 -0.01967304 -0.29 -0.0511105 -0.02157306 -0.29 -0.04837805 -0.02195274 -0.29 -0.04906308 -0.02189356 -0.29 -0.04769039 -0.02198815 -0.2911972 -0.04455405 -0.01934182 -0.2899981 -0.04699516 -0.02199912 -0.29 -0.04974538 -0.02181077 -0.29 -0.05042874 -0.02170389 -0.29 -0.05753958 -0.01899749 -0.29 -0.05377775 -0.02081638 -0.29 -0.0569393 -0.01935529 -0.29 -0.0531159 -0.02104187 -0.2929334 -0.05864179 -0.008658885 -0.29 -0.06033915 -0.01690185 -0.29 -0.06273525 -0.01434499 -0.29 -0.0646491 -0.01140767 -0.2911451 -0.06524759 -0.001451432 -0.2902761 -0.06653189 -0.002940297 -0.2499481 -0.08523637 0 -0.256009 -0.09078896 0 -0.253142 -0.09383958 0 -0.2370784 -0.08799481 0 -0.2393343 -0.08754605 0 -0.256763 -0.09042155 0 -0.256381 -0.09059339 0 -0.263704 -0.08147168 0 -0.2701134 -0.08481931 0 -0.2585995 -0.08977288 0 -0.2530701 -0.08448946 0 -0.299457 -0.04530119 0 -0.291681 -0.04504889 0 -0.2918891 -0.04385393 0 -0.300193 -0.03823167 0 -0.292158 -0.04199999 0 -0.300202 -0.03719735 0 -0.292277 -0.06352651 0 -0.2855014 -0.06143373 0 -0.292786 -0.06267446 0 -0.298554 -0.04918795 0 -0.2909424 -0.04846644 0 -0.2988615 -0.04799431 0 -0.2836478 -0.0645557 0 -0.2906306 -0.06608647 0 -0.2826402 -0.06610816 0 -0.289425 -0.06791126 0 -0.288229 -0.06967461 0 -0.287607 -0.07052659 0 -0.2810841 -0.06831264 0 -0.279748 -0.07861346 0 -0.273922 -0.07589626 0 -0.280531 -0.0779674 0 -0.281886 -0.06721037 0 -0.288835 -0.06880277 0 -0.284962 -0.07373738 0 -0.277902 -0.07216757 0 -0.278513 -0.07149559 0 -0.2793875 -0.07046645 0 -0.286316 -0.0721715 0 -0.280254 -0.06939119 0 -0.282814 -0.07593816 0 -0.276634 -0.073466 0 -0.283546 -0.07522428 0 -0.285647 -0.07296431 0 -0.282066 -0.07663226 0 -0.275978 -0.0740956 0 -0.284262 -0.07449066 0 -0.277275 -0.07282328 0 -0.286969 -0.07135885 0 -0.274623 -0.07531547 0 -0.275307 -0.07471209 0 -0.281303 -0.07730668 0 -0.273203 -0.07644808 0 -0.2900232 -0.06696623 0 -0.278144 -0.07985407 0 -0.272469 -0.07698071 0 -0.278953 -0.0792424 0 -0.271719 -0.07749396 0 -0.277323 -0.0804485 0 -0.270172 -0.07846289 0 -0.2749723 -0.08202219 0 -0.269377 -0.0789178 0 -0.276488 -0.0810256 0 -0.270953 -0.07798808 0 -0.2904714 -0.05755132 0 -0.2876158 -0.05737519 0 -0.26858 -0.07934916 0 -0.27393 -0.08267515 0 -0.267771 -0.07976007 0 -0.273059 -0.08319801 0 -0.266119 -0.08052027 0 -0.272177 -0.0837059 0 -0.271286 -0.08419919 0 -0.266951 -0.08015048 0 -0.286996 -0.05862098 0 -0.291752 -0.06437277 0 -0.291212 -0.06521356 0 -0.2846474 -0.06292408 0 -0.290656 -0.05972379 0 -0.265276 -0.08086955 0 -0.2891109 -0.05412745 0 -0.296305 -0.05566459 0 -0.29592 -0.05656266 0 -0.296767 -0.05452346 0 -0.290656 -0.04956316 0 -0.297694 -0.05200827 0 -0.297369 -0.05293196 0 -0.297999 -0.05107647 0 -0.298286 -0.05013638 0 -0.291215 -0.04731488 0 -0.2914722 -0.04612749 0 -0.299256 -0.04628688 0 -0.299787 -0.04331165 0 -0.299634 -0.04430949 0 -0.292054 -0.0427652 0 -0.299916 -0.04230779 0 -0.300159 -0.03925979 0 -0.300102 -0.04028189 0 -0.300021 -0.04129785 0 -0.188 -0.04199999 0 -0.188 -0.03299999 0 -0.300149 -0.03511077 0 -0.300187 -0.03615719 0 -0.3 -0.03299999 0 -0.300086 -0.03405845 0 -0.2681039 -0.08583098 0 -0.262717 -0.08182895 0 -0.2633076 -0.08796012 0 -0.2575265 -0.08337801 0 -0.2652837 -0.08713018 0 -0.260118 -0.08265858 0 -0.26099 -0.08239799 0 -0.2561622 -0.08374279 0 -0.2614941 -0.08869123 0 -0.26007 -0.0892353 0 -0.2546232 -0.08412551 0 -0.257153 -0.09027367 0 -0.173367 -0.03104835 0 -0.185392 -0.03104835 0 -0.255293 -0.09125179 0 -0.254957 -0.09151577 0 -0.2457311 -0.08619076 0 -0.255647 -0.09100848 0 -0.289656 -0.05284279 0 -0.2902329 -0.05474346 0 -0.29552 -0.05745375 0 -0.295103 -0.05833786 0 -0.2883808 -0.05576014 0 -0.29467 -0.05921494 0 -0.2939188 -0.06065851 0 -0.293279 -0.06181699 0 -0.2863832 -0.05980634 0 -0.2900002 -0.05199956 0 -0.266718 -0.0864858 0 -0.261857 -0.08212149 0 -0.254636 -0.09180051 0 -0.254332 -0.0921055 0 -0.254051 -0.09242486 0 -0.2420297 -0.08699107 0 -0.253789 -0.09276145 0 -0.25355 -0.09311038 0 -0.253335 -0.09346896 0 -0.250747 -0.09879046 0 -0.2339877 -0.08858531 0 -0.2308372 -0.0891568 0 -0.256188 -0.09058856 -0.01516795 -0.2567253 -0.08996057 -0.0176658 -0.255228 -0.09130442 -0.01255822 -0.2543914 -0.09204661 -0.0125544 -0.2531413 -0.09384131 -0.005670607 -0.25369 -0.09289681 0 -0.2531385 -0.09383749 0 -0.2561627 -0.09070968 -0.01255792 -0.25715 -0.09027338 -0.01328039 -0.257146 -0.09025228 -0.01389545 -0.2531396 -0.09384465 -0.01140016 -0.2537363 -0.0928092 -0.01506638 -0.254451 -0.09190487 -0.01542168 -0.25527 -0.09117621 -0.01528936 -0.2547999 -0.09127891 -0.01822274 -0.2531868 -0.09374523 -0.01489746 -0.2531557 -0.09381115 -0.01306325 -0.2556753 -0.09055697 -0.01793909 -0.2539383 -0.09230107 -0.01857888 -0.253226 -0.09366589 -0.01570707 -0.253278 -0.09355878 -0.0164864 -0.253341 -0.09342908 -0.01726645 -0.253415 -0.09327667 -0.01804757 -0.253499 -0.09310156 -0.01882958 -0.257153 -0.0902118 -0.01450777 -0.257245 -0.0899738 -0.01632875 -0.257172 -0.09015178 -0.01511746 -0.257203 -0.09007245 -0.01572448 -0.257299 -0.08985567 -0.0169304 -0.2571647 -0.09027469 -0.01270103 -0.257364 -0.08971816 -0.01752924 -0.2543515 -0.09207659 0 -0.2551421 -0.0913558 0 -0.2561548 -0.09069579 0 -0.2571514 -0.0902692 0 -0.2539637 -0.09231048 -0.01857835 -0.2545143 -0.09149575 -0.018866 -0.255025 -0.09099292 -0.01861751 -0.2553133 -0.09056442 -0.01918333 -0.2546989 -0.09137237 -0.01825791 -0.2536011 -0.09252858 -0.01977217 -0.2543359 -0.09084087 -0.02055823 -0.2546013 -0.09105533 -0.01972228 -0.2534912 -0.0930972 -0.0188294 -0.253354 -0.09245377 -0.02034926 -0.25344 -0.09244698 -0.02021408 -0.2536023 -0.09200763 -0.02034401 -0.2535661 -0.09295064 -0.01902079 -0.2539504 -0.09139513 -0.02042526 -0.2536109 -0.09143561 -0.02084064 -0.2541056 -0.09160256 -0.0198751 -0.2535264 -0.09103184 -0.02131646 -0.2538309 -0.09050452 -0.0215581 -0.2528686 -0.09113132 -0.02181273 -0.2530789 -0.09000653 -0.02282172 -0.2529771 -0.09177774 -0.02123028 -0.2521098 -0.09112209 -0.02237427 -0.2512969 -0.09052354 -0.02345043 -0.2513911 -0.09009587 -0.02390986 -0.251317 -0.0938577 -0.02149748 -0.2521182 -0.09175574 -0.02191424 -0.2507886 -0.09175086 -0.02266997 -0.2511101 -0.09223538 -0.0222063 -0.2497494 -0.09216123 -0.02285695 -0.2503905 -0.09264808 -0.02231943 -0.2506487 -0.09334075 -0.02193111 -0.250432 -0.09470009 -0.02168291 -0.2494053 -0.09278047 -0.02262145 -0.2493847 -0.09364509 -0.02224504 -0.2486214 -0.09324336 -0.02262097 -0.2479179 -0.0973618 -0.02181947 -0.2467425 -0.09654963 -0.02181583 -0.247177 -0.09387481 -0.02263188 -0.2470078 -0.09339439 -0.02292734 -0.242437 -0.09463679 -0.02263909 -0.2425009 -0.09395545 -0.02326482 -0.2412958 -0.09394395 -0.02350151 -0.2440739 -0.09378492 -0.02317488 -0.2443475 -0.09427928 -0.02276515 -0.245404 -0.09433478 -0.02262693 -0.2456513 -0.09487408 -0.02233052 -0.2428691 -0.09324628 -0.02396923 -0.2458088 -0.09292942 -0.02353352 -0.2442541 -0.09313458 -0.02373176 -0.246001 -0.09337723 -0.02314496 -0.2458543 -0.09242141 -0.02398389 -0.2484557 -0.09260702 -0.02303433 -0.2481808 -0.09408783 -0.02234852 -0.2481893 -0.09641087 -0.02184915 -0.2485168 -0.09670013 -0.02182549 -0.249529 -0.09561794 -0.02178412 -0.2467707 -0.0970723 -0.02175533 -0.2400488 -0.09398853 -0.02376174 -0.2396343 -0.09470343 -0.02280282 -0.240869 -0.094751 -0.02262657 -0.2383444 -0.09473621 -0.02298963 -0.2381945 -0.09536761 -0.02198666 -0.2394638 -0.09543621 -0.02189129 -0.2370133 -0.09487903 -0.02316939 -0.236638 -0.09549075 -0.02191591 -0.2359037 -0.09503877 -0.02340745 -0.2352401 -0.09567052 -0.02184957 -0.2350401 -0.09543293 -0.02278828 -0.2376068 -0.0958333 -0.02126443 -0.233638 -0.09609925 -0.02135878 -0.2345573 -0.09600681 -0.02111542 -0.2341 -0.09587419 -0.02191495 -0.234349 -0.09575557 -0.02217429 -0.233425 -0.09620577 -0.02106189 -0.2338629 -0.09598881 -0.02164316 -0.2360393 -0.0958482 -0.02118623 -0.234609 -0.09563279 -0.022421 -0.2491018 -0.09606927 -0.02180784 -0.2511262 -0.09291177 -0.02188163 -0.2499785 -0.09515535 -0.02174073 -0.2517386 -0.09258812 -0.02169573 -0.2504323 -0.09401386 -0.02181208 -0.2523098 -0.09225004 -0.02149158 -0.2523513 -0.09047949 -0.02280628 -0.2544662 -0.0898385 -0.02181011 -0.2547821 -0.09106814 -0.01923251 -0.2555971 -0.09051865 -0.01849025 -0.2557157 -0.09052985 -0.01792752 -0.2562274 -0.09009987 -0.0183863 -0.2567081 -0.08997035 -0.01767033 -0.2568958 -0.08975559 -0.01828604 -0.257397 -0.0896278 -0.01789909 -0.257364 -0.08971816 -0.01752924 -0.2536216 -0.09277063 -0.01928389 -0.253984 -0.09208101 -0.01933062 -0.257405 -0.08954095 -0.01826798 -0.253634 -0.09265935 -0.01948106 -0.2558408 -0.090043 -0.01950687 -0.256453 -0.08964985 -0.01953369 -0.2572813 -0.08929812 -0.0193721 -0.257389 -0.08945798 -0.0186364 -0.253627 -0.09258979 -0.01962566 -0.2551622 -0.09040182 -0.01992505 -0.257347 -0.08937716 -0.01900738 -0.2528699 -0.09265244 -0.02082657 -0.2531019 -0.092534 -0.02063703 -0.2531435 -0.09212851 -0.02083551 -0.257194 -0.0892322 -0.0197339 -0.253568 -0.09248638 -0.01992315 -0.255612 -0.08963882 -0.0208199 -0.2567853 -0.08905786 -0.02078026 -0.257079 -0.08916699 -0.02009189 -0.253512 -0.09245789 -0.02007108 -0.2549765 -0.09019422 -0.02061533 -0.2560854 -0.08924007 -0.02113389 -0.256944 -0.08910876 -0.02044057 -0.256604 -0.08901315 -0.0211125 -0.253256 -0.0924772 -0.02047467 -0.2526819 -0.09276676 -0.02094942 -0.2525137 -0.09288132 -0.02105015 -0.2543699 -0.09028184 -0.02126061 -0.2548986 -0.08938437 -0.02213543 -0.256405 -0.08897656 -0.02143245 -0.256187 -0.08894765 -0.02174127 -0.255951 -0.08892655 -0.02203845 -0.2519894 -0.09297293 -0.0213977 -0.2522749 -0.09305518 -0.02116882 -0.2551544 -0.08890849 -0.02285337 -0.255701 -0.08891338 -0.02232289 -0.255437 -0.08890825 -0.02259415 -0.2520282 -0.0932483 -0.02127325 -0.2509531 -0.09419518 -0.02158504 -0.2531121 -0.0905314 -0.02217727 -0.25487 -0.0889216 -0.02309828 -0.253327 -0.0895515 -0.02326732 -0.254571 -0.0889396 -0.02333098 -0.2516894 -0.09353005 -0.02139419 -0.2532934 -0.08907669 -0.02413737 -0.2537974 -0.08901369 -0.02385491 -0.254263 -0.08896499 -0.0235511 -0.2528113 -0.08915704 -0.0243889 -0.2511655 -0.09117066 -0.02290242 -0.2513547 -0.08974051 -0.02444988 -0.252103 -0.08928602 -0.0247032 -0.2514244 -0.08942842 -0.02496069 -0.2501178 -0.09126889 -0.02336782 -0.2494536 -0.09052276 -0.02452832 -0.250888 -0.08955097 -0.02513599 -0.249428 -0.09099978 -0.02397853 -0.2503668 -0.0896784 -0.0252875 -0.2478374 -0.0906201 -0.0253728 -0.249822 -0.08981978 -0.02542436 -0.2493261 -0.09436202 -0.02203088 -0.2488037 -0.09175366 -0.02353537 -0.2492919 -0.08996391 -0.02554023 -0.2474319 -0.09138554 -0.0244984 -0.248746 -0.09011995 -0.02564078 -0.2486573 -0.09491842 -0.02202093 -0.2477146 -0.09250855 -0.02333503 -0.2475091 -0.09172952 -0.02408498 -0.2465896 -0.09134954 -0.02496355 -0.2482039 -0.09028095 -0.02572494 -0.2473803 -0.09220385 -0.02368414 -0.247667 -0.09044647 -0.02579128 -0.2479887 -0.09550046 -0.02197521 -0.2449777 -0.09235024 -0.0243721 -0.2471316 -0.09061688 -0.0258435 -0.2471876 -0.09516417 -0.02212452 -0.2469863 -0.09463495 -0.02232372 -0.246588 -0.09079509 -0.02588027 -0.2473306 -0.09609657 -0.02189725 -0.2458629 -0.09104007 -0.02590954 -0.243586 -0.0921415 -0.02529966 -0.2454773 -0.09577929 -0.02196985 -0.2447822 -0.09142065 -0.02590262 -0.2438229 -0.09241157 -0.02473777 -0.2456143 -0.09680962 -0.02169287 -0.2459905 -0.09615099 -0.02187007 -0.2438926 -0.09174609 -0.02585387 -0.244253 -0.09505081 -0.02228593 -0.2432021 -0.09200519 -0.02579081 -0.244417 -0.09657114 -0.0216248 -0.2418802 -0.09320765 -0.0243436 -0.2425038 -0.09227317 -0.02570372 -0.2443139 -0.09580934 -0.02191144 -0.2431778 -0.09495121 -0.02236562 -0.243301 -0.09563601 -0.02194434 -0.2418044 -0.09254717 -0.02559202 -0.2434428 -0.09640061 -0.02157139 -0.2398853 -0.09363883 -0.02446711 -0.2409415 -0.09289085 -0.02542078 -0.2422732 -0.09622305 -0.02150863 -0.2420543 -0.0956043 -0.02189278 -0.240945 -0.09543031 -0.02196425 -0.2400718 -0.09324544 -0.02520388 -0.2393973 -0.09352552 -0.02500563 -0.2410085 -0.09606379 -0.02143931 -0.2387492 -0.09379822 -0.02478754 -0.2400927 -0.09597063 -0.02139163 -0.238241 -0.0940144 -0.02459418 -0.2377607 -0.09422022 -0.02439463 -0.2391946 -0.09589636 -0.02134454 -0.237272 -0.094433 -0.0241695 -0.2368093 -0.0946353 -0.02393651 -0.2363359 -0.09484577 -0.02367198 -0.2354429 -0.09524786 -0.02309286 -0.2341467 -0.09607028 -0.02109587 -0.233425 -0.09620577 -0.02106189 -0.1613405 -0.1117455 -0.01751452 -0.0991382 -0.1153116 -0.01424813 -0.1408625 -0.1153446 -0.01637959 -0.1237025 -0.1138958 -0.01553899 -0.1167779 -0.1167975 -0.01504987 -0.2153055 -0.1179397 -0.02049553 -0.2079503 -0.1156686 -0.02004885 -0.1838874 -0.1179878 -0.01871502 -0.1640443 -0.115626 -0.01762014 -0.1857934 -0.1129235 -0.01880598 -0.1861224 -0.1078004 -0.01880687 -0.2479169 -0.09736335 -0.02181965 -0.2472106 -0.09717994 -0.02177923 -0.1970481 -0.1037175 -0.01933944 -0.213492 -0.1080406 -0.02023762 -0.2268967 -0.09893858 -0.02078419 -0.239301 -0.0959047 -0.02135026 -0.244799 -0.09664338 -0.02164405 -0.246001 -0.09689295 -0.02171093 -0.2419342 -0.0961771 -0.02148866 -0.240989 -0.09606182 -0.02143841 -0.2429137 -0.09631597 -0.02154123 -0.2385648 -0.09586429 -0.02131247 -0.2375795 -0.09583473 -0.02126246 -0.2400224 -0.09596407 -0.02138775 -0.235842 -0.09586685 -0.02117609 -0.2363894 -0.09583288 -0.02120268 -0.2351136 -0.09593486 -0.02114164 -0.2438755 -0.09647309 -0.02159333 -0.2034118 -0.1010648 -0.01961863 -0.208434 -0.100316 -0.01985305 -0.132953 -0.1106776 -0.01610332 -0.09446829 -0.1123383 -0.01421958 -0.1205276 -0.1099961 -0.0155372 -0.112818 -0.1102 -0.01520937 -0.107757 -0.110469 -0.01496279 -0.102693 -0.110712 -0.01471585 -0.09255707 -0.111124 -0.01422154 -0.0976265 -0.110931 -0.01446884 -0.117876 -0.109906 -0.01545578 -0.122931 -0.109587 -0.01570188 -0.1037065 -0.1182222 -0.01427322 -0.127984 -0.109243 -0.01594787 -0.1382063 -0.1084651 -0.01643526 -0.133033 -0.108874 -0.01619356 -0.1632456 -0.1062752 -0.01765966 -0.1518632 -0.109053 -0.01706898 -0.143124 -0.10806 -0.01668435 -0.1475069 -0.1180744 -0.01667422 -0.1482209 -0.1076087 -0.01692527 -0.153203 -0.107145 -0.0171743 -0.173327 -0.105014 -0.01815146 -0.1683 -0.105584 -0.0179075 -0.1582379 -0.1066499 -0.01741886 -0.1632699 -0.10613 -0.01766335 -0.18839 -0.103151 -0.01888209 -0.183372 -0.103797 -0.01863878 -0.178351 -0.104418 -0.0183953 -0.223437 -0.0979253 -0.02057898 -0.218439 -0.09874737 -0.02033728 -0.198418 -0.101784 -0.01936799 -0.193405 -0.1024799 -0.01912516 -0.213438 -0.09954416 -0.02009528 -0.2150967 -0.1123712 -0.0203911 -0.228433 -0.09707808 -0.02082055 -0.2455766 -0.1021897 -0.02181565 -0.242276 -0.1089958 -0.02180737 -0.2379477 -0.1179194 -0.02179211 -0.08763843 -0.1112661 -0.01162141 -0.08760118 -0.111267 -0.01141798 -0.09537708 -0.116186 -0.01124799 -0.1037091 -0.1182239 -0.01427185 -0.0915448 -0.1111553 -0.01412451 -0.09255552 -0.1111235 -0.01422548 -0.09732776 -0.1141582 -0.01423871 -0.09088844 -0.1111741 -0.01399332 -0.103365 -0.1187694 -0.01413995 -0.1030324 -0.1192994 -0.0138536 -0.09032034 -0.1111911 -0.01383656 -0.08966511 -0.111209 -0.01359266 -0.1027757 -0.1197085 -0.01349192 -0.08913791 -0.1112248 -0.01332747 -0.1025915 -0.1200046 -0.01311165 -0.08878773 -0.1112341 -0.01310747 -0.08846437 -0.1112427 -0.01285958 -0.1024449 -0.1202399 -0.01267844 -0.08817952 -0.1112511 -0.01258593 -0.1023413 -0.1204088 -0.01221054 -0.0879203 -0.1112574 -0.01225715 -0.08769696 -0.111264 -0.01181447 -0.08777809 -0.111262 -0.01200395 -0.1022558 -0.1205527 -0.01128387 -0.08758926 -0.111267 -0.01121735 -0.102266 -0.120536 0 -0.1022657 -0.1205363 -0.01128023 -0.0875898 -0.1112669 0 -0.08758926 -0.111267 -0.01121735 0.06794679 -0.109098 0 0.05374825 -0.09996956 0 0.04429882 -0.09986239 0 0.08520185 -0.108376 0 0.08860456 -0.10851 0 0.05068629 -0.1097249 0 0.03466588 -0.0997281 0 0.04205405 -0.110002 0 0.07657498 -0.108749 0 0.007511854 -0.110869 0 0.0161494 -0.110688 0 0.01285576 -0.09933006 0 0.02478569 -0.110483 0 0.03342056 -0.110255 0 0.02254539 -0.09952461 0 -0.0270518 -0.111351 0 -0.01379948 -0.09847158 0 -0.009767234 -0.111158 0 0.008191287 -0.09921342 0 -0.03295844 -0.09785699 0 -0.0616368 -0.111447 0 -0.04434156 -0.111447 0 -0.08758968 -0.111267 0 -0.04730701 -0.09741741 0 -0.05939066 -0.09705924 0 -0.07893741 -0.111351 0 -0.08146303 -0.09652286 0 -0.06434482 -0.09693044 0 -0.202226 -0.09699088 0 -0.1030418 -0.09597361 0 -0.1369915 -0.09502613 0 -0.1225 -0.09544217 0 -0.1705246 -0.09399414 0 -0.1849542 -0.09352004 0 -0.1537209 -0.09452402 0 -0.103308 -0.120947 0 -0.103868 -0.121 0 -0.103586 -0.1209869 0 -0.172977 -0.117192 0 -0.102266 -0.120536 0 -0.16793 -0.115586 0 -0.103034 -0.120882 0 -0.102767 -0.120791 0 -0.102511 -0.120676 0 -0.172086 -0.120351 0 -0.171961 -0.121 0 -0.238947 -0.120883 0 -0.2386749 -0.120948 0 -0.238119 -0.121 0 -0.172228 -0.119708 0 -0.172388 -0.1190699 0 -0.204058 -0.10403 0 -0.244213 -0.112293 0 -0.20473 -0.104346 0 -0.172567 -0.118439 0 -0.172763 -0.117812 0 -0.173209 -0.116576 0 -0.173727 -0.115363 0 -0.1734589 -0.115967 0 -0.207319 -0.10583 0 -0.206687 -0.105426 0 -0.1736545 -0.1150831 0 -0.1734679 -0.114643 0 -0.173553 -0.1148149 0 -0.173117 -0.114189 0 -0.171494 -0.11377 0 -0.172968 -0.114069 0 -0.173368 -0.114479 0 -0.173251 -0.114327 0 -0.17226 -0.113786 0 -0.172069 -0.113762 0 -0.17263 -0.113888 0 -0.1728039 -0.113968 0 -0.171787 -0.1137502 0 -0.172448 -0.113827 0 -0.1674759 -0.114695 0 -0.2040638 -0.09286564 0 -0.2012709 -0.102986 0 -0.199034 -0.101765 0 -0.201983 -0.103214 0 -0.1989834 -0.09993058 0 -0.2026799 -0.09788185 0 -0.199116 -0.0996977 0 -0.198831 -0.1002879 0 -0.1987439 -0.101095 0 -0.198729 -0.100911 0 -0.1987349 -0.100727 0 -0.198763 -0.100545 0 -0.200294 -0.1026722 0 -0.1999449 -0.1025001 0 -0.1996356 -0.1023147 0 -0.20055 -0.10278 0 -0.1993398 -0.102091 0 -0.199153 -0.101907 0 -0.1988469 -0.1014479 0 -0.1989319 -0.101613 0 -0.1987839 -0.101275 0 -0.2026849 -0.103464 0 -0.2033759 -0.103736 0 -0.205392 -0.104684 0 -0.206044 -0.105044 0 -0.20853 -0.106691 0 -0.209116 -0.107151 0 -0.207931 -0.10625 0 -0.2151499 -0.11465 0 -0.215474 -0.11532 0 -0.2132109 -0.1114709 0 -0.212764 -0.110877 0 -0.240819 -0.119307 0 -0.215776 -0.116 0 -0.216058 -0.116693 0 -0.214806 -0.113993 0 -0.216552 -0.118101 0 -0.216318 -0.117397 0 -0.2144359 -0.11334 0 -0.216763 -0.118814 0 -0.216951 -0.119535 0 -0.24053 -0.119786 0 -0.240685 -0.119553 0 -0.240353 -0.120003 0 -0.217117 -0.120263 0 -0.239942 -0.120382 0 -0.2401559 -0.120202 0 -0.2397119 -0.120542 0 -0.239468 -0.120679 0 -0.239213 -0.1207939 0 -0.21726 -0.121 0 -0.238399 -0.1209869 0 -0.214046 -0.112702 0 -0.213638 -0.112079 0 -0.2118059 -0.109726 0 -0.212294 -0.110293 0 -0.2113029 -0.109177 0 -0.210783 -0.108646 0 -0.210247 -0.108132 0 -0.209688 -0.107632 0 -0.07028645 -0.111411 0 -0.05298858 -0.111459 0 -0.03569597 -0.111411 0 -0.01840889 -0.111266 0 0.05931717 -0.109423 0 -0.001127004 -0.111025 0 0.06284737 -0.1000499 0 0.07237184 -0.1001098 0 0.0806148 -0.1001825 0 0.08041918 -0.10014 0 0.08085918 -0.1002668 0 0.08121526 -0.1004624 0 0.081043 -0.1003569 0 0.08145141 -0.1006502 0 0.09490704 -0.1087591 -0.007193565 0.09436857 -0.108738 -0.006992399 0.08520179 -0.1083757 -0.01082938 0.08520174 -0.1083774 -0.02799999 0.150575 -0.110957 -0.02799999 0.08861947 -0.108511 -3.87913e-4 0.08860456 -0.10851 0 0.08520185 -0.108376 0 0.08921468 -0.108534 -0.002600848 0.08938997 -0.108541 -0.002941548 0.08865857 -0.108512 -7.70517e-4 0.1028785 -0.1090736 -0.007696986 0.103439 -0.109096 -0.00757116 0.08880937 -0.108518 -0.001519799 0.08872187 -0.108515 -0.001147806 0.0890572 -0.108528 -0.00224781 0.08892118 -0.108523 -0.001886427 0.08958595 -0.1085489 -0.003273069 0.09002959 -0.108566 -0.00390315 0.08980178 -0.108557 -0.003594875 0.09053426 -0.108586 -0.004485845 0.09027367 -0.1085759 -0.00420016 0.09108626 -0.108608 -0.005020141 0.09080457 -0.108597 -0.004759073 0.09152066 -0.1086256 -0.005383312 0.09563595 -0.108788 -0.007424652 0.0921455 -0.1086498 -0.005836963 0.09282344 -0.108677 -0.006254673 0.09385246 -0.1087175 -0.006775438 0.09331655 -0.108696 -0.006518661 0.09639543 -0.1088178 -0.007619738 0.09695255 -0.10884 -0.007734715 0.09752839 -0.1088628 -0.007832705 0.09809327 -0.108885 -0.007905006 0.09866976 -0.1089075 -0.007959127 0.09943461 -0.1089377 -0.007996499 0.1002059 -0.108969 -0.00799638 0.1009787 -0.1089987 -0.007958412 0.1017354 -0.1090283 -0.00788325 0.102309 -0.109051 -0.007799923 0.1039874 -0.1091172 -0.007427692 0.1047366 -0.1091471 -0.007191002 0.1054439 -0.1091748 -0.006921768 0.1059769 -0.109196 -0.006686449 0.1064926 -0.1092165 -0.006430923 0.1074792 -0.1092557 -0.005845665 0.106997 -0.109236 -0.006147623 0.150575 -0.110957 0 0.108259 -0.109286 -0.005269885 0.107955 -0.109274 -0.005506753 0.108834 -0.109309 -0.004759967 0.108551 -0.109298 -0.005020856 0.109363 -0.1093299 -0.004202246 0.109106 -0.10932 -0.004487156 0.10984 -0.109349 -0.003596544 0.109608 -0.1093389 -0.003905355 0.110247 -0.109365 -0.002946019 0.110052 -0.1093569 -0.003276884 0.110583 -0.109378 -0.002252638 0.110426 -0.109372 -0.002603828 0.110831 -0.109388 -0.001524806 0.1107169 -0.109383 -0.001893341 0.110984 -0.109394 -7.71391e-4 0.110921 -0.109391 -0.001148998 0.111023 -0.109395 -3.88388e-4 0.111037 -0.109396 0 0.09820187 -0.0965535 -0.02799999 0.08520168 -0.108376 -0.02799999 0.08520162 -0.108376 -0.04125016 0.08883172 -0.1050745 -0.04958635 0.08921205 -0.1047289 -0.04986077 0.09002161 -0.1039929 -0.05036896 0.08806073 -0.1057756 -0.04893767 0.08843475 -0.105436 -0.04926747 0.08702039 -0.1067219 -0.04779976 0.08723998 -0.106522 -0.04807198 0.08758521 -0.106208 -0.04846453 0.08520567 -0.1083724 -0.04241746 0.08641415 -0.107273 -0.04691386 0.08680987 -0.106913 -0.04751604 0.08660686 -0.107098 -0.04722076 0.08523613 -0.1083433 -0.04318839 0.08590346 -0.107738 -0.04592406 0.08606117 -0.107594 -0.04626518 0.08541876 -0.108178 -0.04445689 0.08533948 -0.108251 -0.04406797 0.08562886 -0.107987 -0.04520887 0.08575975 -0.107868 -0.0455724 0.08527851 -0.108306 -0.04367548 0.08551537 -0.1080909 -0.04483765 0.08623296 -0.107438 -0.04659569 0.08962297 -0.1043552 -0.05013233 0.09043985 -0.1036121 -0.05059647 0.09099441 -0.1031078 -0.05086219 0.09142255 -0.102719 -0.05104285 0.09186321 -0.1023176 -0.05121052 0.09272754 -0.101532 -0.05148291 0.09228539 -0.101934 -0.05135148 0.09330272 -0.101009 -0.05162686 0.09374749 -0.1006039 -0.05171817 0.09419149 -0.1002006 -0.05179476 0.09492313 -0.09953516 -0.0518881 0.09566807 -0.0988577 -0.05193942 0.09623551 -0.09834164 -0.05195248 0.09688067 -0.09775501 -0.05194216 0.09820187 -0.09655344 -0.05189359 0.2351509 -0.100293 0 0.220156 -0.09988385 0 0.220144 -0.09988355 -3.86413e-4 0.09820187 -0.0965535 -0.02799999 0.103218 -0.09669047 -0.0517652 0.108232 -0.09682738 -0.05161166 0.220107 -0.0998826 -7.68555e-4 0.220046 -0.09988087 -0.001146376 0.219961 -0.0998786 -0.001519978 0.219851 -0.09987556 -0.001889348 0.219718 -0.09987199 -0.002250611 0.219563 -0.0998677 -0.002601385 0.219385 -0.09986287 -0.002943754 0.219186 -0.09985738 -0.003271937 0.218966 -0.09985136 -0.003586947 0.218726 -0.09984487 -0.003889143 0.218468 -0.09983777 -0.004172682 0.218192 -0.09983026 -0.004440426 0.217899 -0.09982228 -0.004690468 0.217592 -0.09981387 -0.004919767 0.217269 -0.09980505 -0.005130171 0.216934 -0.09979587 -0.005318999 0.227837 -0.100094 -0.04039996 0.2351509 -0.100293 -0.04039996 0.216588 -0.09978646 -0.005485475 0.118252 -0.09710097 -0.05122935 0.123258 -0.09723776 -0.05100059 0.188123 -0.09900909 -0.04574304 0.193095 -0.09914487 -0.04516297 0.13963 -0.0976848 -0.02799999 0.113243 -0.09696418 -0.05143308 0.133264 -0.09751099 -0.05046778 0.138263 -0.09764748 -0.05016368 0.163223 -0.09832906 -0.04826706 0.168208 -0.09846526 -0.04781246 0.148254 -0.09792035 -0.04948025 0.153246 -0.09805667 -0.04910099 0.212454 -0.09967356 -0.005752384 0.212825 -0.0996837 -0.005849778 0.2132019 -0.09969395 -0.005923092 0.183148 -0.09887325 -0.04629808 0.212087 -0.09966355 -0.005630791 0.211732 -0.09965389 -0.005487084 0.211386 -0.09964436 -0.005320191 0.21105 -0.0996353 -0.005131125 0.13963 -0.0976848 0 0.210729 -0.09962648 -0.004922032 0.21042 -0.09961795 -0.0046916 0.2101269 -0.09961009 -0.004442393 0.209852 -0.09960246 -0.004175424 0.209592 -0.09959536 -0.00388962 0.209353 -0.09958887 -0.003589808 0.209133 -0.09958291 -0.003274679 0.2089329 -0.09957736 -0.002944588 0.208756 -0.09957259 -0.002604901 0.2086 -0.0995683 -0.002252936 0.208467 -0.09956467 -0.001891434 0.208358 -0.09956169 -0.001523792 0.208272 -0.09955936 -0.001147806 0.2082099 -0.09955769 -7.68555e-4 0.208173 -0.09955668 -3.86413e-4 0.2081609 -0.09955638 0 0.09820187 -0.0965535 -0.05189359 0.128262 -0.09737437 -0.05074679 0.14326 -0.09778398 -0.04983454 0.158236 -0.09819298 -0.04869657 0.1731899 -0.09860128 -0.04733276 0.17817 -0.09873729 -0.04682797 0.1980659 -0.09928065 -0.04455786 0.203034 -0.09941625 -0.04392755 0.207999 -0.09955185 -0.04327225 0.217923 -0.09982287 -0.04188627 0.212962 -0.09968745 -0.04259186 0.222881 -0.09995836 -0.04115569 0.213585 -0.0997045 -0.005972266 0.213967 -0.09971487 -0.005996882 0.214352 -0.09972536 -0.005996704 0.214736 -0.09973585 -0.005971968 0.215116 -0.09974628 -0.005922973 0.215867 -0.09976679 -0.00575143 0.215495 -0.09975659 -0.005848944 0.21623 -0.09977668 -0.005630671 0.2351509 -0.100293 -0.04039996 0.227837 -0.100094 -0.04039996 0.2326599 -0.09964966 -0.04039984 0.23726 -0.0992124 -0.04039996 0.2351509 -0.100293 -0.04039996 0.235925 -0.0998966 -0.03952729 0.235526 -0.100101 -0.03922218 0.236347 -0.09968036 -0.03982526 0.236792 -0.09945237 -0.04011619 0.23726 -0.0992124 -0.04039996 0.2351509 -0.100293 -0.03890997 0.2357608 -0.1015039 -0.03258472 0.235733 -0.101458 -0.03448557 0.235747 -0.101486 -0.03397119 0.2351509 -0.100293 -0.03890997 0.235709 -0.101409 -0.03499668 0.235754 -0.1015 -0.03190445 0.2357469 -0.101486 -0.03138697 0.235674 -0.1013399 -0.03550779 0.235574 -0.10114 -0.03651648 0.235629 -0.10125 -0.03601574 0.235509 -0.101011 -0.03700989 0.235435 -0.100861 -0.03749597 0.23535 -0.100692 -0.03797459 0.235255 -0.100502 -0.03844594 0.2351509 -0.100293 0 0.2357469 -0.101486 -0.01010894 0.235752 -0.101496 -0.009304463 0.235767 -0.101526 -0.008503437 0.235792 -0.101577 -0.007705867 0.235828 -0.101649 -0.006911695 0.235875 -0.101741 -0.006120979 0.2359319 -0.101855 -0.005333721 0.235999 -0.101989 -0.00454986 0.2360759 -0.102145 -0.003769457 0.236165 -0.102321 -0.002995848 0.236264 -0.102519 -0.002235233 0.236373 -0.102739 -0.001482427 0.236494 -0.102979 -7.37339e-4 0.236625 -0.103241 0 0.299952 -0.09801548 -0.02758949 0.312288 -0.09766459 -0.02464479 0.297891 -0.09812998 -0.0273292 0.262304 -0.1090199 0 0.281864 -0.112756 -0.001756608 0.2766725 -0.1120577 -0.00113976 0.271557 -0.111366 -4.74655e-4 0.266193 -0.110251 0 0.2974582 -0.1148306 -0.003287434 0.289139 -0.111005 -0.003995299 0.260353 -0.108439 0 0.263636 -0.108407 -9.08739e-4 0.262996 -0.106581 -0.002660691 0.2515691 -0.1061144 -1.42086e-6 0.3111838 -0.1166279 -0.004228591 0.3042168 -0.1157188 -0.00379759 0.292214 -0.114136 -0.002825736 0.31459 -0.110435 -0.006831228 0.288162 -0.105943 -0.007890045 0.314225 -0.107259 -0.008849561 0.2867346 -0.1134066 -0.002288162 0.26425 -0.109624 0 0.268131 -0.1109009 0 0.288678 -0.108371 -0.005758523 0.31492 -0.11378 -0.005351305 0.3183894 -0.1175631 -0.004575431 0.3269236 -0.1186594 -0.004856348 0.2555446 -0.1071063 -1.71236e-6 0.3408613 -0.11703 -0.005219578 0.3410401 -0.1196708 -0.005006313 0.3347577 -0.1196587 -0.004981338 0.341093 -0.12046 -0.004999995 0.3407306 -0.115095 -0.005567014 0.262302 -0.104937 -0.004616677 0.2435875 -0.1044105 4.34362e-7 0.340612 -0.113332 -0.006041109 0.2476057 -0.10522 -6.72076e-7 0.3405113 -0.1118497 -0.006526768 0.2396926 -0.1037213 -8.27383e-7 0.3403312 -0.1091848 -0.007679045 0.313834 -0.10438 -0.01137244 0.236625 -0.103241 0 0.261565 -0.103511 -0.006749987 0.3402066 -0.1073479 -0.00871402 0.340099 -0.105753 -0.009808123 0.236373 -0.102739 -0.001482427 0.236494 -0.102979 -7.37339e-4 0.313431 -0.101912 -0.01432716 0.3399945 -0.1042026 -0.0110206 0.287011 -0.101992 -0.01308959 0.31303 -0.09994268 -0.0176087 0.3398967 -0.1027639 -0.0123744 0.260797 -0.10233 -0.009026885 0.2362102 -0.102411 -0.002626538 0.2360759 -0.102145 -0.003769457 0.3397732 -0.1009319 -0.01442676 0.339696 -0.09978729 -0.01601117 0.26001 -0.101415 -0.01140844 0.235875 -0.101741 -0.006120979 0.259219 -0.100776 -0.01385265 0.2359634 -0.1019175 -0.004936456 0.312645 -0.09852325 -0.0210914 0.275364 -0.09936839 -0.02336126 0.2774 -0.0992574 -0.02380579 0.285215 -0.09902226 -0.02218449 0.265213 -0.09991919 -0.02088767 0.267239 -0.09980958 -0.02141588 0.3395187 -0.09715718 -0.02109235 0.3395677 -0.0978899 -0.01934808 0.27944 -0.099146 -0.02423346 0.289668 -0.09858459 -0.0261209 0.29172 -0.0984714 -0.02644807 0.293775 -0.09835785 -0.02675855 0.302016 -0.0979008 -0.02783286 0.30615 -0.09767049 -0.02826958 0.310906 -0.0973984 -0.02816408 0.304082 -0.09778577 -0.0280596 0.315661 -0.09712296 -0.02803349 0.3394474 -0.09610944 -0.02455669 0.3394747 -0.09651821 -0.02295279 0.325168 -0.09656226 -0.02769678 0.320415 -0.09684425 -0.02787768 0.3394194 -0.09568512 -0.02700203 0.329919 -0.09627705 -0.02749079 0.33467 -0.09598851 -0.02725976 0.295832 -0.09824407 -0.02705228 0.287618 -0.09869748 -0.02577686 0.28557 -0.09881007 -0.02541619 0.283524 -0.09892231 -0.02503865 0.281481 -0.0990343 -0.02464449 0.273329 -0.09947919 -0.0229001 0.271297 -0.09958958 -0.02242207 0.3396261 -0.09875166 -0.01766908 0.269267 -0.09969979 -0.02192735 0.2358065 -0.1016119 -0.007324874 0.2357569 -0.1015042 -0.008902549 0.258437 -0.100415 -0.01631665 0.26319 -0.100028 -0.02034264 0.261169 -0.100137 -0.01978099 0.25915 -0.100246 -0.01920247 0.247318 -0.100877 -0.01507484 0.2453719 -0.10098 -0.01430457 0.249271 -0.100774 -0.01582217 0.251231 -0.100669 -0.01654648 0.253198 -0.100565 -0.01724785 0.2434329 -0.101083 -0.01351135 0.235747 -0.101486 -0.01010894 0.237658 -0.101386 -0.01099395 0.241501 -0.101184 -0.01269519 0.239576 -0.101286 -0.01185607 0.255172 -0.100459 -0.01792627 0.257153 -0.100353 -0.01858168 0.285802 -0.09959036 -0.01908797 0.286406 -0.100582 -0.01602858 0.287602 -0.103795 -0.01035267 0.258398 -0.1078799 0 0.3394464 -0.0960949 -0.02457606 0.348018 -0.09596508 -0.02287727 0.3397422 -0.100474 -0.01504039 0.348256 -0.09938627 -0.01574027 0.3398252 -0.101697 -0.01351886 0.348439 -0.102001 -0.0125615 0.3400362 -0.1048158 -0.01051032 0.3785186 -0.100467 -0.01190072 0.3782708 -0.09786474 -0.01481425 0.348656 -0.105123 -0.009839296 0.3501005 -0.1123606 -0.006146013 0.340509 -0.1118157 -0.006538212 0.3489 -0.108627 -0.007685065 0.3403476 -0.1094289 -0.007560193 0.3613749 -0.1013642 -0.01227569 0.3611589 -0.09875375 -0.01533997 0.3616626 -0.104453 -0.009656071 0.3620301 -0.1078953 -0.007584631 0.4295939 -0.09484839 -0.0133025 0.4298524 -0.09740102 -0.01082485 0.4127271 -0.09848767 -0.01117527 0.4130212 -0.1014344 -0.008951842 0.3959144 -0.1025067 -0.00918132 0.378844 -0.1035098 -0.009415388 0.3396678 -0.09937584 -0.01663041 0.3791242 -0.1068844 -0.00745356 0.4124825 -0.09591227 -0.01379585 0.3956118 -0.09951007 -0.01153373 0.4505837 -0.08959037 -0.01793456 0.442194 -0.09186148 -0.01559919 0.3953693 -0.0969181 -0.01429986 0.4122747 -0.09377974 -0.01671779 0.4292201 -0.09100043 -0.01904529 0.412114 -0.09212827 -0.01983231 0.4289336 -0.08976763 -0.02211928 0.4293845 -0.09270155 -0.01607531 0.348115 -0.09736377 -0.01923125 0.441914 -0.08882588 -0.02142816 0.442033 -0.0901274 -0.01846015 0.4504494 -0.08817392 -0.02096688 0.3395772 -0.09802597 -0.01904195 0.3395 -0.09688669 -0.02180534 0.3394197 -0.09568953 -0.02700263 0.347963 -0.09517288 -0.02652865 0.3399152 -0.1030339 -0.01210933 0.3401843 -0.1070164 -0.008932232 0.4413865 -0.102564 -0.007028639 0.4515139 -0.09938311 -0.008105993 0.3406609 -0.1140578 -0.00582683 0.350569 -0.1161447 -0.00527513 0.3407723 -0.1157184 -0.005448639 0.358272 -0.119264 -0.004999995 0.349684 -0.119871 -0.004999995 0.3409067 -0.1177014 -0.005143463 0.39629 -0.1058008 -0.007324516 0.4133713 -0.1046541 -0.00719887 0.3410931 -0.1204596 -0.004970431 0.442629 -0.0965501 -0.01056635 0.4301974 -0.1002896 -0.008727371 0.4040383 -0.1122707 -0.005240321 0.401195 -0.115961 -0.004999995 0.409775 -0.1152459 -0.004999995 0.442894 -0.09940266 -0.008562505 0.4513494 -0.09766006 -0.009149074 0.4421642 -0.1057763 -0.005885243 0.418354 -0.114514 -0.004999995 0.4434282 -0.1089986 -0.005214035 0.4521356 -0.1059321 -0.005606055 0.4517103 -0.1014582 -0.007066071 0.4519503 -0.10398 -0.006129503 0.4523015 -0.1076812 -0.00527352 0.4525179 -0.109962 -0.005033373 0.444082 -0.11221 -0.004999995 0.452655 -0.111406 -0.004999995 0.375446 -0.117996 -0.004999995 0.36686 -0.118639 -0.004999995 0.3609451 -0.09670525 -0.01871699 0.360817 -0.09524852 -0.02225804 0.3605144 -0.09438776 -0.02583408 0.392613 -0.116657 -0.004999995 0.38403 -0.117336 -0.004999995 0.3795894 -0.1104441 -0.006063938 0.3780496 -0.09578192 -0.01803874 0.3779111 -0.09425234 -0.02143847 0.3776021 -0.09328728 -0.02489525 0.406215 -0.1085906 -0.005982637 0.3951593 -0.09480673 -0.01737231 0.3947514 -0.09214729 -0.02396035 0.3950129 -0.09321206 -0.02063 0.426932 -0.113764 -0.004999995 0.442394 -0.0940153 -0.01293796 0.4507453 -0.09128749 -0.01525777 0.4118356 -0.09097576 -0.02303653 0.4508978 -0.09289628 -0.01327979 0.4510295 -0.09427767 -0.01185941 0.435507 -0.112996 -0.004999995 0.451168 -0.09573894 -0.01056629 0.4746332 -0.09352195 -0.007112562 0.4755202 -0.09137463 -0.009312808 0.4763401 -0.09128504 -0.009089708 0.4770526 -0.08951336 -0.0115872 0.4721115 -0.08987677 -0.01272946 0.4725418 -0.0883094 -0.0154255 0.4786449 -0.08805096 -0.01401764 0.4700229 -0.09419071 -0.008225619 0.47118 -0.091843 -0.01032292 0.4739497 -0.09362083 -0.007302045 0.4762426 -0.08957278 -0.01179563 0.4746841 -0.09146451 -0.009529888 0.4774537 -0.08809971 -0.01432347 0.4752911 -0.08964306 -0.01202911 0.4731965 -0.09372961 -0.007500648 0.4740169 -0.09153664 -0.009694933 0.4761566 -0.08815264 -0.01463985 0.4739258 -0.08824807 -0.01514041 0.4731867 -0.08979731 -0.01250642 0.4732067 -0.09162408 -0.009886264 0.4742407 -0.08971965 -0.0122745 0.4725343 -0.09382545 -0.007666289 0.4751557 -0.08819448 -0.01487129 0.4718667 -0.09392219 -0.007825672 0.4721881 -0.09173434 -0.01011306 0.470975 -0.09405261 -0.008025884 0.4701376 -0.09195727 -0.01052427 0.4710786 -0.08995491 -0.01292949 0.4693318 -0.09429216 -0.008360743 0.4713064 -0.0883665 -0.01566433 0.4685394 -0.09441018 -0.008505761 0.4698145 -0.090052 -0.01315748 0.4690307 -0.09207856 -0.0107221 0.4702994 -0.08841508 -0.0158469 0.4675658 -0.09455585 -0.008670151 0.4679692 -0.09219765 -0.01089513 0.4692922 -0.08846491 -0.01602149 0.468304 -0.0901702 -0.01340663 0.4667561 -0.0946784 -0.008795261 0.4666827 -0.09234362 -0.01108503 0.4678443 -0.08854365 -0.01624715 0.4660453 -0.09478735 -0.008896708 0.4668728 -0.09028404 -0.01362037 0.4651298 -0.09492951 -0.009016156 0.465211 -0.09251397 -0.01127588 0.4657247 -0.09037822 -0.01377511 0.4660998 -0.08863747 -0.01650673 0.4641705 -0.09508013 -0.009127557 0.4644038 -0.09048992 -0.01393538 0.4637884 -0.09268134 -0.01143461 0.4645624 -0.08872723 -0.01670914 0.4632896 -0.0952214 -0.009217321 0.4621021 -0.09541547 -0.009320735 0.4623505 -0.09285563 -0.01156908 0.4629516 -0.09061431 -0.01409256 0.4623711 -0.08886307 -0.01696389 0.4614896 -0.09074515 -0.01422739 0.460855 -0.09562176 -0.009407758 0.4608662 -0.0930376 -0.01168274 0.4596575 -0.09582519 -0.009470641 0.4593671 -0.09322851 -0.01176947 0.4598824 -0.09089094 -0.01435351 0.4594569 -0.08905553 -0.01724654 0.458436 -0.09603524 -0.009514808 0.4579276 -0.09107679 -0.014472 0.4576704 -0.0934472 -0.01183754 0.4575269 -0.09619426 -0.009534478 0.4555751 -0.08933168 -0.01753199 0.4565355 -0.09637194 -0.009542763 0.4564235 -0.0936101 -0.01186746 0.4553018 -0.09133106 -0.0145781 0.4552761 -0.09376454 -0.01187849 0.455448 -0.09656769 -0.009537577 0.4543162 -0.09677648 -0.009515047 0.4539942 -0.09393727 -0.01187491 0.4529086 -0.09157031 -0.01462191 0.4526799 -0.09411895 -0.01185154 0.4528237 -0.09705525 -0.009460389 0.4506819 -0.08971869 -0.01772403 0.4511088 -0.094325 -0.01181149 0.4513881 -0.09730625 -0.009395122 0.4508714 -0.09177619 -0.01462215 0.4525265 -0.110041 -0.005031824 0.4526558 -0.1114051 -0.004987537 0.452434 -0.1090742 -0.00510776 0.4523717 -0.1077517 -0.005271077 0.4521671 -0.1062726 -0.005536019 0.4511615 -0.09569829 -0.01061326 0.4520918 -0.1054716 -0.005719125 0.4519058 -0.1035066 -0.006287038 0.4520328 -0.1041761 -0.006076335 0.4516997 -0.1006308 -0.007461726 0.4517942 -0.1023807 -0.006705582 0.4516503 -0.10083 -0.007364213 0.4514678 -0.09892857 -0.008372604 0.4513167 -0.0973199 -0.009383797 0.4510284 -0.09427183 -0.01186376 0.4508953 -0.09289568 -0.01329571 0.450776 -0.09161609 -0.01483452 0.4506769 -0.09057486 -0.01632559 0.450552 -0.08925151 -0.01858592 0.4505014 -0.0887351 -0.0196805 0.450452 -0.08819359 -0.02097493 0.4753074 -0.09342366 -0.006917834 0.4779615 -0.08944642 -0.01134258 0.4795351 -0.08801501 -0.01377797 0.4769577 -0.09121727 -0.00891447 0.4761864 -0.09329456 -0.006650805 0.4790378 -0.08936661 -0.0110377 0.4804584 -0.08797812 -0.01351869 0.4777317 -0.09113144 -0.008686542 0.4815148 -0.08793532 -0.01320993 0.4770268 -0.09316962 -0.006380856 0.4799898 -0.08929401 -0.01075547 0.4786913 -0.09102356 -0.00838989 0.48063 -0.08924436 -0.01055854 0.4776739 -0.09307134 -0.00616461 0.4824424 -0.0878964 -0.01292914 0.4797025 -0.09090715 -0.008060395 0.4813035 -0.08919161 -0.01034462 0.4783169 -0.09297257 -0.005941092 0.4831498 -0.08786612 -0.01270759 0.4821327 -0.08912461 -0.01007312 0.4791704 -0.09284019 -0.005630552 0.4805426 -0.09080737 -0.007773816 0.4839355 -0.08783251 -0.0124523 0.4813438 -0.09070962 -0.007489979 0.4828206 -0.08906733 -0.009840369 0.4784297 -0.09508752 -0.003536105 0.4799117 -0.0927205 -0.005349636 0.4847416 -0.08779609 -0.0121839 0.4834499 -0.08901435 -0.00962001 0.4804798 -0.09262692 -0.005126953 0.485399 -0.08776551 -0.01195859 0.4820731 -0.09061783 -0.007221281 0.4791952 -0.09493368 -0.003211319 0.4843301 -0.08893752 -0.009302556 0.4860912 -0.08773243 -0.01171404 0.4810695 -0.0925275 -0.004888355 0.4827693 -0.09052801 -0.006955981 0.4815677 -0.09244155 -0.004681468 0.4868481 -0.08769482 -0.0114392 0.4852234 -0.0888555 -0.008968293 0.4821206 -0.09234398 -0.004445314 0.4834268 -0.09044039 -0.006697177 0.4874942 -0.08766108 -0.0111984 0.4840158 -0.09035927 -0.006459534 0.4859171 -0.08878904 -0.008700609 0.4828106 -0.09221893 -0.004140734 0.4883138 -0.08761709 -0.01088225 0.4846342 -0.09027159 -0.006202399 0.4813232 -0.09448164 -0.002229154 0.4867435 -0.08870738 -0.00837022 0.4891346 -0.08756822 -0.01056194 0.4851606 -0.09019446 -0.005978703 0.4835147 -0.09208577 -0.003820359 0.4876103 -0.08861583 -0.008014082 0.4856457 -0.09012079 -0.005768597 0.4897977 -0.08752751 -0.01029336 0.4862735 -0.09002292 -0.005489528 0.4852789 -0.09172666 -0.002970099 0.4882482 -0.08854508 -0.007744431 0.4903796 -0.08748936 -0.01005363 0.4888799 -0.0884723 -0.007470965 0.4908957 -0.08745431 -0.009835898 0.486862 -0.08992713 -0.005221307 0.4915995 -0.08740413 -0.009531736 0.4873952 -0.08983808 -0.004971444 0.4894683 -0.08840107 -0.007209956 0.490001 -0.08833491 -0.006967723 0.4881274 -0.08970934 -0.004622161 0.4923527 -0.08734661 -0.009197652 0.4893503 -0.08947759 -0.00401926 0.4906409 -0.08825135 -0.006671547 0.4930652 -0.08728826 -0.008875191 0.4887653 -0.08959078 -0.004311025 0.4911802 -0.08817666 -0.006418704 0.4937636 -0.08722662 -0.008554399 0.4917496 -0.08809506 -0.006147086 0.4942407 -0.08718204 -0.008331179 0.4899246 -0.08936095 -0.003727257 0.494691 -0.08713829 -0.00811702 0.4971617 -0.08668529 -0.01031148 0.4924227 -0.08799338 -0.005818307 0.4952228 -0.08708435 -0.007857024 0.4976691 -0.08667379 -0.01006036 0.492944 -0.08791095 -0.005557477 0.4957316 -0.08702653 -0.007646203 0.4933812 -0.08783495 -0.005360245 0.4983363 -0.08665299 -0.009722352 0.4986154 -0.08664041 -0.009412825 0.4975526 -0.08691036 -0.005679428 0.4948062 -0.08772438 -0.003878414 0.4990351 -0.08661639 -0.008934974 0.4994639 -0.08659201 -0.008434057 0.4918808 -0.08902788 -0.002339243 0.5000261 -0.08655995 -0.007755577 0.4925657 -0.08895957 -0.001621901 0.4929764 -0.08891659 -0.001182258 0.5005339 -0.08653104 -0.007120609 0.4961012 -0.08762794 -0.002360045 0.5011568 -0.08649563 -0.00630939 0.499319 -0.08680254 -0.003444731 0.4930852 -0.0891866 2.82849e-7 0.4963048 -0.08761143 -0.002113878 0.501657 -0.08646726 -0.005632281 0.4965951 -0.08758985 -0.001749038 0.4969772 -0.08756244 -0.001246273 0.502013 -0.08644711 -0.005133569 0.4946881 -0.0885449 0 0.5023429 -0.08642846 -0.004659831 0.4974985 -0.08753991 -3.97913e-4 0.4956884 -0.08818107 0 0.502724 -0.08640688 -0.004098057 0.5002489 -0.0867443 -0.002183794 0.4970628 -0.0877285 -2.27724e-7 0.5031172 -0.08638477 -0.00349915 0.4978924 -0.08748674 0 0.500509 -0.08673048 -0.001754581 0.500848 -0.08670997 -0.001253366 0.5034837 -0.08636409 -0.002922475 0.4992625 -0.08713507 0 0.5038562 -0.08634305 -0.002317905 0.501341 -0.08668297 -3.77004e-4 0.5008108 -0.08680862 0 0.5040676 -0.08633542 -0.001966238 0.5009362 -0.08677828 -3.37565e-7 0.504269 -0.08632034 -0.001623988 0.5018069 -0.08663707 0 0.5045113 -0.08630645 -0.001204431 0.5029029 -0.08648085 0 0.5048582 -0.08628624 -5.86123e-4 0.5042911 -0.08633279 0 0.5051758 -0.08626866 0 0.4529354 -0.1112757 -0.005000174 0.4527026 -0.1039714 -0.006115436 0.4533905 -0.1110664 -0.004997551 0.4525723 -0.10043 -0.007512331 0.4513483 -0.08813226 -0.02093136 0.4532461 -0.1074613 -0.005293726 0.4524021 -0.0880596 -0.02087295 0.4540278 -0.1107762 -0.004989445 0.4539015 -0.1072056 -0.005309641 0.4535413 -0.1037017 -0.006158828 0.4534571 -0.1002084 -0.007561862 0.4545372 -0.110547 -0.004977643 0.4541373 -0.1035133 -0.00618273 0.4538574 -0.08796262 -0.02078038 0.4544936 -0.1069778 -0.005317866 0.4544188 -0.09997171 -0.00760281 0.4550271 -0.110329 -0.004960536 0.4547863 -0.1033101 -0.006202816 0.4550558 -0.1067637 -0.005320727 0.4557946 -0.1099927 -0.004930198 0.4549952 -0.08788985 -0.02069789 0.4557403 -0.1065077 -0.005316972 0.4552605 -0.09976577 -0.007627546 0.4555897 -0.1030623 -0.006218194 0.4562038 -0.08781498 -0.02060198 0.4562685 -0.1097875 -0.004902958 0.4559912 -0.09959143 -0.007640004 0.4566037 -0.1061905 -0.005301237 0.456462 -0.1027981 -0.006222724 0.4569659 -0.1094908 -0.004860877 0.4569439 -0.09936642 -0.007644653 0.457552 -0.08773505 -0.02048301 0.4574684 -0.1092795 -0.004824042 0.4574244 -0.1058924 -0.005274415 0.4572623 -0.1025588 -0.006216168 0.4578379 -0.1091254 -0.004793643 0.4578204 -0.09916168 -0.007636725 0.4590194 -0.08765196 -0.02034026 0.4581882 -0.1056217 -0.005239307 0.4581031 -0.1023139 -0.006197571 0.4584035 -0.1088935 -0.004745364 0.4586027 -0.09898245 -0.007619738 0.4587627 -0.1087473 -0.00470829 0.4589765 -0.1053467 -0.005192041 0.4589309 -0.1020747 -0.006167709 0.460376 -0.08757925 -0.02019441 0.4592515 -0.1085505 -0.004656016 0.4596866 -0.09873944 -0.007580339 0.4597676 -0.1050776 -0.00513345 0.4597379 -0.1018481 -0.006127178 0.461459 -0.08752369 -0.02006924 0.4600315 -0.1082427 -0.004566848 0.4605236 -0.1080507 -0.00450164 0.4605158 -0.1048257 -0.005067646 0.4605041 -0.1016355 -0.006078124 0.4607515 -0.0985037 -0.007523357 0.4627505 -0.08746063 -0.01990985 0.4612765 -0.1014264 -0.006018042 0.4612719 -0.1045781 -0.004990458 0.4615896 -0.09832197 -0.007466077 0.4614191 -0.1077103 -0.004377245 0.4641909 -0.08739447 -0.01971727 0.4620922 -0.1012075 -0.005943477 0.4618698 -0.1075412 -0.004305958 0.4622216 -0.1042731 -0.004877984 0.4622954 -0.09817099 -0.007408738 0.4652881 -0.08734714 -0.01956081 0.4630079 -0.09802168 -0.007342338 0.46285 -0.1010081 -0.00586301 0.4627162 -0.107232 -0.004167735 0.4631109 -0.1039946 -0.004755854 0.4667376 -0.0872882 -0.01934134 0.4640162 -0.09781455 -0.0072335 0.4631758 -0.1070665 -0.004084289 0.4637589 -0.1007746 -0.005752325 0.4640238 -0.1037163 -0.004614531 0.4639502 -0.106795 -0.003939092 0.4761013 -0.1005291 -8.03314e-4 0.4751488 -0.1034712 8.46424e-7 0.4651006 -0.09759449 -0.007097363 0.4646319 -0.1005548 -0.005630612 0.467925 -0.08724385 -0.0191487 0.4643165 -0.1066682 -0.003863453 0.4688384 -0.08722954 -0.01899677 0.4648341 -0.1034767 -0.004472613 0.4647361 -0.1065244 -0.003773391 0.4654483 -0.1003542 -0.005502998 0.4660202 -0.09741157 -0.006965398 0.4653956 -0.1033128 -0.004366815 0.4701145 -0.08721035 -0.01877433 0.4653737 -0.1063092 -0.003629028 0.4661251 -0.1001881 -0.005387842 0.4669083 -0.09723812 -0.006823837 0.466063 -0.10312 -0.004232347 0.4658021 -0.1061667 -0.003525316 0.4667217 -0.1000458 -0.00527811 0.4712897 -0.08719211 -0.01855802 0.466484 -0.1059451 -0.003353238 0.4666746 -0.1029465 -0.004099786 0.4677248 -0.0970804 -0.006680727 0.4673709 -0.09989213 -0.005150139 0.4722355 -0.08717691 -0.01837617 0.4674267 -0.1027392 -0.003924965 0.4668499 -0.1058272 -0.0032534 0.4685745 -0.09691977 -0.006518244 0.4680504 -0.09973478 -0.005006253 0.4672505 -0.1057009 -0.003142833 0.4731662 -0.08716154 -0.01819026 0.468242 -0.1025166 -0.003719747 0.4677957 -0.1055319 -0.002986013 0.4686249 -0.0996018 -0.00487709 0.4694342 -0.09675788 -0.006339848 0.4742596 -0.08714383 -0.0179634 0.4692546 -0.09945875 -0.004727244 0.4682633 -0.1053898 -0.002845406 0.469053 -0.1023009 -0.003499627 0.4702951 -0.09659898 -0.006146311 0.4754615 -0.08712381 -0.01770174 0.4686074 -0.105286 -0.00273621 0.4699738 -0.09929752 -0.004544019 0.4710409 -0.09646046 -0.005967378 0.4693729 -0.1050627 -0.002488851 0.4697791 -0.1021118 -0.003287017 0.4766484 -0.0871039 -0.01743161 0.4707921 -0.09911602 -0.004321992 0.4717016 -0.09634006 -0.005798578 0.4703944 -0.1019537 -0.003096818 0.4698082 -0.1049389 -0.002339422 0.4778233 -0.08708387 -0.01715129 0.4703336 -0.1047893 -0.00215274 0.4723775 -0.09621632 -0.005616843 0.4716967 -0.09891569 -0.004057645 0.4711957 -0.1017499 -0.002833366 0.4788012 -0.08706635 -0.01690804 0.4707621 -0.104663 -0.001990079 0.473083 -0.09608817 -0.00541675 0.4722993 -0.09878385 -0.003869831 0.4719371 -0.1015622 -0.002573668 0.4797407 -0.08704936 -0.01666635 0.4729337 -0.09864705 -0.003662288 0.4715359 -0.1044427 -0.001688838 0.4738388 -0.0959509 -0.005189955 0.4726949 -0.1013731 -0.002292275 0.4807155 -0.08703178 -0.01640617 0.47197 -0.1043197 -0.001509666 0.4746356 -0.0958051 -0.004937946 0.4736523 -0.09848964 -0.003415465 0.4723696 -0.1042078 -0.001338124 0.4816758 -0.08701455 -0.01614093 0.4734618 -0.1011814 -0.001989781 0.4744426 -0.09831762 -0.00312829 0.4755297 -0.09563958 -0.004638612 0.4730402 -0.1040252 -0.001042723 0.4827163 -0.08699482 -0.01584231 0.4742084 -0.1009978 -0.001677751 0.4733671 -0.1039372 -8.91631e-4 0.4752016 -0.09815108 -0.002835988 0.4764222 -0.095474 -0.004320085 0.4736407 -0.1038632 -7.62232e-4 0.4836264 -0.08697789 -0.01557207 0.4739462 -0.1037817 -6.13936e-4 0.4748864 -0.1008283 -0.001379072 0.4757164 -0.09803754 -0.002628803 0.4845914 -0.08695924 -0.01527518 0.4771316 -0.09533905 -0.004054069 0.4744305 -0.1036561 -3.74553e-4 0.4763055 -0.09790676 -0.002382636 0.4754957 -0.1006777 -0.001097261 0.4747919 -0.1035632 -1.89259e-4 0.477705 -0.09522956 -0.003829896 0.4855187 -0.08694112 -0.01498025 0.4768884 -0.0977751 -0.002129495 0.4866443 -0.08691859 -0.01460909 0.4755651 -0.1028498 2.63111e-7 0.4765679 -0.1004035 -5.73647e-4 0.4760145 -0.1022124 0 0.477385 -0.09766083 -0.001906812 0.4781581 -0.09751659 -0.001516759 0.4764893 -0.1015723 0 0.4877374 -0.08689641 -0.01423329 0.4771062 -0.100299 -2.73697e-4 0.476899 -0.1010478 2.9789e-7 0.4784098 -0.09742242 -0.00142157 0.4771963 -0.1006818 -2.36165e-7 0.4800059 -0.09476655 -0.002851366 0.4887134 -0.08687585 -0.01388549 0.4776512 -0.10014 -1.19601e-7 0.4787136 -0.09734821 -0.001273036 0.4782277 -0.09949046 -7.94639e-7 0.4789828 -0.09728354 -0.001137435 0.4793996 -0.09717512 -9.30035e-4 0.4893728 -0.08686298 -0.01364374 0.4807814 -0.09460079 -0.002490639 0.4787285 -0.09897196 2.34606e-7 0.4900469 -0.08684796 -0.0133903 0.4794499 -0.0982604 -4.84722e-7 0.4802169 -0.09703195 -4.37321e-4 0.4909298 -0.08682894 -0.01304972 0.4817127 -0.09436649 -0.002072811 0.4798967 -0.09783452 1.7348e-7 0.4804027 -0.09736704 0 0.4820739 -0.09430998 -0.001855313 0.4917762 -0.08681112 -0.01271241 0.4823469 -0.09424597 -0.001715421 0.4841834 -0.09195435 -0.003505706 0.4809255 -0.09689903 0 0.4827204 -0.09415572 -0.001522362 0.481484 -0.09641492 0 0.4926773 -0.08679115 -0.01234287 0.4847656 -0.09183573 -0.003223598 0.483158 -0.09404474 -0.001294732 0.4818879 -0.09607595 0 0.4823724 -0.0956847 0 0.4836854 -0.09391373 -0.001004874 0.4936218 -0.08676874 -0.01194119 0.4829602 -0.09522444 1.96571e-7 0.4857872 -0.09161555 -0.002712428 0.4940953 -0.08675891 -0.01173496 0.4838725 -0.09453624 2.27349e-7 0.4843526 -0.0937758 -5.74864e-4 0.4947347 -0.08674287 -0.011451 0.4862418 -0.09150332 -0.002497911 0.4844444 -0.09412348 0 0.486611 -0.09142684 -0.002283275 0.4952833 -0.08673155 -0.01120215 0.4869105 -0.0913549 -0.002124488 0.4850517 -0.09369611 0 0.4958828 -0.08671653 -0.01092427 0.4872508 -0.09127205 -0.001940429 0.4857448 -0.09322464 0 0.4965626 -0.0866996 -0.01060211 0.4876955 -0.09116035 -0.001696705 0.486422 -0.09277755 -1.42147e-7 0.4880753 -0.09105962 -0.001490592 0.4904925 -0.0892415 -0.003431618 0.4871634 -0.09230142 -2.16227e-7 0.4885128 -0.09094184 -0.001244902 0.4909934 -0.08912789 -0.003177285 0.4879552 -0.09181636 0 0.489139 -0.0908215 -7.48289e-4 0.4914645 -0.08905804 -0.002805888 0.4885938 -0.09144091 2.51983e-7 0.4891819 -0.09110969 0 0.4900218 -0.09065568 0 0.4922114 -0.08899402 -0.002000749 0.4909746 -0.09016805 0 0.4919893 -0.08967763 0 0.4935555 -0.08888423 -4.08601e-4 0.4939535 -0.08883059 0 0.5041563 -0.08634591 0 0.2764711 -0.09108853 0 0.2499769 -0.09269529 0 0.246583 -0.105007 0 0.222374 -0.09194147 0 0.22079 -0.0926519 0 0.220655 -0.09283119 0 0.22032 -0.09388619 0 0.220339 -0.09366208 0 0.220382 -0.09344309 0 0.22045 -0.09322917 0 0.221927 -0.09197968 0 0.221711 -0.09203571 0 0.5049697 -0.08628195 0 0.51 -0.07799953 -3.9217e-7 0.455 -0.074225 0 0.48 -0.07958668 0 0.48 -0.074225 0 0.455 -0.08093041 0 0.51 -0.08599996 0 0.4988528 -0.08723437 0 0.5034234 -0.08642017 0 0.5026354 -0.08651596 0 0.50172 -0.08665078 0 0.5010185 -0.08677119 0 0.5003834 -0.08689218 0 0.4996978 -0.08703714 0 0.4979124 -0.08748239 0 0.4971316 -0.08770877 0 0.4963263 -0.0879637 0 0.4956476 -0.0881955 0 0.4948201 -0.08849537 0 0.4938692 -0.08886319 0 0.4928965 -0.08927053 0 0.4921733 -0.08959412 0 0.4913594 -0.08997768 0 0.490453 -0.09043323 0 0.4897985 -0.09077441 0 0.4889684 -0.09122842 0 0.4881865 -0.09167867 0 0.4876 -0.09203082 0 0.4869708 -0.0924229 0 0.4863547 -0.09282171 0 0.4854933 -0.09339362 0 0.4257257 -0.08252376 0 0.4849321 -0.09377932 0 0.4843774 -0.09417164 0 0.4835809 -0.09475266 0 0.4827234 -0.09540832 0 0.4820247 -0.09596264 0 0.4816012 -0.09631615 0 0.4811094 -0.0967378 0 0.4806616 -0.09713345 0 0.4801306 -0.09761625 0 0.4795281 -0.09818387 0 0.4790309 -0.09867054 0 0.4786298 -0.09907299 0 0.4782425 -0.09947341 0 0.4777862 -0.09998476 0 0.4773308 -0.1005178 0 0.4768897 -0.1010596 0 0.3873946 -0.08465164 0 0.4764724 -0.1015954 0 0.4760918 -0.1021059 0 0.4756522 -0.1027241 0 0.4751947 -0.1034024 0 0.39 -0.127696 0 0.415 -0.129584 0 0.449355 -0.145388 0 0.415 -0.147584 0 0.446985 -0.147764 0 0.4337115 -0.1497437 0 0.446625 -0.147988 0 0.449124 -0.1457369 0 0.4441016 -0.1491021 0 0.4344894 -0.1498198 0 0.4428524 -0.1494392 0 0.4361756 -0.1499302 0 0.4407908 -0.1497898 0 0.4416064 -0.1496786 0 0.442248 -0.149565 0 0.4390773 -0.1499295 0 0.4399425 -0.1498743 0 0.4379956 -0.1499627 0 0.4369255 -0.149955 0 0.443495 -0.1492789 0 0.4352955 -0.1498824 0 0.444704 -0.148895 0 0.4452871 -0.1486657 0 0.445879 -0.148393 0 0.446257 -0.148198 0 0.447334 -0.1475239 0 0.447999 -0.146989 0 0.447669 -0.147267 0 0.44831 -0.146697 0 0.448602 -0.146391 0 0.448873 -0.146071 0 0.3495234 -0.08680075 0 0.268131 -0.1109009 0 0.3125069 -0.08894902 0 0.342357 -0.13665 0 0.340568 -0.1361629 0 0.3486647 -0.1382506 0 0.3522791 -0.139086 0 0.3595392 -0.1405867 0 0.39 -0.1446959 0 0.382416 -0.14382 0 0.3796374 -0.1435474 0 0.3759617 -0.1431348 0 0.3704512 -0.1424092 0 0.373196 -0.142785 0 0.367696 -0.141996 0 0.3649503 -0.141555 0 0.362222 -0.141081 0 0.3559176 -0.139868 0 0.3451292 -0.137376 0 0.266193 -0.110251 0 0.26425 -0.109624 0 0.262304 -0.1090199 0 0.260353 -0.108439 0 0.258398 -0.1078799 0 0.256439 -0.107344 0 0.252509 -0.106341 0 0.254476 -0.106831 0 0.248562 -0.105429 0 0.250538 -0.105874 0 0.2445999 -0.104609 0 0.242612 -0.104232 0 0.2351509 -0.100293 0 0.24062 -0.103879 0 0.238624 -0.103549 0 0.236625 -0.103241 0 0.220156 -0.09988385 0 0.2215009 -0.09211605 0 0.221302 -0.09221917 0 0.2211149 -0.0923438 0 0.220944 -0.092489 0 0.222149 -0.09194809 0 0.220542 -0.09302479 0 0.51 -0.05029577 -0.01941984 0.51 -0.0424031 -0.02693539 0.51 -0.04176235 -0.02676349 0.51 -0.06499367 -0.0190162 0.51 -0.07727307 -0.02448415 0.51 -0.07669776 -0.02483969 0.51 -0.0742079 -0.01238918 0.51 -0.08540755 -0.01319307 0.51 -0.0852276 -0.01384985 0.51 -0.07838928 -0.02370685 0.51 -0.0662617 -0.01854157 0.51 -0.07892376 -0.02329099 0.51 -0.06563121 -0.01879036 0.51 -0.07783907 -0.02410459 0.51 -0.07994949 -0.02240157 0.51 -0.0674951 -0.01797938 0.51 -0.08043795 -0.02193027 0.51 -0.06688517 -0.01826965 0.51 -0.0794425 -0.02285695 0.51 -0.08090806 -0.02144294 0.51 -0.06868618 -0.01733535 0.51 -0.08135956 -0.02093964 0.51 -0.06809538 -0.01766794 0.51 -0.08221048 -0.0198791 0.51 -0.06983017 -0.01660746 0.51 -0.08260577 -0.01932948 0.51 -0.06926727 -0.0169816 0.51 -0.08179509 -0.02041578 0.51 -0.05899995 -0.01999998 0.51 -0.04699993 -0.02749997 0.51 -0.07091689 -0.01579689 0.51 -0.07144057 -0.01536029 0.51 -0.08333837 -0.0181874 0.51 -0.07037997 -0.01621258 0.51 -0.08298081 -0.01876705 0.51 -0.07194399 -0.01490867 0.51 -0.0724315 -0.01443856 0.51 -0.08398765 -0.01699805 0.51 -0.08367395 -0.01759779 0.51 -0.07290309 -0.01395004 0.51 -0.07335865 -0.01344299 0.51 -0.0848 -0.01513278 0.51 -0.08455127 -0.01576405 0.51 -0.07379245 -0.01292395 0.51 -0.08502537 -0.01449477 0.51 -0.07460516 -0.01183837 0.51 -0.07498407 -0.01127189 0.51 -0.08556377 -0.01253288 0.51 -0.07533937 -0.01069658 0.51 -0.07567429 -0.01010829 0.51 -0.08580458 -0.01120215 0.51 -0.0856961 -0.01186925 0.51 -0.08588916 -0.01053178 0.51 -0.07598876 -0.00950694 0.51 -0.08594995 -0.009857892 0.51 -0.08598685 -0.009180665 0.51 -0.07628285 -0.008892595 0.51 -0.07655346 -0.008272886 0.51 -0.03771889 -0.008889794 0.51 -0.02804726 -0.009825825 0.51 -0.02801227 -0.009164094 0.51 -0.02828896 -0.01179897 0.51 -0.02818566 -0.01114445 0.51 -0.03865849 -0.0106914 0.51 -0.07680249 -0.007643282 0.51 -0.08599996 -0.008500158 0.51 -0.03939145 -0.01183408 0.51 -0.02856427 -0.01309597 0.51 -0.02841496 -0.01244878 0.51 -0.02892899 -0.01436907 0.51 -0.02873569 -0.01373606 0.51 -0.04020386 -0.01291894 0.51 -0.07702988 -0.007003664 0.51 -0.04109269 -0.01394438 0.51 -0.02938258 -0.01561576 0.51 -0.02914518 -0.01499706 0.51 -0.04156279 -0.01443159 0.51 -0.02964109 -0.01622509 0.51 -0.07723569 -0.006354093 0.51 -0.08599996 0 0.51 -0.04205107 -0.01490288 0.51 -0.02992266 -0.01682657 0.51 -0.04255765 -0.01535844 0.51 -0.03022336 -0.01741707 0.51 -0.0774157 -0.005702018 0.51 -0.0775724 -0.00504297 0.51 -0.04307657 -0.01579207 0.51 -0.03054314 -0.01799649 0.51 -0.03088176 -0.01856696 0.51 -0.0777058 -0.004376947 0.51 -0.04361128 -0.01620745 0.51 -0.03123986 -0.01912426 0.51 -0.03161746 -0.01966828 0.51 -0.04416185 -0.0166046 0.51 -0.077816 -0.003703892 0.51 -0.04064077 -0.0134415 0.51 -0.03201639 -0.02020275 0.51 -0.04472827 -0.01698338 0.51 -0.07789915 -0.003032922 0.51 -0.0453034 -0.01733934 0.51 -0.03243309 -0.0207203 0.51 -0.03978747 -0.01238316 0.51 -0.07795751 -0.002358675 0.51 -0.07799118 -0.00168097 0.51 -0.03286767 -0.02122098 0.51 -0.03332269 -0.02170479 0.51 -0.04589146 -0.01767516 0.51 -0.03901594 -0.01127177 0.51 -0.03379297 -0.02217155 0.51 -0.04649245 -0.01799076 0.51 -0.078 -9.99712e-4 0.51 -0.02810508 -0.01048517 0.51 -0.0383231 -0.0101009 0.51 -0.03427869 -0.02262139 0.51 -0.078 0 0.51 -0.03800988 -0.009500324 0.51 -0.02799999 -0.00849992 0.51 -0.03744888 -0.008264005 0.51 -0.04710656 -0.01828634 0.51 -0.03478187 -0.02305555 0.51 -0.03720176 -0.007631659 0.51 -0.08427947 -0.01638847 0.51 -0.07610929 -0.02517467 0.51 -0.07550758 -0.02548915 0.51 -0.06434917 -0.01921898 0.51 -0.07427281 -0.02605307 0.51 -0.07489269 -0.02578306 0.51 -0.0736429 -0.02630126 0.51 -0.06369227 -0.01939976 0.51 -0.07300305 -0.02652758 0.51 -0.0723533 -0.02673196 0.51 -0.07170128 -0.0269109 0.51 -0.06303197 -0.01955687 0.51 -0.07104235 -0.02706646 0.51 -0.07037669 -0.02719879 0.51 -0.06970405 -0.02730774 0.51 -0.0690332 -0.02739185 0.51 -0.06835889 -0.02745187 0.51 -0.06768119 -0.02748787 0.51 -0.06236839 -0.01969015 0.51 -0.06699997 -0.02749997 0.51 -0.06170135 -0.01979964 0.51 -0.0610311 -0.01988536 0.51 -0.06035739 -0.01994735 0.51 -0.0596804 -0.01998555 0.51 -0.05499988 -0.01999998 0.51 -0.04633587 -0.02748805 0.51 -0.05095505 -0.01957595 0.51 -0.05296605 -0.0199002 0.51 -0.05229485 -0.01981747 0.51 -0.04370158 -0.02721118 0.51 -0.04435688 -0.02731478 0.51 -0.04964369 -0.0192402 0.51 -0.03807705 -0.02527779 0.51 -0.0489946 -0.0190345 0.51 -0.04304856 -0.02708446 0.51 -0.0405001 -0.02635407 0.51 -0.03988057 -0.0261178 0.51 -0.04112654 -0.02656888 0.51 -0.03866779 -0.02557975 0.51 -0.03926807 -0.02585995 0.51 -0.04835528 -0.01880699 0.51 -0.03692829 -0.02461206 0.51 -0.03749585 -0.02495378 0.51 -0.03582787 -0.02386927 0.51 -0.0363723 -0.02425056 0.51 -0.04772597 -0.01855754 0.51 -0.03529828 -0.02347147 0.51 -0.03697758 -0.006992816 0.51 -0.03677606 -0.006347358 0.51 -0.03643995 -0.005030453 0.51 -0.03659617 -0.005690574 0.51 -0.03630739 -0.004366993 0.51 -0.03619855 -0.003700256 0.51 -0.03601408 -0.001680016 0.51 -0.03605186 -0.002356767 0.51 -0.03611338 -0.003030121 0.51 -0.02799999 0 0.51 -0.03599995 -10e-4 0.51 -0.03599995 0 0.51 -0.04501438 -0.02739548 0.51 -0.04567396 -0.0274533 0.51 -0.05162137 -0.01970845 0.51 -0.05364066 -0.01995807 0.51 -0.05431866 -0.01999139 0.337412 -0.02406334 0 0.338 -0.02387237 0 0.337546 -0.02398139 0 0.477332 -0.02615308 0 0.48 -0.0345757 0 0.493666 -0.02708947 0 0.337691 -0.02392137 0 0.337844 -0.02388465 0 0.48 -0.04722499 0 0.455 -0.04651415 0 0.337293 -0.02416527 0 0.455 -0.04722499 0 0.411237 -0.04336738 0 0.406237 -0.03536736 0 0.411999 -0.02214819 0 0.363 -0.02387237 0 0.337191 -0.0242846 0 0.337109 -0.02441835 0 0.337049 -0.02456337 0 0.337012 -0.02471596 0 0.411237 -0.03536736 0 0.444665 -0.02420246 0 0.428332 -0.02318829 0 0.337 -0.02487236 0 0.379333 -0.01999026 0 0.395666 -0.02108216 0 0.363 -0.01887249 0 0.460999 -0.02519065 0 0.4913943 -0.03513312 0 0.51 -0.02799999 0 0.51 -0.03600269 0 0.337 -0.04265129 0 0.408733 -0.04319846 0 0.406237 -0.04300785 0 0.4529116 -0.04415798 -0.01099991 0.4521715 -0.04406839 -0.03163093 0.3679643 -0.03627818 -0.03641498 0.4641793 -0.04402267 -0.01099997 0.411237 -0.04336738 0 0.411237 -0.04336738 -0.01099997 0.4084701 -0.04318636 -0.03458154 0.4062365 -0.04301434 0 0.4647279 -0.04395419 -0.03069931 0.468035 -0.04393726 -0.01099997 0.468035 -0.04393726 -0.01999998 0.4767441 -0.04392707 -0.01999998 0.4767441 -0.04392319 -0.02980506 0.4438946 -0.04412341 -0.03223299 0.4431346 -0.04415524 -0.01099997 0.437816 -0.04412716 -0.03266555 0.4374487 -0.04410105 -0.01099997 0.4308266 -0.04407626 -0.03315085 0.4288324 -0.04396349 -0.01099997 0.4243619 -0.04394525 -0.03358483 0.4196487 -0.04379236 -0.03389161 0.41503 -0.04352378 -0.01099997 0.41462 -0.04356491 -0.03420889 0.406237 -0.04300785 -0.01099997 0.4005999 -0.04253387 -0.01099997 0.4023347 -0.04266691 -0.03493237 0.3971691 -0.04211294 -0.0352109 0.3935005 -0.04166817 -0.01099997 0.3913253 -0.04133874 -0.03550499 0.3880064 -0.04080766 -0.01099997 0.3858984 -0.04044985 -0.03575402 0.3835475 -0.03999322 -0.01099997 0.3815682 -0.03962403 -0.03593659 0.3789514 -0.03904128 -0.01099997 0.3779702 -0.03884971 -0.03607642 0.3735772 -0.03780388 -0.03623491 0.3743004 -0.03796219 -0.01099997 0.371237 -0.03718459 -0.01099997 0.3712345 -0.03719383 -0.01999998 0.3667925 -0.03592646 -0.01999998 0.3643 -0.03512722 -0.03651386 0.363947 -0.03500783 -0.01999998 0.3615546 -0.03413224 -0.03657007 0.361324 -0.03404372 -0.01999998 0.3596222 -0.03332799 -0.03659433 0.3571126 -0.03213536 -0.01999998 0.3574615 -0.03231394 -0.03661012 0.3591474 -0.03312051 -0.01999998 0.3556879 -0.03133761 -0.03662455 0.3552495 -0.03107893 -0.01999998 0.3543342 -0.03049516 -0.03662353 0.3534273 -0.02988016 -0.01999998 0.352669 -0.02929538 -0.03657555 0.353447 -0.02987807 -0.03660529 0.351693 -0.02849507 -0.01999998 0.351713 -0.02850145 -0.03651475 0.349647 -0.02641797 -0.03633266 0.3501212 -0.0269742 -0.01999998 0.349966 -0.02678167 -0.03638947 0.3503581 -0.02722036 -0.03643661 0.3487706 -0.02531987 -0.01999998 0.349044 -0.02567225 -0.03616964 0.348759 -0.02529036 -0.03606349 0.34934 -0.02604818 -0.03625947 0.348228 -0.02451777 -0.03579449 0.348486 -0.02490359 -0.03593975 0.347536 -0.02335268 -0.03524219 0.347637 -0.02356231 -0.01999998 0.347984 -0.02412927 -0.03563004 0.346815 -0.02185666 -0.03422325 0.3468079 -0.02185094 -0.01999998 0.346974 -0.02221828 -0.03450655 0.346123 -0.01990908 -0.03215998 0.3461386 -0.02000677 -0.01999998 0.34621 -0.02020049 -0.03254199 0.346307 -0.02050715 -0.03291106 0.346417 -0.02082556 -0.03326338 0.345974 -0.01937395 -0.03135877 0.345913 -0.01912915 -0.03093886 0.346043 -0.01963418 -0.03176617 0.345702 -0.01816827 -0.02871268 0.345676 -0.01802927 -0.02824497 0.3456065 -0.01766353 -0.01999998 0.34581 -0.01869297 -0.03007429 0.345612 -0.0176627 -0.02632945 0.345622 -0.017726 -0.02681505 0.345654 -0.01790875 -0.02777177 0.345636 -0.01780796 -0.02729588 0.345733 -0.01832497 -0.02917277 0.345769 -0.01849979 -0.02962636 0.345858 -0.01890277 -0.03051179 0.346538 -0.02115559 -0.03359895 0.34667 -0.02150249 -0.0339207 0.347147 -0.02259159 -0.0347715 0.347335 -0.02297097 -0.03501695 0.347752 -0.0237382 -0.03544676 0.345612 -0.01759898 -0.02433037 0.345612 -0.01759827 -0.02328449 0.345612 -0.01761877 -0.02218484 0.345612 -0.0176205 -0.02534538 0.345612 -0.0176627 -0.02632945 0.345612 -0.01763504 -0.01999998 0.345612 -0.0176627 -0.01999998 0.477035 -0.03594249 -0.01999998 0.495241 -0.03060024 -0.01999998 0.495023 -0.03659635 -0.01999998 0.349559 -0.02631735 -0.01999998 0.371237 -0.02918457 -0.01999998 0.349959 -0.02677875 -0.01999998 0.468035 -0.04393726 -0.01999998 0.4727039 -0.04392504 -0.01999998 0.468035 -0.03543728 -0.01999998 0.3566038 -0.03185808 -0.01999998 0.355779 -0.03139156 -0.01999998 0.349174 -0.02584224 -0.01999998 0.476744 -0.04393714 -0.01999998 0.495241 -0.03034007 -0.01999998 0.4205348 -0.02269983 -0.01999998 0.346059 -0.01967436 -0.01999998 0.34589 -0.0190199 -0.01999998 0.346685 -0.02154088 -0.01999998 0.346456 -0.02093487 -0.01999998 0.3456103 -0.01763558 -0.01999998 0.345741 -0.01834934 -0.01999998 0.346248 -0.02031266 -0.01999998 0.346933 -0.0221309 -0.01999998 0.347201 -0.02270466 -0.01999998 0.347489 -0.02326285 -0.01999998 0.347791 -0.023808 -0.01999998 0.348449 -0.0248537 -0.01999998 0.348111 -0.0243383 -0.01999998 0.348805 -0.0253542 -0.01999998 0.350806 -0.0276618 -0.01999998 0.350376 -0.02722668 -0.01999998 0.351704 -0.02849805 -0.01999998 0.351248 -0.02808618 -0.01999998 0.3529251 -0.02949494 -0.01999998 0.352174 -0.0288977 -0.01999998 0.353654 -0.03002965 -0.01999998 0.3549381 -0.0308842 -0.01999998 0.354169 -0.03038549 -0.01999998 0.357823 -0.03248953 -0.01999998 0.3589167 -0.03301435 -0.01999998 0.3601273 -0.03354692 -0.01999998 0.361053 -0.0339297 -0.01999998 0.3619409 -0.03427851 -0.01999998 0.3633238 -0.03478574 -0.01999998 0.3645123 -0.03519642 -0.01999998 0.3662269 -0.03574901 -0.01999998 0.3676399 -0.03617709 -0.01999998 0.3697938 -0.03679454 -0.01999998 0.371237 -0.03718459 -0.01999998 0.495241 -0.03034007 -0.01999998 0.495241 -0.03060024 -0.02034616 0.495241 -0.03060024 -0.01999998 0.495143 -0.03330469 -0.02333986 0.495124 -0.03382086 -0.02378308 0.495023 -0.03659635 -0.01999998 0.495241 -0.03060024 -0.01999998 0.495241 -0.03060024 -0.02034616 0.495226 -0.03100425 -0.02088487 0.495211 -0.03142708 -0.02140766 0.495195 -0.03186845 -0.0219146 0.495178 -0.03232848 -0.02240556 0.495161 -0.03280729 -0.02288067 0.495104 -0.0343557 -0.02421045 0.495085 -0.03489577 -0.02461856 0.495065 -0.03544926 -0.02500945 0.495044 -0.03601616 -0.02538305 0.495023 -0.03659635 -0.02573937 0.495023 -0.03659635 -0.01999998 0.495023 -0.03659635 -0.02573937 0.486007 -0.03626859 -0.02635806 0.477035 -0.03594249 -0.01999998 0.477035 -0.03594249 -0.0269888 0.476985 -0.03732585 -0.02770036 0.476959 -0.03802925 -0.028023 0.477035 -0.03594249 -0.01999998 0.477035 -0.03594249 -0.0269888 0.47701 -0.03663027 -0.02735567 0.476933 -0.03874045 -0.02832347 0.476744 -0.04393714 -0.01999998 0.476907 -0.03945946 -0.02860176 0.476881 -0.04018628 -0.02885788 0.476854 -0.04092085 -0.02909189 0.476827 -0.04166328 -0.02930366 0.4768 -0.04241335 -0.02949327 0.476772 -0.0431714 -0.02966076 0.476744 -0.04393714 -0.02980619 -0.07699996 -0.01372468 -0.03849995 -0.05899995 -0.01322466 -0.03849995 -0.07699996 -0.01322466 -0.03849995 -0.05899995 -0.01372468 -0.03849995 -0.07699996 -0.01322466 0 -0.05899995 -0.01322466 -0.03849995 -0.05899995 -0.01322466 0 -0.07699996 -0.01322466 -0.03849995 0.02414858 -0.04573005 -0.037 0.02414858 -0.04573005 -0.0451222 0.02446359 -0.03231519 -0.04511183 0.02490395 -0.01355636 -0.0417003 0.02491068 -0.01327198 -0.04132556 0.02489686 -0.0138579 -0.04205805 0.02488934 -0.01417636 -0.04239875 0.02488148 -0.01451528 -0.0427252 0.02487319 -0.01486879 -0.04303258 0.02486449 -0.01523607 -0.04332047 0.02485549 -0.01562005 -0.0435906 0.02472841 -0.0210337 -0.04510277 0.02484619 -0.01601707 -0.04384046 0.02483659 -0.01642459 -0.04406869 0.02482676 -0.01684427 -0.04427587 0.02481669 -0.01727586 -0.0444619 0.02480638 -0.01771426 -0.04462414 0.02477437 -0.01907557 -0.04496717 0.02476358 -0.01953697 -0.04503619 0.02475267 -0.0200023 -0.04506659 0.02479588 -0.01815968 -0.04476279 0.02478516 -0.01861649 -0.04487597 0.02492249 -0.01276588 -0.04054015 0.02491676 -0.01300889 -0.04093939 0.0249325 -0.01234066 -0.03970408 0.02492779 -0.01254236 -0.04012715 0.02494037 -0.01200497 -0.03883087 0.02493667 -0.01216197 -0.03927266 0.02494609 -0.01176089 -0.03792709 0.02494359 -0.0118705 -0.03838056 0.02494955 -0.01161187 -0.037 0.02494817 -0.0116747 -0.03746688 -0.127851 -0.04216158 -0.037 -0.1217679 -0.04230439 -0.0477429 -0.127851 -0.04216158 -0.04755616 -0.115684 -0.04244714 -0.04790598 -0.103519 -0.04273277 -0.04816108 -0.109601 -0.04258996 -0.04804527 -0.09135437 -0.0430184 -0.04832148 -0.09743648 -0.04287558 -0.04825305 -0.07919108 -0.04330396 -0.04838716 -0.08527261 -0.04316115 -0.04836606 -0.06702899 -0.04358947 -0.0483582 -0.07310986 -0.04344666 -0.04838448 -0.05486816 -0.04387497 -0.04823446 -0.06094837 -0.04373228 -0.04830807 -0.04270845 -0.04416048 -0.04801607 -0.04878818 -0.04401767 -0.04813706 -0.03055 -0.04444587 -0.04770296 -0.03662908 -0.04430317 -0.04787135 -0.01839256 -0.04473125 -0.04729515 -0.0244711 -0.04458856 -0.04751086 -0.006236493 -0.0450167 -0.04679268 -0.01231437 -0.04487395 -0.04705578 -1.58877e-4 -0.04515939 -0.04650586 0.02414858 -0.04573005 -0.037 0.01199549 -0.04544478 -0.04586136 0.005918443 -0.04530209 -0.04619544 0.01807218 -0.04558736 -0.04550355 0.02414858 -0.04573005 -0.04512214 -0.127851 -0.04216158 -0.037 -0.127063 -0.008590996 -0.03763419 -0.127053 -0.008151113 -0.037 -0.127074 -0.009048998 -0.03825169 -0.127097 -0.0100193 -0.03943639 -0.127085 -0.00952512 -0.03885239 -0.127121 -0.01106178 -0.04055416 -0.127109 -0.01053148 -0.04000365 -0.127147 -0.01217645 -0.04160505 -0.127134 -0.01161009 -0.04108798 -0.127175 -0.01336216 -0.04258757 -0.127161 -0.01276099 -0.04210537 -0.127204 -0.01460075 -0.04348486 -0.1271899 -0.01397389 -0.04304587 -0.1272349 -0.01590049 -0.04430437 -0.127219 -0.01524299 -0.0439043 -0.127299 -0.01863896 -0.04567986 -0.127283 -0.01793748 -0.04536926 -0.12725 -0.01657056 -0.04468315 -0.127384 -0.02227646 -0.04688805 -0.127581 -0.03066259 -0.04758638 -0.1274994 -0.02717542 -0.04757356 -0.12735 -0.02079987 -0.04647535 -0.127333 -0.02007424 -0.04623448 -0.12742 -0.02378159 -0.04720729 -0.127402 -0.02302747 -0.04705977 -0.1275449 -0.02912527 -0.04762369 -0.1275269 -0.02835845 -0.047616 -0.1274549 -0.02529466 -0.04742825 -0.1274369 -0.02453589 -0.04732978 -0.1274729 -0.02605807 -0.04750287 -0.1275629 -0.02989327 -0.04761385 -0.127367 -0.0215339 -0.0466932 -0.1273159 -0.01935249 -0.04596865 -0.127266 -0.01724809 -0.04503709 -0.1275998 -0.03146523 -0.04757505 -0.127851 -0.04216158 -0.04755616 -0.137849 -0.04192686 -0.037 -0.1378483 -0.04192692 -0.04673337 -0.1375592 -0.0296052 -0.04676008 -0.137409 -0.02320373 -0.04614835 -0.137538 -0.0287016 -0.04675197 -0.137344 -0.02043199 -0.04538989 -0.137361 -0.02117049 -0.04563415 -0.137436 -0.02435219 -0.04637575 -0.1374662 -0.02583491 -0.04661256 -0.137453 -0.02508687 -0.04650247 -0.137379 -0.0219298 -0.04585486 -0.137327 -0.01970165 -0.04512208 -0.13731 -0.01897948 -0.04483067 -0.137293 -0.01826548 -0.04451584 -0.137277 -0.01757568 -0.04418766 -0.137246 -0.01625877 -0.04348474 -0.137261 -0.01690906 -0.04384535 -0.137217 -0.01500737 -0.04270857 -0.1372309 -0.01562488 -0.0431059 -0.137188 -0.01377928 -0.04183506 -0.137202 -0.01439517 -0.04228675 -0.137159 -0.0125702 -0.04086178 -0.1371729 -0.01317089 -0.04136008 -0.137132 -0.01139926 -0.03980147 -0.137145 -0.01197695 -0.04034018 -0.137107 -0.01035076 -0.03872007 -0.1371189 -0.01086467 -0.0392673 -0.137085 -0.009384751 -0.03758645 -0.137096 -0.009857475 -0.03815978 -0.1370739 -0.008932709 -0.037 -0.18638 -0.04078745 -0.037 -0.178954 -0.0409618 -0.04103797 -0.182669 -0.0408746 -0.04036676 -0.137849 -0.04192686 -0.037 -0.175235 -0.04104906 -0.04168355 -0.18638 -0.04078745 -0.03966999 -0.167787 -0.041224 -0.04289805 -0.171513 -0.0411365 -0.04230356 -0.164058 -0.0413115 -0.04346698 -0.160324 -0.04139918 -0.0440104 -0.156588 -0.04148685 -0.04452806 -0.152847 -0.04157465 -0.04502028 -0.149103 -0.04166257 -0.04548686 -0.145355 -0.04175055 -0.045928 -0.141604 -0.0418387 -0.0463435 -0.137849 -0.04192686 -0.04673337 -0.1731538 -0.03004193 -0.04199999 -0.1720287 -0.02695149 -0.04199999 -0.17264 -0.02795809 -0.04199999 -0.173117 -0.02955257 -0.04199999 -0.1729969 -0.02889597 -0.04199999 -0.172897 -0.028575 -0.04199999 -0.172779 -0.02826279 -0.04199999 -0.1730729 -0.02922105 -0.04199999 -0.172484 -0.0276615 -0.04199999 -0.172313 -0.02737385 -0.04199999 -0.171623 -0.02643811 -0.04199999 -0.1731629 -0.03055417 -0.04199999 -0.171177 -0.02594697 -0.04199999 -0.1707112 -0.02549213 -0.04199999 -0.1731539 -0.03088897 -0.04199999 -0.170313 -0.02513688 -0.04199999 -0.1697911 -0.02470552 -0.04199999 -0.1691043 -0.02419257 -0.04199999 -0.1685856 -0.02383327 -0.04199999 -0.1680314 -0.02347218 -0.04199999 -0.1674814 -0.02313405 -0.04199999 -0.1667155 -0.02268987 -0.04199999 -0.1658062 -0.02219861 -0.04199999 -0.1647998 -0.02169191 -0.04199999 -0.1636114 -0.02113598 -0.04199999 -0.1625528 -0.02067327 -0.04199999 -0.1616243 -0.0202884 -0.04199999 -0.1606552 -0.01990574 -0.04199999 -0.1597398 -0.01956039 -0.04199999 -0.1586081 -0.01915222 -0.04199999 -0.157323 -0.01871317 -0.04199999 -0.156547 -0.01845979 -0.04199999 -0.1496199 -0.007950723 -0.03373789 -0.1470659 -0.01136398 -0.03299999 -0.149294 -0.008387029 -0.03445827 -0.148602 -0.00931096 -0.03584688 -0.148954 -0.008840441 -0.03516125 -0.1478599 -0.01030325 -0.0371657 -0.148237 -0.009798526 -0.03651499 -0.1470659 -0.01136398 -0.03841465 -0.147469 -0.01082509 -0.03779888 -0.1499339 -0.007531523 -0.03299999 -0.146925 -0.007240295 -0.03299999 -0.1470659 -0.01136398 -0.03299999 -0.1499339 -0.007531523 -0.03299999 -0.14089 -0.006741702 -0.03299999 -0.1439099 -0.006977021 -0.03299999 -0.1525961 -0.01550263 -0.01212263 -0.1519142 -0.01499241 -0.01198321 -0.173354 -0.03103828 -4.48598e-4 -0.173367 -0.03104835 0 -0.188 -0.04199999 0 -0.176463 -0.03336524 -0.04143667 -0.18638 -0.04078745 -0.037 -0.1814348 -0.0370863 -0.04056727 -0.1561339 -0.01815068 -0.01249426 -0.1470659 -0.01136398 -0.03299999 -0.1547127 -0.01708674 -0.01241469 -0.1554201 -0.01761645 -0.01246583 -0.1593295 -0.02054262 -0.01234126 -0.1568456 -0.01868331 -0.01250004 -0.1575495 -0.01921004 -0.01248335 -0.1600399 -0.02107387 -0.01224374 -0.1687434 -0.02758806 -0.008637249 -0.169174 -0.02791035 -0.008284926 -0.1668069 -0.02613866 -0.009933054 -0.1674967 -0.02665472 -0.009518265 -0.1584465 -0.01988154 -0.01243102 -0.163517 -0.02367663 -0.01140159 -0.1731539 -0.03088897 -0.04199999 -0.1372675 -0.004030704 -0.02307444 -0.137709 -0.004360854 -0.02635645 -0.1378549 -0.004470586 -0.0269314 -0.137328 -0.004076242 -0.02400755 -0.14089 -0.006741702 -0.03299999 -0.140561 -0.006495237 -0.03255856 -0.138203 -0.00473082 -0.0280478 -0.13802 -0.00459367 -0.02749347 -0.139652 -0.005815327 -0.03116238 -0.139371 -0.00560522 -0.03067088 -0.138858 -0.005220711 -0.02965569 -0.139106 -0.005406916 -0.03016859 -0.138625 -0.005046665 -0.02913218 -0.139942 -0.006032049 -0.03163975 -0.138405 -0.004882037 -0.02859425 -0.137581 -0.004265427 -0.02577584 -0.137473 -0.004184544 -0.0251916 -0.1373839 -0.004118144 -0.02460348 -0.140244 -0.006258726 -0.03210514 -0.1696195 -0.02824324 -0.007892966 -0.1608965 -0.02171504 -0.01209497 -0.17327 -0.0309754 -0.001328289 -0.1731989 -0.03092265 -0.001759409 -0.173321 -0.0310139 -8.91373e-4 -0.1533007 -0.01603066 -0.01224344 -0.1540072 -0.01655924 -0.01234072 -0.137224 -0.00399816 -0.02160573 -0.1512119 -0.01446688 -0.01181429 -0.156547 -0.01845979 -0.04199999 -0.1505149 -0.01394504 -0.01162141 -0.155726 -0.01784557 -0.04182779 -0.1498209 -0.01342576 -0.01140165 -0.154911 -0.01723539 -0.04163259 -0.18638 -0.04078745 -0.03966999 -0.1484575 -0.01240575 -0.01088637 -0.1491338 -0.01291185 -0.01115727 -0.1477664 -0.01188814 -0.01057839 -0.154101 -0.01662945 -0.04141426 -0.153297 -0.01602774 -0.0411731 -0.1471388 -0.01141828 -0.01026707 -0.14859 -0.01250487 -0.03924238 -0.147825 -0.01193225 -0.03884005 -0.149361 -0.01308155 -0.03962165 -0.150137 -0.01366245 -0.03997796 -0.1470659 -0.01136398 -0.03841465 -0.150919 -0.01424747 -0.04031127 -0.151706 -0.01483678 -0.04062145 -0.152499 -0.01543015 -0.04090875 -0.1464486 -0.01090204 -0.009889483 -0.1372233 -0.003997683 -0.009718358 -0.1451965 -0.009964823 -0.009087264 -0.1458414 -0.01044785 -0.009519934 -0.144312 -0.009302973 -0.008411705 -0.1437007 -0.008845508 -0.007881522 -0.1431595 -0.008440434 -0.007352471 -0.1425991 -0.008020639 -0.006740808 -0.1418833 -0.007485091 -0.005815625 -0.142248 -0.007758259 -0.006307542 -0.141544 -0.007231533 -0.005307435 -0.172206 -0.03017967 -0.004584848 -0.172004 -0.03002798 -0.004951059 -0.141133 -0.006923556 -0.004587948 -0.141333 -0.007073044 -0.004952967 -0.140944 -0.006782352 -0.004212379 -0.140606 -0.006529092 -0.003431141 -0.140767 -0.006649494 -0.00382632 -0.173001 -0.03077465 -0.002604246 -0.17311 -0.03085577 -0.002184748 -0.172728 -0.03056985 -0.003425717 -0.172874 -0.0306794 -0.003017902 -0.172394 -0.03032004 -0.00420916 -0.1725659 -0.03044909 -0.003824114 -0.1716515 -0.02976465 -0.005523145 -0.171332 -0.02952557 -0.005984961 -0.1706817 -0.02903854 -0.006800651 -0.171088 -0.02934288 -0.00630778 -0.1701726 -0.02865719 -0.00735861 -0.188 -0.04199999 -0.037 -0.1680977 -0.02710467 -0.009114623 -0.1617834 -0.02237862 -0.01190066 -0.1662045 -0.02568769 -0.01026308 -0.1655331 -0.02518546 -0.01059377 -0.1648705 -0.02468919 -0.01088976 -0.1624556 -0.02288228 -0.0117262 -0.164206 -0.02419221 -0.01115489 -0.162997 -0.02328729 -0.01156795 -0.1372309 -0.004003345 -0.02221119 -0.144757 -0.009635627 -0.008763134 -0.1404629 -0.006422519 -0.003027319 -0.140336 -0.006327211 -0.002614021 -0.140224 -0.006243288 -0.002191305 -0.140129 -0.006172597 -0.001761317 -0.1400589 -0.006120085 -0.001329898 -0.137223 -0.003997325 0 -0.140008 -0.006081879 -8.92583e-4 -0.139976 -0.006057977 -4.49269e-4 -0.139963 -0.006048381 0 -0.08099997 -0.006209254 0 -0.07699996 -0.01322466 0 -0.06999999 -0.005724668 0 -0.05899995 -0.01322466 0 -0.05899995 -0.005724668 0 -0.08099997 -0.01372468 0 -0.07699996 -0.01372468 0 -0.08611798 -0.0058766 0 -0.08121776 0.002021253 0 -0.09634989 -0.00529021 0 -0.09242999 0.002245426 0 -0.09123456 -0.005570232 0 -0.111687 -0.004608035 0 -0.106576 -0.004809141 0 -0.103637 0.002447724 0 -0.101464 -0.005036532 0 -0.114838 0.002628147 0 -0.126033 0.002786695 0 -0.127013 -0.004162669 0 -0.116797 -0.004433274 0 -0.137223 -0.003997266 0 -0.1321189 -0.004066824 0 -0.1399616 0.002953171 0 -0.139963 -0.006048381 0 -0.1519888 -0.006048381 0 -0.121906 -0.004284799 0 -0.06999999 0.001775264 0 -0.08099997 -0.007091343 -0.0356847 -0.08099997 -0.007308065 -0.03633368 -0.08099997 -0.006179749 -0.02681154 -0.08099997 -0.01264488 -0.04418748 -0.08099997 -0.01317495 -0.04463517 -0.08099997 -0.01372468 0 -0.08099997 -0.01372468 -0.04506736 -0.08099997 -0.01164317 -0.04324507 -0.08099997 -0.01213419 -0.04372406 -0.08099997 -0.01071965 -0.04224038 -0.08099997 -0.01117169 -0.04275059 -0.08099997 -0.009874403 -0.04117327 -0.08099997 -0.01028728 -0.04171454 -0.08099997 -0.00841844 -0.03885167 -0.08099997 -0.009481072 -0.04061627 -0.08099997 -0.006183564 -0.02509373 -0.08099997 -0.007547676 -0.03697246 -0.08099997 -0.007810056 -0.03760099 -0.08099997 -0.006897389 -0.03502529 -0.08099997 -0.006205856 -0.02820795 -0.08099997 -0.006726324 -0.0343557 -0.08099997 -0.00621885 -0.03095519 -0.08099997 -0.006273746 -0.03163838 -0.08099997 -0.006452977 -0.03299206 -0.08099997 -0.00618714 -0.03026765 -0.08099997 -0.006178557 -0.029576 -0.08099997 -0.006351768 -0.03231739 -0.08099997 -0.006578028 -0.03367578 -0.08099997 -0.008103311 -0.03823226 -0.08099997 -0.00875312 -0.03945547 -0.08099997 -0.009107291 -0.04004365 -0.08099997 -0.006212234 -0.0235024 -0.08099997 -0.006209313 0 -0.07699996 -0.01372468 -0.03849995 -0.07699996 -0.01372468 0 -0.08099997 -0.01372468 0 -0.05899995 -0.01372468 -0.03849995 -0.0632494 -0.01372468 -0.04502087 -0.05899995 -0.01372468 -0.04495298 -0.08099997 -0.01372468 -0.04506736 -0.06757408 -0.01372468 -0.04506629 -0.07197409 -0.01372468 -0.04508918 -0.07644939 -0.01372468 -0.04508948 -0.2005783 -0.04645574 -0.037 -0.188 -0.04199999 -0.037 -0.200577 -0.04199999 -0.037 0.1778039 -0.01959508 -0.037 0.177106 -0.04932105 -0.037 0.182874 -0.0202589 -0.037 0.226821 -0.05648988 -0.037 0.226821 -0.05048829 -0.037 0.187104 -0.04955577 -0.037 0.03414589 -0.04596477 -0.037 0.02494955 -0.01161187 -0.037 0.02414858 -0.04573005 -0.037 0.03494948 -0.01173305 -0.037 0.187776 -0.02093738 -0.037 -0.132197 -0.008513391 -0.037 -0.127053 -0.008151113 -0.037 -0.129658 -0.008325159 -0.037 -0.127851 -0.04216158 -0.037 -0.137849 -0.04192686 -0.037 -0.1370739 -0.008932709 -0.037 -0.134669 -0.008715927 -0.037 -0.18638 -0.04078745 -0.037 0.05217999 0.00170803 -0.06499999 0.001036822 0.001983463 -0.06499999 0.001563906 0.002535939 -0.06499999 0.08515024 0.01568228 -0.06499999 0.04823237 0.015473 -0.06499999 0.05330097 0.004225254 -0.06499999 0.005181014 0.00529474 -0.06499999 0.05353575 0.004485785 -0.06499999 0.00203365 0.002990484 -0.06499999 0.002518296 0.003425598 -0.06499999 0.05243277 0.002721428 -0.06499999 0.05405187 -0.00292772 -0.06499999 0.008289575 -0.004473805 -0.06499999 0.02746617 -0.00715965 -0.06499999 0.05626165 -0.003912329 -0.06499999 0.07340127 -0.008875906 -0.06499999 0.02371597 -0.006803333 -0.06499999 0.05592149 -0.003840088 -0.06499999 0.05289036 -0.00163716 -0.06499999 0.05271637 -0.00133568 -0.06499999 2.07427e-4 -7.8007e-4 -0.06499999 0.05232465 -3.65482e-4 -0.06499999 0.05243259 -6.98342e-4 -0.06499999 0.02951478 -0.007335007 -0.06499999 0.05214369 0.001361787 -0.06499999 6.43781e-4 0.001510858 -0.06499999 4.11485e-4 0.001190483 -0.06499999 0.05213117 0.001011312 -0.06499999 0.05232536 0.002390921 -0.06499999 0.05224084 0.002052128 -0.06499999 0.1334505 0.009352445 -0.06499999 0.05932438 0.005504608 -0.06499999 0.05900537 0.005646646 -0.06499999 0.05256426 0.003046512 -0.06499999 0.1276305 0.01036548 -0.06499999 0.1225015 0.01122057 -0.06499999 0.05834239 0.005862295 -0.06499999 0.05271685 0.003359436 -0.06499999 0.003538966 0.004231393 -0.06499999 0.05289179 0.00366193 -0.06499999 0.005913853 0.00572282 -0.06499999 0.05378615 0.004727602 -0.06499999 0.004351615 0.004778444 -0.06499999 0.007182061 0.0063892 -0.06499999 0.05405396 0.004952073 -0.06499999 0.05799949 0.00593537 -0.06499999 0.05765527 0.00598371 -0.06499999 0.118936 0.01178914 -0.06499999 0.05494099 0.005505919 -0.06499999 0.008387923 0.006974697 -0.06499999 0.05433648 0.005157291 -0.06499999 0.01074874 0.007988691 -0.06499999 0.0559231 0.00586313 -0.06499999 0.05525898 0.00564754 -0.06499999 0.05661028 0.005984008 -0.06499999 0.01318377 0.008908689 -0.06499999 0.02265149 0.01163709 -0.06499999 0.0569576 0.006008327 -0.06499999 0.0212143 0.01128756 -0.06499999 0.0169332 0.01012068 -0.06499999 0.01835459 0.01053059 -0.06499999 0.03941088 0.01456701 -0.06499999 0.09402525 0.01497143 -0.06499999 0.03648179 0.01418119 -0.06499999 0.02773708 0.01272922 -0.06499999 0.057307 0.006008148 -0.06499999 0.09105443 0.01523751 -0.06499999 0.04232794 0.0149073 -0.06499999 0.08809983 0.01547425 -0.06499999 0.08221197 0.01586008 -0.06499999 0.04526448 0.0152086 -0.06499999 0.0762816 0.01612502 -0.06499999 0.07924973 0.01600849 -0.06499999 0.05413538 0.01588374 -0.06499999 0.05118381 0.015697 -0.06499999 0.06150698 0.01618993 -0.06499999 0.07039934 0.01625615 -0.06499999 0.07333791 0.01620751 -0.06499999 0.05856239 0.01609498 -0.06499999 0.06742846 0.01627016 -0.06499999 0.06446427 0.01624822 -0.06499999 0.05634546 0.01599836 -0.06499999 0.09695398 0.01468282 -0.06499999 0.03063517 0.01326435 -0.06499999 0.03354835 0.01374685 -0.06499999 0.02553856 0.01228117 -0.06499999 0.02409327 0.01196706 -0.06499999 0.01978147 0.01091998 -0.06499999 0.01411318 0.009227156 -0.06499999 0.01551967 0.009685635 -0.06499999 0.05626296 0.00593537 -0.06499999 0.01195996 0.008461713 -0.06499999 0.05558735 0.005766868 -0.06499999 0.009546279 0.007488131 -0.06499999 0.05463117 0.00534147 -0.06499999 0.1130372 0.01267796 -0.06499999 0.115975 0.01224404 -0.06499999 0.05308705 0.00395143 -0.06499999 0.05867707 0.005766332 -0.06499999 0.003017842 0.00384128 -0.06499999 0.06047767 0.004726111 -0.06499999 0.06021016 0.004950821 -0.06499999 0.1392788 0.008302986 -0.06499999 0.05963116 0.00534147 -0.06499999 0.08463299 8.63139e-4 -0.06499999 0.05214357 6.61153e-4 -0.06499999 0.06096148 0.004225254 -0.06499999 0.06117719 0.003948807 -0.06499999 1.02307e-4 5.81977e-4 -0.06499999 0.05217999 3.1494e-4 -0.06499999 4.83647e-5 3.89483e-4 -0.06499999 0.164227 -3.50175e-4 -0.06499999 0.1640239 -5.27049e-4 -0.06499999 0.05730438 -0.003985464 -0.06499999 0.06135088 -0.009068489 -0.06499999 0.00542587 -0.003684937 -0.06499999 0.05353355 -0.002460777 -0.06499999 0.05695569 -0.003985464 -0.06499999 0.05660778 -0.003961026 -0.06499999 0.05525755 -0.00362426 -0.06499999 0.01232737 -0.005281269 -0.06499999 0.05463027 -0.00331813 -0.06499999 0.003921508 -0.003143966 -0.06499999 0.05330049 -0.002201914 -0.06499999 0.05433475 -0.003133416 -0.06499999 0.003195166 -0.002854228 -0.06499999 0.05308556 -0.0019266 -0.06499999 0.002323806 -0.002488672 -0.06499999 0.00186032 -0.00227642 -0.06499999 0.00151658 -0.002099454 -0.06499999 0.02043819 -0.006446957 -0.06499999 0.05558478 -0.00374335 -0.06499999 0.01360273 -0.00549966 -0.06499999 0.01508957 -0.00573498 -0.06499999 0.05493825 -0.003481924 -0.06499999 0.007525444 -0.004289448 -0.06499999 0.05378538 -0.002704143 -0.06499999 0.01102608 -0.005043268 -0.06499999 0.009433865 -0.004726648 -0.06499999 0.006750047 -0.004084885 -0.06499999 0.02203613 -0.006626427 -0.06499999 0.01885074 -0.00625509 -0.06499999 0.01695525 -0.006006658 -0.06499999 0.02551954 -0.006980478 -0.06499999 0.03211843 -0.007541775 -0.06499999 0.00608015 -0.00389111 -0.06499999 0.035115 -0.007757663 -0.06499999 0.03739696 -0.007909119 -0.06499999 0.0046705 -0.003424108 -0.06499999 0.0398854 -0.008063852 -0.06499999 0.04346138 -0.008268773 -0.06499999 0.001176476 -0.001889407 -0.06499999 8.57005e-4 -0.001642763 -0.06499999 0.05256295 -0.001020967 -0.06499999 0.04706484 -0.008456468 -0.06499999 5.83949e-4 -0.001367628 -0.06499999 0.04970145 -0.008583784 -0.06499999 4.04438e-4 -0.001128375 -0.06499999 0.05255818 -0.00871402 -0.06499999 2.98879e-4 -9.58109e-4 -0.06499999 1.31167e-4 -5.95034e-4 -0.06499999 3.02834e-5 -2.07627e-4 -0.06499999 7.08158e-5 -4.03727e-4 -0.06499999 0.05638736 -0.008876025 -0.06499999 0.05224025 -2.72721e-5 -0.06499999 1.163e-5 -8.50227e-6 -0.06499999 1.73199e-5 1.92036e-4 -0.06499999 0.06193715 -3.67822e-4 -0.06499999 0.06202155 -2.94072e-5 -0.06499999 0.07363599 0.001121282 -0.06499999 0.06632852 -0.009243428 -0.06499999 0.0701484 -0.0093683 -0.06499999 0.163838 -7.21834e-4 -0.06499999 0.07432973 -0.009496748 -0.06499999 0.06182938 -6.99361e-4 -0.06499999 0.05765336 -0.003961265 -0.06499999 0.07977002 -0.009653031 -0.06499999 0.08439826 -0.009134054 -0.06499999 0.16367 -9.31941e-4 -0.06499999 0.057998 -0.003912806 -0.06499999 0.06169825 -0.001023471 -0.06499999 0.163522 -0.001156926 -0.06499999 0.05834066 -0.003840088 -0.06499999 0.08577746 -0.00981307 -0.06499999 0.05867505 -0.003744184 -0.06499999 0.06154584 -0.001336097 -0.06499999 0.05900329 -0.003624796 -0.06499999 0.163394 -0.001393496 -0.06499999 0.09255832 -0.009982466 -0.06499999 0.05932229 -0.003482937 -0.06499999 2.11901e-4 8.45809e-4 -0.06499999 0.1632879 -0.001641571 -0.06499999 0.164676 -5.39444e-5 -0.06499999 0.164445 -1.91858e-4 -0.06499999 0.06137055 -0.001639366 -0.06499999 0.09914213 -0.01013696 -0.06499999 0.163205 -0.001896917 -0.06499999 0.06211876 0.001361787 -0.06499999 0.06213116 0.001011312 -0.06499999 0.163145 -0.002160131 -0.06499999 0.05962997 -0.003319323 -0.06499999 0.05992686 -0.003133952 -0.06499999 0.06117588 -0.001928091 -0.06499999 0.06096059 -0.002203345 -0.06499999 0.163109 -0.002426087 -0.06499999 0.06072705 -0.002462685 -0.06499999 0.1594455 0.004484593 -0.06499999 0.165171 1.57338e-4 -0.06499999 0.06047648 -0.00270462 -0.06499999 0.163097 -0.002695977 -0.06499999 0.163109 -0.002965688 -0.06499999 0.163145 -0.003231465 -0.06499999 0.06020838 -0.002929449 -0.06499999 0.163205 -0.003493249 -0.06499999 0.1632879 -0.003749728 -0.06499999 0.163394 -0.003996849 -0.06499999 0.16543 2.28923e-4 -0.06499999 0.1689866 0.002612531 -0.06499999 0.165695 2.76887e-4 -0.06499999 0.163521 -0.004234194 -0.06499999 0.1048238 -0.01026505 -0.06499999 0.163669 -0.004458725 -0.06499999 0.1659629 3.00996e-4 -0.06499999 0.163837 -0.004669249 -0.06499999 0.1112245 -0.01040464 -0.06499999 0.164023 -0.004864037 -0.06499999 0.166232 3.00864e-4 -0.06499999 0.1175776 -0.01053971 -0.06499999 0.1642259 -0.005040943 -0.06499999 0.164444 -0.005199611 -0.06499999 0.1665 2.76765e-4 -0.06499999 0.1646749 -0.005337297 -0.06499999 0.166765 2.28504e-4 -0.06499999 0.1250828 -0.01069617 -0.06499999 0.164918 -0.00545448 -0.06499999 0.167277 6.21365e-5 -0.06499999 0.167024 1.57009e-4 -0.06499999 0.168171 -5.2836e-4 -0.06499999 0.167968 -3.50733e-4 -0.06499999 0.1801147 3.96752e-4 -0.06499999 0.165169 -0.005548775 -0.06499999 0.168356 -7.22402e-4 -0.06499999 0.1654289 -0.005620658 -0.06499999 0.1351237 -0.01090151 -0.06499999 0.168672 -0.001157462 -0.06499999 0.1687999 -0.001395285 -0.06499999 0.168906 -0.001641988 -0.06499999 0.1931635 -0.002231538 -0.06499999 0.165693 -0.00566864 -0.06499999 0.169049 -0.00216037 -0.06499999 0.169085 -0.002426087 -0.06499999 0.1427667 -0.01105684 -0.06499999 0.169097 -0.002695977 -0.06499999 0.169085 -0.002965688 -0.06499999 0.165962 -0.005692899 -0.06499999 0.169049 -0.003231942 -0.06499999 0.1542596 -0.01129198 -0.06499999 0.168988 -0.003494739 -0.06499999 0.168905 -0.003750622 -0.06499999 0.166231 -0.005692899 -0.06499999 0.168799 -0.00399816 -0.06499999 0.1616851 -0.01144582 -0.06499999 0.1721915 -0.01166594 -0.06499999 0.168672 -0.004235267 -0.06499999 0.20626 -0.004884243 -0.06499999 0.168524 -0.004459679 -0.06499999 0.168355 -0.004670381 -0.06499999 0.16817 -0.004864513 -0.06499999 0.167967 -0.005041956 -0.06499999 0.167749 -0.00519973 -0.06499999 0.166499 -0.005668878 -0.06499999 0.167518 -0.005338072 -0.06499999 0.167276 -0.005454599 -0.06499999 0.184335 -0.01192432 -0.06499999 0.167023 -0.005549311 -0.06499999 0.166764 -0.005620777 -0.06499999 0.2214614 -0.007979094 -0.06499999 0.1980552 -0.01222193 -0.06499999 0.2046924 -0.01236426 -0.06499999 0.2273809 -0.009207367 -0.06499999 0.2105681 -0.01248836 -0.06499999 0.2317362 -0.01013779 -0.06499999 0.2153624 -0.01258641 -0.06499999 0.220247 -0.01267713 -0.06499999 0.224115 -0.01273512 -0.06499999 0.2360278 -0.01108062 -0.06499999 0.2275628 -0.01277118 -0.06499999 0.2305007 -0.01278275 -0.06499999 0.2388409 -0.01168459 -0.06499999 0.2327238 -0.0127772 -0.06499999 0.240234 -0.01199287 -0.06499999 0.2371227 -0.01274573 -0.06499999 0.241668 -0.01228529 -0.06499999 0.2443769 -0.01281756 -0.06499999 0.244664 -0.01282227 -0.06499999 0.2404814 -0.01274037 -0.06499999 0.243145 -0.01256167 -0.06499999 0.2435101 -0.0127682 -0.06499999 0.2420439 -0.01273047 -0.06499999 0.2428165 -0.01274085 -0.06499999 0.16775 -1.92885e-4 -0.06499999 0.168524 -9.33503e-4 -0.06499999 0.06169945 0.003043651 -0.06499999 0.06154638 0.003357529 -0.06499999 0.06182968 0.002721428 -0.06499999 0.06193786 0.002387881 -0.06499999 0.152433 0.005837738 -0.06499999 0.164918 6.28601e-5 -0.06499999 0.167519 -5.44214e-5 -0.06499999 0.168989 -0.001898825 -0.06499999 0.06208246 3.1494e-4 -0.06499999 0.1458579 0.007084786 -0.06499999 0.1101169 0.01309037 -0.06499999 0.1064902 0.01357567 -0.06499999 0.1028719 0.01402407 -0.06499999 0.09989035 0.01436823 -0.06499999 0.05992847 0.005155444 -0.06499999 0.06072884 0.00448352 -0.06499999 0.06137186 0.003660202 -0.06499999 0.06208235 0.00170803 -0.06499999 0.06202208 0.002050042 -0.06499999 0.06211876 6.61153e-4 -0.06499999 0.4180487 -0.04889041 -0.02578252 0.4333845 -0.04830771 -0.02480274 0.455 -0.05089128 -0.02344733 0.455 -0.04901546 -0.02338832 0.3713393 -0.07420569 -0.02828139 0.3702465 -0.07255637 -0.02865326 0.1876153 -0.02775812 -0.03905904 0.1956337 -0.02938407 -0.03861325 0.1778663 -0.01695144 -0.03388172 0.19629 -0.01774358 -0.03175276 0.4366748 -0.04979211 -0.02461284 0.3692884 -0.04521799 -0.02877652 0.3633065 -0.07112377 -0.02914094 0.4086511 -0.0674259 -0.02636921 0.2949997 -0.03929209 -0.03316158 0.288704 -0.03677284 -0.03349804 0.2239089 -0.08160728 -0.03709733 0.2268214 -0.06549638 -0.03700631 0.2422842 -0.08588951 -0.03510737 0.2422147 -0.08447539 -0.03563404 0.3532039 -0.08503174 -0.02218496 0.297504 -0.08829432 -0.02625775 0.3326483 -0.08691829 -0.02219772 0.1861323 -0.09095364 -0.03755027 0.2326647 -0.09153461 -0.03158295 0.2270686 -0.09206908 -0.03181529 0.229929 -0.09214776 -0.03124499 0.4229822 -0.0827313 -0.008961975 0.4322913 -0.08216249 -0.0098899 0.231898 -0.09220159 -0.03083056 0.2338629 -0.09225529 -0.03039526 0.251744 -0.09101688 -0.02932798 0.3489633 -0.08687931 -0.01544344 0.2511419 -0.09167516 -0.02808004 0.2368779 -0.0923376 -0.02967715 0.239605 -0.09241199 -0.02895915 0.2516039 -0.09211844 -0.02663874 0.2422375 -0.09248375 -0.02818042 0.3494075 -0.08680826 0 0.270228 -0.09134989 -0.02361869 0.2449005 -0.09255623 -0.02726262 0.2435657 -0.09251993 -0.02774369 0.251744 -0.09243607 -0.02495467 0.245822 -0.09258186 -0.02689397 0.246459 -0.09259915 -0.02661907 0.2748626 -0.09117418 0 0.2499773 -0.09270578 0 0.2472925 -0.09262096 -0.0262233 0.2716608 -0.09134769 -0.02128553 0.2479649 -0.09264016 -0.0258603 0.2485661 -0.09265649 -0.02548843 0.2708266 -0.09138709 -0.00395298 0.2489897 -0.09266829 -0.02518087 0.2492682 -0.0926758 -0.02494817 0.2495294 -0.09268289 -0.02468907 0.2497456 -0.09268742 -0.02441126 0.405201 -0.08365291 0 0.4190773 -0.08291256 -0.001789689 0.4550001 -0.08093231 0 0.2382381 -0.09237468 -0.02932858 0.3298735 -0.08758217 -0.02078199 0.4242402 -0.08229762 -0.01267319 0.2151063 -0.09174293 -0.03387367 0.233259 -0.09066736 -0.03257715 0.3363429 -0.08751827 -0.01851946 0.4343365 -0.08121633 -0.01365751 0.2230591 -0.09196066 -0.03255671 0.4550011 -0.07926034 -0.01384031 0.4549998 -0.07964819 -0.01295608 0.436536 -0.0790919 -0.01747077 0.2022984 -0.09139335 -0.03568035 0.2147729 -0.09006005 -0.03528535 0.3991203 -0.08238208 -0.01859736 0.3906276 -0.08185911 -0.02098625 0.1971256 -0.0912519 -0.0363205 0.455 -0.07868856 -0.01489454 0.4549997 -0.07768779 -0.01644819 0.436536 -0.07767379 -0.01925587 0.1912779 -0.09109228 -0.03699773 0.1862559 -0.08566945 -0.03911989 0.1959046 -0.08608275 -0.03848129 0.2423873 -0.08822202 -0.03375554 0.2612326 -0.0879786 -0.0318495 0.2981964 -0.0843864 -0.03057849 0.2610918 -0.08891385 -0.03091698 0.3166143 -0.08634853 -0.0262469 0.1861937 -0.08831977 -0.03868263 0.1957834 -0.08914411 -0.03760552 0.2145215 -0.09103685 -0.03450721 0.196202 -0.08351957 -0.0385791 0.3894678 -0.08371096 -0.01755678 0.1861597 -0.0897597 -0.03817796 0.4550002 -0.07641512 -0.01798009 0.436535 -0.07602179 -0.02082139 0.2791739 -0.08450442 -0.032444 0.3169131 -0.08537286 -0.02744036 0.455 -0.07538205 -0.01900082 0.3168976 -0.08428496 -0.0285266 0.4342232 -0.07434332 -0.02229076 0.4549997 -0.07389587 -0.02019393 0.2422636 -0.08272796 -0.0359897 0.3910121 -0.08062243 -0.02249056 0.1864657 -0.0767306 -0.03911668 0.2972842 -0.08180278 -0.0320698 0.4549998 -0.07215631 -0.02129286 0.422232 -0.07334381 -0.02406865 0.2970343 -0.07855248 -0.03293824 0.1986074 -0.0665068 -0.03845119 0.1865818 -0.07178753 -0.03911089 0.2609513 -0.07896834 -0.03506273 0.233046 -0.06986534 -0.03659856 0.391026 -0.07922029 -0.02384316 0.3724014 -0.07903581 -0.0261482 0.4549998 -0.06978702 -0.02236288 0.4289311 -0.07088351 -0.02436089 0.1867514 -0.06455576 -0.03910237 0.3532798 -0.07892978 -0.0281859 0.3901728 -0.07427072 -0.02668434 0.3531283 -0.07736772 -0.02886182 0.4328619 -0.06704515 -0.02480554 0.4163465 -0.07021719 -0.02558469 0.2547696 -0.0545628 -0.03540545 0.226821 -0.05048829 -0.037 0.1871036 -0.04955577 -0.03908473 0.2031186 -0.04993176 -0.0382663 0.2949994 -0.04127621 -0.03314417 0.1871992 -0.04547673 -0.03907865 0.1960824 -0.04587537 -0.03858566 0.2522185 -0.02294307 -0.03054761 0.249155 -0.02206677 -0.02999997 0.2332569 -0.02091968 -0.03063267 0.1872825 -0.04193127 -0.03907567 0.1873665 -0.03835773 -0.0390715 0.2281006 -0.04676026 -0.03687065 0.1874854 -0.0332998 -0.03906548 0.2558493 -0.03408014 -0.03534913 0.1876659 -0.02561068 -0.03892046 0.196289 -0.02678877 -0.03848677 0.196289 -0.02504467 -0.03813225 0.295 -0.03607195 -0.03317964 0.288704 -0.03445446 -0.03342688 0.196289 -0.02248018 -0.03704339 0.1877492 -0.02205973 -0.03771215 0.196289 -0.0236566 -0.03763645 0.241338 -0.03046333 -0.03607445 0.2243143 -0.02586704 -0.03614062 0.2239732 -0.02726709 -0.03665971 0.2609162 -0.03030902 -0.0346468 0.2612248 -0.0288521 -0.03412806 0.288704 -0.03113007 -0.03259897 0.288704 -0.03265428 -0.03309667 0.2950001 -0.03295356 -0.03271847 0.2949998 -0.02939337 -0.03115665 0.288703 -0.02851015 -0.03120118 0.288703 -0.02976155 -0.03196495 0.2704495 -0.02705037 -0.0322169 0.2278565 -0.02289903 -0.03388863 0.2246228 -0.02466911 -0.03551703 0.1778345 -0.01831221 -0.03578424 0.25174 -0.02372825 -0.03157997 0.2749998 -0.02594351 -0.03087556 0.270221 -0.02505177 -0.03046309 0.1969252 -0.02157229 -0.03640353 0.177804 -0.01958972 -0.03700608 0.182874 -0.0202589 -0.037 0.2615288 -0.02757716 -0.03348773 0.177877 -0.01648616 -0.03296738 0.1778527 -0.0175392 -0.03480404 0.2330985 -0.02036112 -0.02999836 0.214774 -0.01904118 -0.03061378 0.19629 -0.01726025 -0.03044569 0.210321 -0.01819068 -0.02999997 0.1778861 -0.01609438 -0.03200757 0.2201015 -0.01908308 -0.0300011 0.18959 -0.01646262 -0.02999985 0.2006734 -0.01735287 -0.03000128 0.1778935 -0.0157895 -0.03097915 0.177898 -0.01559758 -0.02999997 0.2181879 -0.02132141 -0.03356891 0.2899998 -0.02647364 -0.02935343 0.295 -0.02746164 -0.02967864 0.268542 -0.0243175 -0.02999997 0.29 -0.02712118 -0.02999997 0.270222 -0.02601158 -0.03141319 0.288703 -0.02738034 -0.03031909 0.275 -0.02511399 -0.02999997 0.2949999 -0.03111547 -0.03207534 0.295 -0.02647608 -0.02862 0.295 -0.02849137 -0.03052687 0.280212 -0.02647608 -0.03068405 0.285347 -0.02647608 -0.02999997 0.3931487 -0.04448938 -0.02723896 0.4126147 -0.04512691 -0.02600079 0.275 -0.02647608 -0.03134715 0.295 -0.03431844 -0.03300154 0.4003217 -0.04620856 -0.02688145 0.4130539 -0.04544126 -0.02599996 0.4132934 -0.04563897 -0.02599996 0.4135289 -0.04586672 -0.0259999 0.4137273 -0.04610866 -0.02599984 0.413897 -0.04643368 -0.02599996 0.413836 -0.04629075 -0.02599996 0.4139494 -0.04674035 -0.02599704 0.413936 -0.04658406 -0.02599996 0.413949 -0.04767167 -0.02599996 0.2499763 -0.09269684 -0.0238527 0.24987 -0.09269237 -0.02418845 0.249934 -0.09269416 -0.02402305 0.2409384 -0.09244841 -0.02857732 0.4549999 -0.08099251 -0.006686925 0.2352711 -0.09229391 -0.03006941 0.2191289 -0.09185266 -0.03322958 0.4549998 -0.08081603 -0.008733332 0.2071921 -0.09152674 -0.03502804 0.4549997 -0.08037567 -0.01087886 0.2111178 -0.09163391 -0.03447264 0.2239136 -0.08839619 -0.03548783 0.1863762 -0.08053594 -0.03912115 0.4549999 -0.06768494 -0.02299302 0.186217 -0.08731389 -0.03892177 0.3155946 -0.07883572 -0.03153711 0.3057255 -0.07564306 -0.03252887 0.4550001 -0.06580102 -0.02333456 0.4550002 -0.06335943 -0.02344816 0.2546007 -0.0632323 -0.03541588 0.3352701 -0.04259467 -0.03080409 0.226821 -0.05949068 -0.037 0.233258 -0.05675148 -0.03658747 0.1877089 -0.02378052 -0.038455 0.187776 -0.02093738 -0.037 0.262082 -0.02354407 -0.02999997 0.242688 -0.0213629 -0.02999997 0.25562 -0.02279376 -0.02999997 0.275 -0.02511399 -0.02999997 0.275 -0.0255444 -0.03047239 0.275 -0.02597606 -0.02999997 0.275 -0.02597606 0 0.275 -0.02147608 0 0.275 -0.02599847 -0.03092145 0.275 -0.02647608 -0.02999997 0.275 -0.02647608 -0.03134715 0.275 -0.02147608 -0.02999997 0.275 -0.02147608 0 0.283 -0.02147608 0 0.283 -0.02147608 -0.02999997 0.275 -0.02147608 -0.02999997 0.2830001 -0.01347833 0 0.283 -0.02147608 0 0.283 -0.02147608 -0.02999997 0.2830001 -0.01346111 -0.02153152 0.283 -0.01344305 -0.02999997 0.2315035 -0.01008766 -0.06499999 0.2319326 -0.01018112 -0.02999997 0.2319473 -0.01018375 -0.03390663 0.232012 -0.01019847 -0.03440785 0.232075 -0.01021218 -0.03460568 0.2322559 -0.01025187 -0.03497618 0.2331457 -0.01044672 -0.03594809 0.2328377 -0.01037907 -0.0356779 0.2325519 -0.01031666 -0.03538143 0.2334814 -0.01052075 -0.03620249 0.2397856 -0.0118978 -0.06499999 0.2338225 -0.01059579 -0.03643125 0.2341807 -0.01067477 -0.03664636 0.2345329 -0.01075243 -0.03683876 0.2349762 -0.01085007 -0.0370596 0.2355462 -0.01097524 -0.03731411 0.236172 -0.01111221 -0.03756499 0.2369518 -0.01128154 -0.03784179 0.2377174 -0.01144582 -0.03808248 0.2386842 -0.01165145 -0.03835415 0.2399343 -0.0119158 -0.03866189 0.24113 -0.0121687 -0.03892797 0.241886 -0.0123316 -0.03908467 0.242435 -0.01244366 -0.0391829 0.242989 -0.0125463 -0.03926014 0.2446637 -0.01282364 -0.06499999 0.244107 -0.01272535 -0.03936237 0.243547 -0.0126394 -0.03931826 0.244664 -0.01282227 -0.03942304 0.23237 -0.01027679 -0.03514796 0.232157 -0.01023006 -0.03479498 0.23197 -0.01018947 -0.03420579 0.2226198 -0.008212208 -0.02999997 0.2253627 -0.008779048 -0.06499999 0.2013241 -0.003881812 -0.06499999 0.1760515 0.001213192 -0.06499999 0.1823372 -4.36532e-5 -0.02999997 0.1575724 0.004850685 -0.06499999 0.1563851 0.005086779 -0.02999997 0.1431109 0.007602274 -0.06499999 0.1420239 0.007799267 -0.02999997 0.1276227 0.01037865 -0.06499999 0.1296911 0.01002216 -0.02999997 0.1177279 0.01198327 -0.02999997 0.1157874 0.01227831 -0.06499999 0.1105907 0.01302725 -0.02999997 0.1085857 0.01330119 -0.06499999 0.1019878 0.0141341 -0.06499999 0.1032325 0.01398938 -0.02999997 0.0959984 0.01478272 -0.02999997 0.09539514 0.01484262 -0.06499999 0.0887224 0.01543331 -0.06499999 0.08860296 0.01544636 -0.02999997 0.08130532 0.01591217 -0.02999997 0.08211427 0.01586896 -0.06499999 0.07529056 0.01616203 -0.02999997 0.07469052 0.0161854 -0.06499999 0.06726539 0.01628476 -0.02999997 0.06736272 0.01627415 -0.06499999 0.06160819 0.01619672 -0.06499999 0.05115681 0.01569944 -0.06499999 0.05186706 0.01574754 -0.02999997 0.05856472 0.01610422 -0.02999997 0.05640792 0.0160048 -0.06499999 0.04073673 0.01473194 -0.06499999 0.04594528 0.01527523 -0.06499999 0.04587876 0.01527279 -0.02999997 0.03922796 0.01455259 -0.02999997 0.03502541 0.0139774 -0.06499999 0.03327286 0.01370769 -0.02999997 0.03062766 0.0132634 -0.06499999 0.02806973 0.01280057 -0.02999997 0.02613812 0.01241588 -0.06499999 0.02264565 0.01164621 -0.02999997 0.02050393 0.0111202 -0.06499999 0.01746731 0.01028972 -0.02999997 0.01625221 0.009918689 -0.06499999 0.01285803 0.008799433 -0.06499999 0.01337242 0.008980035 -0.02999997 0.01003199 0.007713377 -0.02999997 0.01017439 0.007757961 -0.06499999 0.007792651 0.00669825 -0.06499999 0.007128059 0.006381511 -0.02999997 0.005078315 0.005252957 -0.06499999 0.004709005 0.005043387 -0.02999997 0.002804338 0.003686964 -0.06499999 0.003484189 0.004206717 -0.02999997 0.002079129 0.00305289 -0.02999997 0.001102805 0.002067863 -0.06499999 0.001109004 0.002061963 -0.02999997 1.07624e-5 -3.95715e-7 -0.04424482 6.38278e-6 2.94832e-6 -0.04501414 0.227903 -0.01277261 -0.04192978 0.2228631 -0.01271808 -0.04255157 0.219591 -0.01266539 -0.0429216 0.2168855 -0.01261562 -0.04321348 0.2136694 -0.01255238 -0.04354852 0.2173073 -0.01262843 -0.06499999 0.2093964 -0.01246374 -0.04397648 0.2053228 -0.01237756 -0.04436981 0.2014822 -0.0122956 -0.04472935 0.1974292 -0.01220828 -0.04509705 0.1940681 -0.01213538 -0.04539346 0.1904866 -0.01205754 -0.04570162 0.1916087 -0.01208198 -0.06499999 0.179242 -0.01181548 -0.04661929 0.1669588 -0.01155596 -0.04754251 0.1488204 -0.0111804 -0.04876655 0.1446434 -0.01109516 -0.04902648 0.1406203 -0.01101326 -0.04926967 0.1367527 -0.01093465 -0.04949659 0.1326984 -0.01085209 -0.04972755 0.1273037 -0.01074177 -0.05002439 0.121545 -0.01062268 -0.05032658 0.1186274 -0.01056438 -0.06499999 0.1159441 -0.01050525 -0.05060833 0.1091398 -0.01035958 -0.050933 0.1036325 -0.01023846 -0.05118209 0.09628194 -0.01007217 -0.06499999 0.09928721 -0.01014024 -0.05137091 0.09365552 -0.01000869 -0.0516057 0.08672279 -0.009837508 -0.05187892 0.08045369 -0.009674906 -0.06499999 0.07936608 -0.009642183 -0.05215144 0.07345098 -0.009470343 -0.05235695 0.06868672 -0.009322643 -0.06499999 0.06725192 -0.009275674 -0.05256247 0.05857449 -0.008966565 -0.06499999 0.06013506 -0.00902301 -0.05278438 0.05459946 -0.008802473 -0.05294895 0.04695999 -0.008457481 -0.06499999 0.04968696 -0.008583962 -0.0530883 0.04340666 -0.00826776 -0.05325669 0.03702682 -0.007890522 -0.06499999 0.03779774 -0.007935941 -0.05339288 0.03447908 -0.007713317 -0.05346441 0.0314691 -0.007492482 -0.05352181 0.0302428 -0.007397472 -0.06499999 0.02837818 -0.00723946 -0.05356889 0.02570176 -0.006999254 -0.06499999 0.02559894 -0.006988763 -0.05359923 0.02287137 -0.006715953 -0.05361312 0.02119755 -0.006538629 -0.06499999 0.02023339 -0.00642389 -0.05360788 0.01792657 -0.006137073 -0.05358111 0.01694321 -0.006007134 -0.06499999 0.01602727 -0.005875408 -0.05353963 0.01284641 -0.005379438 -0.06499999 0.01453608 -0.005649805 -0.05349016 0.01331484 -0.005451917 -0.05343788 0.01210761 -0.005242288 -0.05337256 0.01102751 -0.005042791 -0.05330169 0.009930253 -0.004827737 -0.0532152 0.009235858 -0.004687607 -0.06499999 0.008910179 -0.004613637 -0.05311894 0.007868587 -0.004374444 -0.05299836 0.006751656 -0.004093468 -0.06499999 0.006761431 -0.004088878 -0.05283552 0.005947232 -0.00385034 -0.05268245 0.004787564 -0.003469526 -0.06499999 0.005264699 -0.003631412 -0.05253028 0.00446552 -0.00334984 -0.05231529 0.00382322 -0.003105461 -0.05211114 0.002425372 -0.002541363 -0.06499999 0.003305494 -0.00289905 -0.05192589 0.002789914 -0.002685844 -0.05172115 0.002262115 -0.002459466 -0.05148738 0.00180298 -0.002246558 -0.05125033 0.001481831 -0.002076566 -0.05104476 0.001129329 -0.001872658 -0.06499999 0.001273214 -0.001950323 -0.05088388 0.001080095 -0.001819074 -0.05070817 9.06818e-4 -0.001683592 -0.05051589 5.15527e-4 -0.001290261 -0.06499999 7.52466e-4 -0.001545369 -0.05030888 6.19159e-4 -0.001407504 -0.05008846 5.04947e-4 -0.001270532 -0.04985564 4.08044e-4 -0.001138091 -0.04961389 2.92186e-4 -9.49468e-4 -0.04924148 1.46168e-4 -6.64417e-4 -0.06499999 1.7897e-4 -7.17179e-4 -0.04871243 1.03483e-4 -5.15544e-4 -0.04816728 5.7132e-5 -3.47723e-4 -0.04761546 1.28042e-5 -8.10779e-5 -0.06499999 3.07137e-5 -2.08348e-4 -0.04703217 1.80985e-5 -1.0792e-4 -0.04647696 1.34915e-5 -3.80883e-5 -0.0458737 1.07963e-5 -9.56399e-6 -0.04544734 6.70957e-6 -1.26314e-7 -0.02999997 3.6095e-5 3.75756e-4 -0.06499999 5.85742e-5 4.47288e-4 -0.02999997 2.61326e-4 9.57913e-4 -0.02999997 3.62054e-4 0.001137793 -0.06499999 0.001096785 0.002072572 -0.02999997 0.001107037 0.002063632 -0.06499999 0.1528871 -0.01126378 -0.04850536 0.1639322 -0.01149159 -0.06499999 0.156626 -0.01134091 -0.0482589 0.1612648 -0.01143717 -0.04794347 0.1733363 -0.01169013 -0.0470727 0.185487 -0.01194936 -0.04611873 0.2262432 -0.01276093 -0.06499999 0.2258449 -0.01275503 -0.04219245 0.2298355 -0.01278173 -0.04166918 0.2315604 -0.01278454 -0.06499999 0.2315313 -0.01278162 -0.04142546 0.2330635 -0.0127747 -0.04119253 0.2360442 -0.0127514 -0.04071289 0.2372357 -0.01274603 -0.06499999 0.2395849 -0.01274168 -0.04014116 0.2408649 -0.01273834 -0.03992724 0.2426248 -0.01273018 -0.06499999 0.2419148 -0.01273047 -0.03974163 0.2425557 -0.012735 -0.03964161 0.2433136 -0.01275902 -0.03955155 0.2446637 -0.01282954 -0.06499999 0.2440514 -0.01279926 -0.03949093 0.244664 -0.01282095 -0.03942304 0.3456119 -0.01763701 -0.01999956 0.4179091 -0.02252703 0 0.3879886 -0.02056998 0 0.4087852 -0.02189606 -0.008857071 0.4423475 -0.02405136 -0.005556643 0.3629999 -0.01888334 0 0.318 -0.01582509 0 0.334 -0.01690888 0 0.317987 -0.01582419 -3.53221e-4 0.2396586 -0.01274174 -0.04012906 0.2652457 -0.01470476 -0.03882545 0.2330446 -0.0127747 -0.04119551 0.26877 -0.01591646 -0.03972053 0.3456118 -0.01760065 -0.02377814 0.3229072 -0.01608413 -0.02669811 0.2650712 -0.01302647 -0.03576827 0.2377107 -0.0114445 -0.03808045 0.2830004 -0.01346331 -0.01666057 0.31789 -0.01581746 -0.001044273 0.31795 -0.01582157 -7.01322e-4 0.312825 -0.01547294 -0.004996836 0.313174 -0.01549649 -0.004996955 0.3339999 -0.01689034 -0.01499998 0.317805 -0.01581168 -0.001382112 0.310205 -0.01529687 -0.004145622 0.310501 -0.01531678 -0.004330813 0.317697 -0.01580417 -0.001713931 0.317413 -0.01578468 -0.002351224 0.317566 -0.01579529 -0.002036452 0.317042 -0.01575934 -0.002942442 0.317238 -0.01577275 -0.002652823 0.316594 -0.01572865 -0.003476381 0.316827 -0.01574456 -0.003217756 0.316075 -0.01569324 -0.00394237 0.316342 -0.01571148 -0.00371927 0.315497 -0.01565384 -0.004331886 0.315792 -0.01567399 -0.004147529 0.314869 -0.01561129 -0.004637598 0.315188 -0.01563298 -0.004495501 0.314208 -0.01556646 -0.004851937 0.314543 -0.01558917 -0.004756033 0.313868 -0.01554346 -0.004923939 0.313522 -0.01551997 -0.004972577 0.312132 -0.01542627 -0.004924118 0.31179 -0.01540327 -0.00485152 0.311128 -0.01535874 -0.004636228 0.310809 -0.01533734 -0.004494369 0.311456 -0.01538085 -0.004755616 0.309924 -0.0152781 -0.003941535 0.309405 -0.01524347 -0.003475368 0.309656 -0.01526015 -0.003717243 0.308955 -0.01521337 -0.00293976 0.309171 -0.01522779 -0.003215491 0.308586 -0.01518875 -0.002348005 0.308761 -0.01520037 -0.002651035 0.283 -0.01347607 0 0.308433 -0.01517856 -0.002035677 0.308302 -0.01516985 -0.001711845 0.308194 -0.01516264 -0.001380205 0.30811 -0.0151571 -0.001041173 0.308049 -0.01515299 -6.96185e-4 0.308012 -0.01515054 -3.49953e-4 0.308 -0.01514977 0 -0.137519 -0.009264826 -0.05241376 -0.1570927 -0.009868264 -0.05021691 0.312476 -0.01544946 -0.004972517 0.3456118 -0.01765644 -0.02629745 0.3456282 -0.01774567 -0.02703219 0.255783 -0.01168417 -0.03197067 0.2319474 -0.01018446 -0.03391158 0.2355502 -0.01097601 -0.03731584 0.2349756 -0.01085001 -0.0370593 0.2319328 -0.01018005 -0.02999997 0.23197 -0.01018947 -0.03420579 0.232012 -0.01019847 -0.03440785 0.232157 -0.01023006 -0.03479498 0.232075 -0.01021218 -0.03460568 0.255784 -0.01189517 -0.03448325 0.23237 -0.01027679 -0.03514796 0.2322559 -0.01025187 -0.03497618 0.2325521 -0.01031666 -0.03538149 0.2328377 -0.01037907 -0.03567779 0.2331451 -0.01044672 -0.03594762 0.2334823 -0.01052087 -0.0362032 0.233823 -0.01059585 -0.03643161 0.2341828 -0.01067519 -0.03664761 0.2345334 -0.01075255 -0.03683906 0.2361705 -0.01111185 -0.03756439 0.2884412 -0.01398438 -0.03193098 0.23695 -0.01128125 -0.0378412 0.2830002 -0.01344031 -0.02999997 0.2384343 -0.01159864 -0.03828603 0.2396126 -0.01184797 -0.03858715 0.2674782 -0.0139178 -0.03720784 0.242435 -0.01244366 -0.0391829 0.2417077 -0.01229178 -0.0390523 0.242989 -0.0125463 -0.03926014 0.243547 -0.0126394 -0.03931826 0.244107 -0.01272535 -0.03936237 0.311358 -0.0166133 -0.03346204 0.3109607 -0.01592767 -0.03190362 0.232652 -0.01488405 -0.04334586 0.3121735 -0.01839768 -0.03598743 0.3117778 -0.01744335 -0.03480768 0.346173 -0.02008116 -0.03239154 0.1919293 -0.01208889 -0.04557931 0.2095209 -0.01344519 -0.04480326 0.2440741 -0.01280081 -0.03948891 0.240859 -0.0127384 -0.03992825 0.2425573 -0.01273584 -0.03964084 0.2433156 -0.01275944 -0.03955119 0.2419126 -0.01273065 -0.03974193 0.1451792 -0.01110607 -0.04899394 0.163273 -0.01308798 -0.04864597 0.140157 -0.01155757 -0.04955935 0.2370197 -0.01274603 -0.04055452 0.2315378 -0.01278162 -0.04142445 0.232653 -0.01371407 -0.0423153 0.2298232 -0.01278173 -0.04167091 0.2279062 -0.01277261 -0.04192936 0.2207521 -0.01268547 -0.04279309 0.2239194 -0.01273238 -0.04242646 0.1971657 -0.01220262 -0.04512065 0.228188 -0.09440088 -0.04505681 0.255787 -0.09430611 -0.04277968 0.232655 -0.09566497 -0.04408735 0.1861366 -0.01196342 -0.04606497 0.3401046 -0.09566831 -0.02696722 0.325154 -0.09640675 -0.02892005 0.186394 -0.01324278 -0.0469014 0.2716607 -0.08760428 -0.0434674 0.2326509 -0.01617777 -0.04421454 -0.06816768 -0.1116201 -0.01968449 -0.06815856 -0.11162 -0.01293259 -0.08970141 -0.1112083 -0.01360607 0.3133933 -0.08883661 -0.04008376 0.2617143 -0.09055262 -0.04375725 0.3136748 -0.08683061 -0.0406714 0.160568 -0.01142179 -0.0479933 0.2988809 -0.08562159 -0.04186153 0.5099999 -0.03361117 -0.02199721 0.4951542 -0.0329945 -0.02305972 0.5100001 -0.03251791 -0.020837 0.209519 -0.01472645 -0.04565906 0.209516 -0.01613998 -0.04635345 0.451693 -0.07796066 -0.03083616 0.4518369 -0.07533645 -0.03154665 0.4514267 -0.08053493 -0.02968549 0.4507614 -0.08295804 -0.02812594 0.4054441 -0.08400756 -0.03302645 0.1316933 -0.01083165 -0.04978436 0.140156 -0.01299506 -0.05007636 0.186392 -0.01462548 -0.04758656 0.486919 -0.08273488 -0.0230481 0.486922 -0.08045756 -0.02522957 0.5099999 -0.08367556 -0.01761066 0.486917 -0.0845465 -0.02059787 0.5099998 -0.03485524 -0.02312362 0.4950779 -0.03509289 -0.02476269 0.1256715 -0.01070821 -0.05011117 0.1192337 -0.01057451 -0.05044466 0.352855 -0.02943706 -0.03658378 0.353447 -0.02987807 -0.03660529 0.3399027 -0.02875328 -0.03768485 0.11704 -0.01142668 -0.05086767 0.5100001 -0.07809972 -0.02392482 0.5099999 -0.07970416 -0.02264493 0.232648 -0.02092945 -0.04576557 0.209514 -0.01770758 -0.04687237 0.232649 -0.01917397 -0.04544568 0.4497342 -0.08508902 -0.02623236 0.1132255 -0.01044744 -0.05074006 -0.08769696 -0.111264 -0.01181447 -0.08777809 -0.111262 -0.01200395 0.5099999 -0.03615689 -0.02410507 0.495023 -0.03659254 -0.0257464 0.4438948 -0.08710342 -0.02452486 0.1074502 -0.01032274 -0.0510106 0.4769848 -0.03732544 -0.02770519 0.186221 -0.03087532 -0.04833662 0.186386 -0.02010619 -0.04846608 -0.2900004 -0.04744893 -0.02199804 -0.2733673 -0.05704897 -0.0345841 -0.273366 -0.05924689 -0.03447568 0.51 -0.08157384 -0.02071028 0.09392118 -0.01147758 -0.05192327 0.5100001 -0.0376985 -0.02508223 0.5100002 -0.08276659 -0.01910173 0.3341823 -0.02944576 -0.03828406 0.355296 -0.03110069 -0.03662526 0.355931 -0.03147709 -0.036623 0.470484 -0.08715927 -0.01868867 0.468683 -0.0872159 -0.01901274 0.486915 -0.0858612 -0.01804387 0.1013228 -0.01018679 -0.05128371 0.117039 -0.01306205 -0.05122095 0.4770345 -0.03594052 -0.02698737 0.209513 -0.01947569 -0.04718565 0.2304275 -0.02302342 -0.04596126 0.486924 -0.07783597 -0.02698785 0.51 -0.0764231 -0.02501702 0.4175999 -0.07572001 -0.03425675 0.4056898 -0.07935184 -0.03475856 0.163271 -0.01458609 -0.0491631 -0.01448106 -0.1112309 0 0.3480197 -0.06936115 -0.03895092 0.09556609 -0.01005381 -0.05152708 0.3928706 -0.07789468 -0.03593313 -0.08787316 -0.111259 -0.01217907 0.08915352 -0.009899079 -0.0517854 0.5099998 -0.07171177 -0.02691453 0.486929 -0.072241 -0.02897524 0.209511 -0.02158939 -0.04723095 0.186387 -0.0179283 -0.04842036 0.2799677 -0.02850049 -0.04260921 0.3184281 -0.03206497 -0.03981566 0.4420855 -0.07355797 -0.03254163 0.4700499 -0.07099437 -0.03052312 0.3248592 -0.07103186 -0.04037272 0.3015226 -0.07010132 -0.04177433 0.0708 -0.01000589 -0.05256408 0.09475558 -0.01383262 -0.05200529 0.4769124 -0.03931283 -0.02855616 0.3457183 -0.08192396 -0.03898745 0.3222001 -0.08382141 -0.04044973 0.3595545 -0.03329795 -0.0365948 0.348376 -0.0324921 -0.0374158 0.233726 -0.07166188 -0.04554641 -0.08798575 -0.111256 -0.01234757 0.2915941 -0.05380451 -0.04239106 0.08198297 -0.009713232 -0.05205625 0.07692646 -0.009572625 -0.05223721 0.3712346 -0.06754606 -0.03748172 0.3608708 -0.03385496 -0.03657972 0.348376 -0.03481537 -0.03774034 0.3622134 -0.03437918 -0.03655785 0.210223 -0.02965778 -0.04708927 0.07107973 -0.01235359 -0.05267333 0.4768344 -0.04146403 -0.02926021 -0.04496008 -0.111675 -0.04226863 0.3650678 -0.03537768 -0.03649443 0.140154 -0.01468777 -0.0504173 0.2337015 -0.05120718 -0.04556047 0.2573211 -0.05403029 -0.04431891 0.07224351 -0.009433805 -0.05239778 0.3664911 -0.03582829 -0.0364561 0.348375 -0.03729397 -0.03805279 0.1637701 -0.01850563 -0.04952287 0.1408532 -0.01694601 -0.0504617 0.2553909 -0.04578244 -0.04440426 0.2331991 -0.04308611 -0.04563254 0.5099996 -0.04043704 -0.02633446 0.440814 -0.04525399 -0.03260529 0.3679309 -0.03626054 -0.03641492 0.06798553 -0.009298503 -0.05253809 -0.0218085 -0.1114272 -0.007000446 0.3693474 -0.03666615 -0.03637194 0.256337 -0.0278865 -0.04425877 0.2654532 -0.03387951 -0.04369813 0.4659892 -0.04394757 -0.03060793 0.325239 -0.03493696 -0.0395351 0.4742184 -0.04392725 -0.02999287 0.5099999 -0.04272723 -0.02702629 0.3112124 -0.04164326 -0.04094266 0.264926 -0.03680467 -0.0437684 0.3133769 -0.03906309 -0.04066437 0.4951912 -0.03196662 -0.022026 0.5099998 -0.03146475 -0.01945489 0.3711331 -0.03715783 -0.0363155 0.4556366 -0.04710966 -0.03172999 0.4767441 -0.04393535 -0.02981644 0.3359299 -0.03865653 -0.03908205 0.371503 -0.03949689 -0.03664875 0.1178233 -0.01537662 -0.05128496 0.3729318 -0.03763073 -0.03625589 0.51 -0.04501968 -0.02740359 0.2892788 -0.03380751 -0.04207509 0.375052 -0.03816413 -0.03618282 0.06368994 -0.009152531 -0.05267482 0.3793691 -0.03915929 -0.03602319 0.2449384 -0.03996008 -0.04499274 0.2139608 -0.04087758 -0.04669111 -0.08832055 -0.1112471 -0.01273024 0.234667 -0.03445929 -0.0456202 0.1166709 -0.03073275 -0.05128705 0.1172328 -0.04037833 -0.05121982 0.09395998 -0.03309577 -0.05203056 0.3884193 -0.04087769 -0.03564041 0.3819823 -0.04283362 -0.0363537 0.4617213 -0.0439791 -0.03092324 -0.08862519 -0.1112395 -0.01299005 -0.2889902 -0.06857985 -4.10739e-7 -0.29 -0.06699997 0 -0.29 -0.06699997 -1.94739e-4 0.4401503 -0.04412996 -0.0325002 0.0476737 -0.008852958 -0.05321049 0.05827426 -0.008951723 -0.05284088 0.05281144 -0.008725702 -0.05300039 0.001376211 -0.110968 -0.007197558 0.04884213 -0.008543193 -0.05311137 0.04567819 -0.008386194 -0.05319678 -0.08896958 -0.1112303 -0.01322764 -0.06812572 -0.01680403 -0.05779331 -0.1145254 -0.05791807 -0.05741858 -0.1842807 -0.05854678 -0.04898357 -0.2061305 -0.04674804 -0.04525697 0.04770243 -0.09003996 -0.05339646 0.02517116 -0.1018308 -0.05402433 -0.2051789 -0.05329942 -0.04547297 0.00281918 -0.1014887 -0.05487686 -0.2277452 -0.09720051 -0.02078753 -0.233425 -0.09620577 -0.02106189 -0.233638 -0.09609925 -0.02135878 -0.183584 -0.0620746 -0.04907029 -0.2876694 -0.07043343 6.3737e-6 -0.206413 -0.0585196 -0.04549628 -0.206422 -0.06113505 -0.04563146 -0.2291949 -0.05200856 -0.04216545 -0.1144636 -0.06762707 -0.05750137 -0.09134709 -0.06978958 -0.0580691 -0.04475754 -0.07795488 -0.05705213 -0.04468816 -0.08606588 -0.05711823 -0.06816416 -0.07764363 -0.05787974 -0.2338629 -0.09598881 -0.02164316 -0.183582 -0.06485718 -0.0490458 -0.1605432 -0.06843197 -0.05280584 -0.1374997 -0.06933879 -0.05584263 -0.1375819 -0.06105107 -0.05579364 -0.1604831 -0.07461071 -0.05272662 -0.183574 -0.07357817 -0.04893845 -0.183577 -0.0705831 -0.04898047 -0.183569 -0.08001166 -0.04882168 -0.183566 -0.08347505 -0.04843068 -0.206459 -0.07324057 -0.04647576 0.00137639 -0.103458 -0.05464559 -0.02180176 -0.101933 -0.05583494 -0.0199629 -0.0998615 -0.05600643 0.02453398 -0.1037819 -0.05373537 0.02453368 -0.105081 -0.05326747 0.00137633 -0.104902 -0.05416464 -0.160564 -0.0792582 -0.05262857 -0.183571 -0.07670569 -0.04888856 -0.02178382 -0.1114263 -0.04386323 -0.206535 -0.100745 -0.02389395 -0.1144708 -0.08138078 -0.05772876 -0.1374977 -0.07581526 -0.05588126 -0.229387 -0.09458029 -0.02898007 -0.229373 -0.09191399 -0.03331327 -0.206521 -0.09830886 -0.03188908 -0.286969 -0.07135885 0 -0.160562 -0.08266139 -0.05254828 -0.2387489 -0.09379792 -0.0247873 -0.2294009 -0.09629857 -0.02461677 -0.238241 -0.0940144 -0.02459418 -0.02180147 -0.10369 -0.05532544 -0.16056 -0.08617538 -0.05213397 -0.2341 -0.09587419 -0.02191495 -0.09132796 -0.09628748 -0.05760127 -0.0681675 -0.101567 -0.05640047 -0.09132677 -0.09926027 -0.05646419 -0.237272 -0.094433 -0.0241695 -0.2368093 -0.0946356 -0.02393656 -0.137521 -0.08061701 -0.05591595 -0.04498809 -0.10164 -0.05650728 -0.06816965 -0.09640359 -0.05798929 -0.04498887 -0.0994513 -0.05706077 -0.286316 -0.0721715 0 -0.09007942 -0.1111986 -0.01375442 -0.09132301 -0.111161 -0.01765656 -0.09128528 -0.08997809 -0.058501 -0.09132915 -0.09318017 -0.0582841 -0.114454 -0.08665579 -0.05785816 -0.2363359 -0.09484577 -0.02367198 -0.06816858 -0.09906738 -0.05737739 -0.285647 -0.07296431 0 -0.234349 -0.09575557 -0.02217429 -0.183553 -0.09928178 -0.0382508 -0.206513 -0.09595406 -0.0357846 -0.206504 -0.0928598 -0.03930938 -0.114452 -0.09017169 -0.0576092 -0.13752 -0.08415699 -0.05594128 -0.13752 -0.08776766 -0.05562686 -0.137529 -0.1086449 -0.03077214 -0.137518 -0.108369 -0.03483486 -0.1144426 -0.1102008 -0.03416091 -0.284962 -0.07373738 0 -0.114445 -0.109911 -0.03817445 -0.137518 -0.1074399 -0.03877735 -0.183551 -0.101301 -0.03480637 -0.09132963 -0.111159 -0.03727942 -0.06815892 -0.1116177 -0.04003554 -0.284262 -0.07449066 0 0.02453225 -0.110143 -0.04710096 0.02453237 -0.109682 -0.04851979 0.04767096 -0.109454 -0.04644978 -0.283546 -0.07522428 0 -0.0217995 -0.110601 -0.04854559 -0.0217998 -0.109835 -0.05014526 0.001376152 -0.110229 -0.04878455 0.00140345 -0.1109676 -0.044716 0.02451843 -0.1103794 -0.04472666 -0.0893293 -0.1112191 -0.01343095 -0.234609 -0.09563279 -0.022421 -0.282814 -0.07593816 0 -0.2519146 -0.04507327 -0.03838568 -0.1835449 -0.10377 -0.02367848 -0.1970962 -0.101971 -0.01930397 -0.203427 -0.101063 -0.0196107 -0.04498326 -0.111406 -0.04537135 0.07073026 -0.108907 -0.04304236 -0.282066 -0.07663226 0 -0.206542 -0.100979 -0.02011907 -0.281303 -0.07730668 0 0.0477057 -0.1096863 -0.04410278 -0.2802152 -0.07823747 -1.82245e-6 0.07079821 -0.108904 -0.006919443 0.04767173 -0.1096869 -0.007119059 0.08520221 -0.1083863 0 -0.04498505 -0.108557 -0.05166667 -0.04498445 -0.109775 -0.04983937 -0.06816446 -0.107856 -0.05134707 -0.206528 -0.09988868 -0.02786117 -0.09046459 -0.1111871 -0.01388025 -0.2733632 -0.08300763 -0.001290917 -0.160545 -0.10618 -0.03114396 -0.183547 -0.10354 -0.02737969 -0.183549 -0.102726 -0.03113436 -0.2786871 -0.07944875 1.81849e-7 -0.0449838 -0.110737 -0.04776257 -0.06816345 -0.109388 -0.04902315 -0.2770416 -0.08064967 0 -0.2350402 -0.09543251 -0.02278828 -0.2354429 -0.09524786 -0.02309286 -0.0217992 -0.111172 -0.04662674 -0.29 -0.04909169 -0.02189099 -0.273366 -0.06120836 -0.0342226 -0.273808 -0.08276891 1.74955e-7 -0.06816256 -0.110563 -0.04641538 -0.160546 -0.105309 -0.03500479 -0.160554 -0.0963484 -0.04765439 -0.183561 -0.09046596 -0.04601067 -0.160555 -0.09312421 -0.04969078 -0.2705506 -0.08459568 0 -0.160548 -0.103831 -0.03869634 -0.1605499 -0.101793 -0.04209715 -0.137518 -0.105892 -0.04249864 -0.273365 -0.06301635 -0.03385645 -0.29 -0.05047017 -0.0216974 -0.266865 -0.08642536 2.30437e-7 -0.1807349 -0.1041418 -0.01851093 -0.1612182 -0.1063629 -0.01960945 -0.1835629 -0.08699721 -0.04750555 -0.160557 -0.08969795 -0.05118668 -0.2641836 -0.08759647 1.01573e-6 -0.09220361 -0.1111348 -0.01420128 -0.2571529 -0.09027415 -0.001317679 -0.2597034 -0.08937919 0 -0.257153 -0.09027367 0 -0.0913214 -0.110004 -0.04448294 -0.06816178 -0.111336 -0.04350358 -0.2277452 -0.04200059 -0.04180532 0.001376152 -0.1107259 -0.04720807 -0.2571656 -0.09027534 -0.01268035 -0.2733618 -0.08301478 -0.009313464 -0.2900002 -0.06699913 -0.00248456 -0.25715 -0.09027338 -0.01328039 -0.273363 -0.08294969 -0.01128005 -0.09132045 -0.110869 -0.04108428 -0.257146 -0.09025228 -0.01389545 -0.2291781 -0.04466462 -0.04158842 -0.257153 -0.0902118 -0.01450777 0.08527046 -0.108313 -0.04356485 0.08523327 -0.1083469 -0.04317975 -0.257172 -0.09015178 -0.01511746 -0.257203 -0.09007245 -0.01572448 0.001376211 -0.109606 -0.05004125 -0.09132236 -0.108637 -0.04759538 -0.1834265 -0.0481683 -0.0491352 -0.257245 -0.0899738 -0.01632875 -0.0913245 -0.1046 -0.05283796 -0.09132337 -0.106817 -0.05039554 -0.114448 -0.102962 -0.05142205 -0.29 -0.06689935 -0.004091322 -0.273363 -0.08270239 -0.01339375 -0.1144469 -0.105453 -0.04863744 0.02453279 -0.1085 -0.05054277 0.001376211 -0.108884 -0.05110758 0.001376271 -0.108066 -0.05203539 -0.114446 -0.107484 -0.04545456 -0.137519 -0.103778 -0.0458973 -0.257299 -0.08985567 -0.0169304 -0.206496 -0.0891813 -0.04222667 -0.183556 -0.09673351 -0.04133147 -0.2359039 -0.09503901 -0.02340757 -0.2573965 -0.08963608 -0.01787 -0.183579 -0.06768518 -0.04901599 -0.2432017 -0.09200555 -0.02579087 -0.2438903 -0.09174662 -0.02585351 -0.29 -0.06695765 -0.003397166 -0.2447768 -0.09142154 -0.02590191 -0.257283 -0.08930206 -0.01937288 -0.257347 -0.08937716 -0.01900738 -0.257389 -0.08945798 -0.0186364 -0.257194 -0.0892322 -0.0197339 -0.06816649 -0.103894 -0.05506175 -0.06816548 -0.106009 -0.05336999 -0.0913257 -0.102055 -0.05487215 -0.09135025 -0.08104681 -0.05826067 -0.273363 -0.08223527 -0.01561635 -0.257079 -0.08916699 -0.02009189 -0.251958 -0.08748608 -0.02789068 -0.248746 -0.09011995 -0.02564078 -0.2492918 -0.08996415 -0.02554035 -0.29 -0.06681597 -0.004784107 -0.29 -0.06670761 -0.005476474 -0.2540951 -0.08898395 -0.02367103 -0.273364 -0.08151715 -0.01790708 -0.2521029 -0.08928638 -0.0247035 -0.2514245 -0.08942818 -0.02496051 -0.256405 -0.08897656 -0.02143245 -0.256187 -0.08894765 -0.02174127 -0.25487 -0.0889216 -0.02309828 -0.255158 -0.08891129 -0.02285259 -0.257405 -0.08954095 -0.01826798 -0.256944 -0.08910876 -0.02044057 -0.256785 -0.08905756 -0.02078068 -0.229243 -0.05948227 -0.04317766 -0.20644 -0.06671077 -0.0459823 -0.206449 -0.06978815 -0.04620826 -0.206431 -0.06385517 -0.04579216 -0.2292259 -0.05682927 -0.04278194 -0.2458553 -0.0910415 -0.02590888 -0.247667 -0.09044647 -0.02579128 -0.273364 -0.0745871 -0.02791368 -0.273364 -0.07626467 -0.02630519 -0.29 -0.0613752 -0.01588797 -0.29 -0.06465929 -0.01139199 -0.29 -0.06432068 -0.01200056 -0.273364 -0.07929825 -0.02240669 -0.273364 -0.0805335 -0.02019679 -0.251955 -0.08447396 -0.03153336 -0.2503666 -0.08967834 -0.0252875 -0.2425039 -0.09227305 -0.02570372 0.06259012 -0.1093068 0 0.02453255 -0.109126 -0.04962015 0.04767119 -0.108997 -0.04785728 0.08520156 -0.108376 -0.04198116 -0.114446 -0.108988 -0.0419442 -0.13752 -0.0913642 -0.05477017 -0.114451 -0.09361499 -0.05684417 -0.11445 -0.09694761 -0.05555605 -0.137519 -0.101173 -0.04888397 -0.0449866 -0.105459 -0.05459749 -0.04498577 -0.107109 -0.05325555 -0.02180075 -0.106595 -0.05376517 -0.02180039 -0.107822 -0.05273199 -0.2064869 -0.08516138 -0.04438889 -0.183558 -0.0937547 -0.04394167 -0.2377603 -0.09422069 -0.02439451 -0.2409414 -0.09289103 -0.02542078 -0.241804 -0.09254711 -0.02559185 -0.206468 -0.07703298 -0.04642587 -0.1606521 -0.05927056 -0.05287873 -0.1144589 -0.07461351 -0.05759781 -0.29 -0.06037229 -0.01686066 -0.273365 -0.07287609 -0.02928227 -0.04495203 -0.09232044 -0.05721366 -0.06847196 -0.09357666 -0.05820548 -0.206405 -0.05598127 -0.045385 0.00143212 -0.07963222 -0.05494552 -0.04452002 -0.06157833 -0.05697143 0.04181873 -0.008177161 -0.05329674 0.02453505 -0.008253991 -0.05393958 0.03894865 -0.008006572 -0.05336576 -0.06817179 -0.01115429 -0.05718797 -0.0449903 -0.009296715 -0.0564779 -0.04499286 -0.01143479 -0.05691707 0.03673893 -0.00786674 -0.05341643 -0.0912646 -0.0192542 -0.05801409 -0.1144118 -0.02138584 -0.05743932 -0.1845934 -0.03045076 -0.04893177 -0.1880005 -0.03299999 -0.04834806 0.03371089 -0.007659256 -0.05347996 -0.09133177 -0.01305437 -0.05736094 -0.09133565 -0.01595205 -0.05788975 -0.114455 -0.01470535 -0.05674356 -0.1604349 -0.03085643 -0.05291026 -0.114459 -0.0179373 -0.0573129 -0.137522 -0.01928907 -0.05567717 -0.114452 -0.01161557 -0.05573225 -0.09132736 -0.01033645 -0.05645465 -0.06816768 -0.008856177 -0.05639779 -0.1609082 -0.02357137 -0.05285257 0.03084099 -0.007442474 -0.05353206 -0.160582 -0.01968008 -0.05277138 -0.1375248 -0.0228036 -0.05579954 0.02792662 -0.007201015 -0.05357503 0.02564686 -0.00699228 -0.05359822 -0.1605809 -0.01609599 -0.05215638 -0.1723085 -0.02125585 -0.05102604 -0.16992 -0.01946854 -0.05129545 0.001376569 -0.006875991 -0.0544545 0.02398216 -0.006829798 -0.05360919 0.02233105 -0.006657838 -0.05361318 -0.1682086 -0.01818764 -0.05140423 -0.137521 -0.01581567 -0.05507785 -0.1628437 -0.01417243 -0.05126541 0.02068668 -0.006475687 -0.0536099 -0.04498738 -0.007415533 -0.05580157 -0.06816327 -0.006739616 -0.05532407 0.01877528 -0.006246089 -0.05359351 -0.1643537 -0.01530265 -0.05138081 -0.1612653 -0.01299124 -0.05107897 0.0168572 -0.005992889 -0.05356043 0.00137645 -0.005617082 -0.05394536 0.01494979 -0.005714893 -0.05350607 -0.13752 -0.01245278 -0.05398666 -0.1596655 -0.01179379 -0.05081194 -0.0681585 -0.004802823 -0.05398547 -0.0449841 -0.005715906 -0.05491518 -0.114439 -0.003596186 -0.05022525 -0.09131729 -0.005463719 -0.05358767 -0.114443 -0.006015419 -0.05245167 0.01332479 -0.005453586 -0.05343836 0.01211041 -0.005242764 -0.05337274 -0.1582307 -0.01072001 -0.05050778 0.01102864 -0.005043029 -0.05330181 -0.09131175 -0.003359317 -0.05166035 -0.09132248 -0.007799327 -0.05518949 0.00137633 -0.004538238 -0.05333429 -0.156077 -0.009108603 -0.0499227 0.009932696 -0.004828155 -0.05321538 -0.1551218 -0.00839293 -0.04960805 0.008920192 -0.004615843 -0.05311995 -0.1541815 -0.007689177 -0.04926604 -0.0681535 -0.003057837 -0.05238765 -0.0449807 -0.004174947 -0.05383348 0.007871329 -0.004375278 -0.05299866 -0.1532021 -0.006956219 -0.04887115 -0.137518 -0.006316125 -0.05038535 0.007054507 -0.00416702 -0.05288147 -0.1520245 -0.006075203 -0.04833948 -0.02179789 -0.003722369 -0.05332046 -0.0217995 -0.004918515 -0.05418109 0.006498336 -0.004013597 -0.05278831 -0.1509008 -0.005234062 -0.04776442 0.001376211 -0.003587663 -0.05262994 0.005950808 -0.003851413 -0.05268323 -0.04497706 -0.00278902 -0.0525586 -0.06814837 -0.001523673 -0.05053186 -0.0913062 -0.001519739 -0.04941695 -0.114434 -0.001494824 -0.04763507 -0.1144289 2.3826e-4 -0.04471069 0.004751801 -0.003453612 -0.05239689 -0.1500457 -0.004594743 -0.04728227 0.004084289 -0.003206431 -0.05219721 -0.1491857 -0.003950417 -0.04674857 -0.137517 -0.003671407 -0.04792827 -0.0913006 1.54963e-5 -0.04687088 -0.1483197 -0.003302395 -0.04616296 -0.02179616 -0.002650439 -0.05232387 -0.137223 0.002920866 -0.02726727 -0.1150671 0.002636194 0 0.003561973 -0.003002405 -0.05202001 -0.1475456 -0.002723217 -0.04558712 -0.04497337 -0.001563906 -0.05108517 -0.06814318 -2.27636e-4 -0.04841744 0.003047108 -0.002791047 -0.05182784 -0.114424 0.001542747 -0.04147905 -0.09170848 0.002232372 0 -0.146126 -0.001660764 -0.04439246 -0.137515 -0.001392364 -0.04507809 -0.1466992 -0.00208956 -0.04490286 0.002539217 -0.00257945 -0.05161356 -0.1455529 -0.00123161 -0.0438463 0.002027511 -0.002354383 -0.05137193 -0.1440641 -1.17139e-4 -0.04221034 -0.1375139 4.62996e-4 -0.04188305 -0.091295 0.001193165 -0.04402744 0.001704812 -0.002196371 -0.05119025 -0.02179437 -0.001697421 -0.05118215 0.001481831 -0.002076566 -0.05104476 -0.1447998 -6.68137e-4 -0.04306507 0.001080095 -0.001819074 -0.05070817 0.001273214 -0.001950323 -0.05088388 9.06818e-4 -0.001683592 -0.05051589 -0.1144199 0.002359807 -0.03797477 -0.09128957 0.001955509 -0.04088598 -0.06813806 7.88904e-4 -0.04603087 -0.1433926 3.84986e-4 -0.04134148 -0.02179259 -8.67243e-4 -0.04987585 6.19159e-4 -0.001407504 -0.05008846 7.52466e-4 -0.001545369 -0.05030888 -0.1427736 8.4801e-4 -0.0404275 -0.142048 0.001391112 -0.03918349 -0.06813305 0.001474678 -0.04333335 -0.04496598 3.32204e-4 -0.04747915 -0.02179086 -1.74663e-4 -0.04836237 -0.142328 0.001182138 -0.03968775 2.88907e-4 -9.45731e-4 -0.04923117 4.08044e-4 -0.001138091 -0.04961389 -0.1141346 0.002617597 -0.03421545 -0.09141415 0.002219736 -0.0373013 -0.141306 0.001946628 -0.03760504 -0.137513 0.00183463 -0.03839337 -0.141539 0.001772284 -0.03814375 1.76063e-4 -7.13128e-4 -0.04870104 -0.14109 0.002108514 -0.03705626 -0.140892 0.002256453 -0.03649979 -0.1401 0.002849698 -0.03299999 -0.137223 0.002855181 -0.03299999 -0.1401849 0.002785801 -0.03360235 -0.04496234 9.33647e-4 -0.04524189 -0.06795626 0.001726627 -0.04007548 -0.1405529 0.002510249 -0.03536379 -0.137512 0.002670526 -0.03467297 1.01378e-4 -5.11306e-4 -0.0481559 -0.140713 0.002390325 -0.03593558 -0.140289 0.002707958 -0.03419715 -0.140412 0.002616107 -0.03478437 -0.02178919 3.48501e-4 -0.04653668 5.53892e-5 -3.44076e-4 -0.0476011 -0.03767889 0.00100398 -0.04279613 -0.06999999 0.001773834 -0.02999997 2.11645e-5 -1.50295e-4 -0.04677325 -0.03555601 9.50086e-4 -0.02999997 1.04533e-5 -1.06609e-6 -0.04546767 1.06239e-5 4.61039e-7 -0.02999997 -0.04496967 -5.14195e-4 -0.04940205 -0.06999993 0.001777052 0 -0.137223 0.002925157 0 -0.276517 -0.04199975 -0.03339707 -0.275004 -0.04199999 -0.03399825 -0.277261 -0.04199969 -0.0330674 -0.02180105 -0.006255447 -0.05490607 -0.1662729 -0.01673895 -0.05144405 -0.02180248 -0.007773339 -0.05548429 -0.1144469 -0.008704423 -0.05429339 -0.1772957 -0.02498877 -0.0501846 -0.02180367 -0.00957942 -0.05588525 0.001376628 -0.00844419 -0.0548287 -0.06817537 -0.01367175 -0.05767154 -0.09138244 -0.05777078 -0.05798155 0.0962305 -0.09834641 -0.05195724 0.0707997 -0.100054 -0.0527116 0.07079958 -0.101925 -0.05242395 0.09496968 -0.09949284 -0.05189627 0.09281826 -0.101449 -0.05150973 0.07079946 -0.103285 -0.05195116 0.09170687 -0.1024604 -0.05115723 0.02453297 -0.107803 -0.05134665 0.001376271 -0.107145 -0.05284935 0.04767137 -0.108447 -0.04894858 -0.1028434 -0.1107141 -0.01472324 0.07079875 -0.108199 -0.04691314 0.0857008 -0.107922 -0.04541528 0.07079869 -0.108671 -0.04542875 0.08521395 -0.1083643 -0.04271513 -0.2469479 -0.0906825 -0.02586483 -0.251901 -0.0426293 -0.03839164 -0.2386975 -0.04200005 -0.04021728 -0.287212 -0.04200428 -0.02574259 -0.286655 -0.04200357 -0.02636307 -0.273366 -0.04504698 -0.03457695 -0.2899999 -0.04199981 -0.02199983 -0.273366 -0.0484367 -0.03457885 -0.2813351 -0.04199934 -0.0308358 -0.2591137 -0.03300005 -0.03756946 -0.255026 -0.0349937 -0.03799736 -0.255026 -0.03299999 -0.03799736 -0.2634658 -0.03299999 -0.03689026 -0.2663179 -0.03299969 -0.0363363 -0.2690175 -0.03300046 -0.03573077 -0.275004 -0.03599989 -0.03399807 -0.2750118 -0.03299975 -0.03402251 -0.255026 -0.04039388 -0.03799736 -0.2780472 -0.04199618 -0.03269386 -0.275764 -0.04199987 -0.03370738 -0.279882 -0.04199951 -0.03172075 -0.2825896 -0.04199916 -0.02997565 -0.2839458 -0.04200005 -0.02892059 -0.285487 -0.04200237 -0.02755099 -0.284871 -0.04200178 -0.02812165 -0.255026 -0.04199999 -0.03799736 -0.2880641 -0.04200476 -0.02472627 -0.288974 -0.04200327 -0.02353763 -0.248912 -0.04199999 -0.03880685 -0.29 -0.0483976 -0.02195149 -0.29 -0.04978245 -0.02180629 -0.29 -0.05183595 -0.02140694 -0.29 -0.05251067 -0.02122616 0.23265 -0.01760166 -0.04491925 0.3694832 -0.0799362 -0.03746825 0.350295 -0.02713936 -0.0364297 0.348367 -0.02780896 -0.03673017 0.1674818 -0.01156681 -0.04750519 0.15274 -0.0112605 -0.04851675 0.463823 -0.0871725 -0.02031087 0.457793 -0.08771347 -0.02046948 0.455964 -0.08782267 -0.02063089 0.08532106 -0.108267 -0.04394817 0.08538866 -0.108206 -0.0443263 0.4702669 -0.04392814 -0.03028613 -0.2528387 -0.08915978 -0.02438467 -0.256604 -0.08901315 -0.0211125 -0.255951 -0.08892655 -0.02203845 -0.255701 -0.08891338 -0.02232289 -0.255437 -0.08890825 -0.02259415 -0.254571 -0.0889396 -0.02333098 -0.2534837 -0.08905375 -0.02403759 -0.29 -0.06657487 -0.006162285 -0.29 -0.06641787 -0.00684154 -0.29 -0.06623446 -0.007516324 -0.29 -0.06602656 -0.008184731 -0.250888 -0.08955097 -0.02513599 -0.249822 -0.08981978 -0.02542436 -0.29 -0.06579691 -0.008843898 -0.29 -0.06554538 -0.009493768 -0.273364 -0.07785558 -0.02446067 -0.29 -0.06275135 -0.01431155 -0.29 -0.06497615 -0.01077109 -0.29 -0.06527167 -0.01013779 -0.29 -0.06395709 -0.0126006 -0.2482038 -0.09028118 -0.02572506 -0.114449 -0.100094 -0.05374276 0.3836976 -0.04004025 -0.03584814 0.486954 -0.04594606 -0.02929216 0.450586 -0.04408121 -0.03174781 0.4181395 -0.04373055 -0.03398782 0.4105546 -0.04622608 -0.03480613 0.3569204 -0.03202587 -0.03661447 0.4951162 -0.0340237 -0.02395021 -0.04497945 -0.1116772 -0.006647288 0.486927 -0.07504266 -0.02823716 -0.08763778 -0.111266 -0.01161837 0.4056232 -0.08173465 -0.03407531 0.4050375 -0.08611196 -0.03163766 -0.08760118 -0.111267 -0.01141798 -0.08758926 -0.111267 -0.01121735 0.278936 -0.02027314 -0.04157167 0.302082 -0.0229277 -0.04023468 0.278939 -0.02178585 -0.04212999 0.3130643 -0.09221327 -0.03817737 0.3132346 -0.09061938 -0.03924065 0.4952203 -0.0311625 -0.02108621 0.3801895 -0.09277278 -0.02608549 0.3579865 -0.09324353 -0.03009474 0.325227 -0.02547156 -0.03860789 0.349044 -0.02567225 -0.03616964 0.34934 -0.02604818 -0.03625947 -0.06815838 -0.111621 -0.006170094 0.278915 -0.0956012 -0.03925895 0.278917 -0.09432107 -0.0404067 0.3128585 -0.0936163 -0.03691875 0.2365518 -0.09957528 -0.03996461 0.2656143 -0.09839302 -0.03741306 0.47228 -0.08711028 -0.0183413 -0.0674619 -0.1114407 0 -0.04004579 -0.1114351 0 0.1739622 -0.01170343 -0.04702538 0.3320496 -0.09547251 -0.03046554 0.3122462 -0.09582567 -0.03389793 -0.08758974 -0.111275 0 -0.08758956 -0.111267 -0.005353629 0.251061 -0.100678 -0.01650434 0.249098 -0.100783 -0.01578009 0.2357467 -0.1014816 -0.03137111 0.278914 -0.09671396 -0.03794455 0.3125957 -0.09482133 -0.03548824 0.255785 -0.09798491 -0.03953164 0.255786 -0.0969128 -0.0407747 0.2540446 -0.08879673 -0.04447758 0.255793 -0.02053707 -0.04385524 0.2758451 -0.0234946 -0.04275864 0.1401275 -0.04102402 -0.05029457 0.1631774 -0.03152406 -0.04942107 0.1398616 -0.03218257 -0.05040681 0.3968212 -0.04206681 -0.03522837 0.305956 -0.04396325 -0.04137098 0.2635725 -0.03971135 -0.04388439 0.350032 -0.04289156 -0.03850287 0.4067807 -0.04305195 -0.03467935 0.4045739 -0.04286873 -0.03480601 0.3707802 -0.04749155 -0.03749012 0.4159579 -0.04363077 -0.03412514 0.4218158 -0.04386919 -0.03375166 0.4254779 -0.04397207 -0.03351056 0.4280813 -0.0440275 -0.03333634 0.436826 -0.04412382 -0.03273493 0.4306597 -0.04406976 -0.03316158 0.2801091 -0.04512816 -0.04296475 0.51 -0.03898274 -0.02573353 0.302095 -0.03240638 -0.04109048 0.3596464 -0.08321022 -0.03779447 0.18639 -0.0161677 -0.04810327 0.1387454 -0.01097518 -0.04938095 0.209527 -0.09695446 -0.04533559 0.232656 -0.09699881 -0.04320907 0.33467 -0.09598851 -0.02725976 0.1802548 -0.01183694 -0.04654031 0.232656 -0.09817999 -0.04218119 0.232657 -0.099222 -0.04099607 0.212962 -0.09968745 -0.04259186 0.348486 -0.02490359 -0.03593975 0.325221 -0.02397155 -0.03817725 0.348228 -0.02451777 -0.03579449 0.222881 -0.09995836 -0.04115569 0.2278506 -0.1000882 -0.04039305 0.474073 -0.08706867 -0.01797068 0.23726 -0.0992124 -0.04039996 0.2351509 -0.100293 -0.03890997 0.235526 -0.100101 -0.03922218 0.2675967 -0.09979552 -0.03091722 0.325168 -0.09656226 -0.02769678 0.329919 -0.09627705 -0.02749079 0.296354 -0.09821546 -0.027152 0.294366 -0.09832549 -0.0268712 0.292368 -0.09843587 -0.02657145 0.290361 -0.09854656 -0.02625256 0.2357574 -0.101502 -0.03239279 0.2356535 -0.1012992 -0.03576779 0.2655326 -0.09968942 -0.03379511 0.288344 -0.09865766 -0.02591466 0.2860382 -0.09878444 -0.02550733 0.269361 -0.09969496 -0.02205628 0.267272 -0.09980809 -0.02152526 0.277858 -0.09923249 -0.02396535 0.275713 -0.09934955 -0.02352029 0.25503 -0.100467 -0.01788848 0.257035 -0.100359 -0.01854825 0.259055 -0.100251 -0.01918655 0.253039 -0.100573 -0.01720708 0.245214 -0.100989 -0.01426714 0.247149 -0.100886 -0.01503437 0.243292 -0.10109 -0.01347845 0.2394919 -0.10129 -0.01183664 0.241385 -0.101191 -0.01266825 0.237613 -0.101389 -0.01098346 0.235747 -0.101486 -0.01010894 0.265197 -0.09992027 -0.02097278 0.261088 -0.100142 -0.01980346 0.271464 -0.09958076 -0.02256578 0.273582 -0.09946566 -0.02305376 0.280018 -0.09911435 -0.02438896 0.235709 -0.101409 -0.03499668 0.2357425 -0.1014771 -0.03422623 0.298332 -0.09810578 -0.0274136 0.300301 -0.09799635 -0.02765619 0.30203 -0.09790009 -0.0283553 0.30226 -0.09788739 -0.02787977 0.302033 -0.09769618 -0.0308907 0.30615 -0.09767049 -0.02826958 0.2355476 -0.1010874 -0.03673613 0.255784 -0.09965986 -0.03646957 0.2889232 -0.09788173 -0.03398078 0.235435 -0.100861 -0.03749597 0.320415 -0.09684425 -0.02787768 0.2353095 -0.1006111 -0.03818905 0.495241 -0.03060024 -0.02034616 0.5100001 -0.0308277 -0.01848936 0.51 -0.08441799 -0.01608532 0.325214 -0.02260005 -0.03756594 0.5099997 -0.08503067 -0.01449477 0.477645 -0.08700829 -0.0171597 0.475861 -0.0870347 -0.01757675 0.486913 -0.08671605 -0.01550829 0.479425 -0.08698928 -0.0167194 0.4879533 -0.08687084 -0.01380902 0.4829744 -0.08697396 -0.01576852 0.51 -0.08549082 -0.01286721 0.5099998 -0.08574742 -0.01157528 0.5099997 -0.0859602 -0.009763717 0.4983378 -0.08664935 -0.009720742 0.5100001 -0.08600121 -0.008480072 0.4985937 -0.0866416 -0.009436964 0.4990024 -0.08661824 -0.008972883 0.4994636 -0.08659195 -0.008434414 0.5000271 -0.08655995 -0.007754266 0.5004432 -0.08653622 -0.00723499 0.5010836 -0.08649981 -0.006406724 0.501657 -0.08646726 -0.005632281 0.502013 -0.08644711 -0.005133628 0.5023762 -0.08642661 -0.004611849 0.5027548 -0.08640521 -0.004051685 0.5031281 -0.08638411 -0.003482043 0.5034837 -0.08636409 -0.002922415 0.51 -0.08599972 0 0.5038354 -0.08634424 -0.002351701 0.5042056 -0.08632344 -0.001732707 0.5045728 -0.08630287 -0.00109601 0.5048895 -0.08628511 -5.2917e-4 0.5051758 -0.08626914 0 0.481201 -0.08697789 -0.01625579 0.495241 -0.03034007 -0.01999998 0.347752 -0.0237382 -0.03544676 0.347984 -0.02412927 -0.03563004 0.2023314 -0.01231384 -0.04465126 0.2065497 -0.01240354 -0.04425251 0.347536 -0.02335268 -0.03524219 0.347335 -0.02297097 -0.03501695 0.2112814 -0.01250332 -0.04379034 0.2692686 -0.01707744 -0.04071533 0.347147 -0.02259159 -0.0347715 0.3128519 -0.02064973 -0.03791064 0.2163616 -0.01260602 -0.04326951 0.346815 -0.02185666 -0.03422325 0.3125298 -0.01946806 -0.03702121 0.2260681 -0.01275718 -0.04216438 0.3464692 -0.02097344 -0.03341865 0.4635876 -0.025321 -0.008996605 0.4909736 -0.02690696 -0.01120233 0.371371 -0.01934218 -0.01996439 0.383072 -0.02016735 -0.01999998 0.4620448 -0.02527004 0 0.4863603 -0.02669382 1.99613e-7 0.51 -0.02799975 0 0.1622636 -0.04471975 -0.04924422 0.3905947 -0.04122096 -0.03553867 0.3949782 -0.04183697 -0.03532296 0.1865575 -0.0452274 -0.04804295 0.4441669 -0.04412174 -0.03221309 0.4019628 -0.04262793 -0.03495252 0.399018 -0.04232162 -0.03511261 0.4335764 -0.04410278 -0.03296107 0.4096772 -0.04326653 -0.03450912 0.4133324 -0.04349452 -0.03428786 0.163269 -0.01632106 -0.04949069 0.5100001 -0.03014695 -0.01728272 0.48279 -0.0290668 -0.01999998 0.51 -0.02962493 -0.01620268 0.47034 -0.02779334 -0.01999998 0.486941 -0.02832859 -0.01817876 0.457889 -0.02652007 -0.01999998 0.486936 -0.0279147 -0.01726758 0.489613 -0.02727025 -0.01456218 0.5100001 -0.02861076 -0.01332002 0.486931 -0.02755528 -0.016321 0.463842 -0.02606338 -0.01823645 0.4206873 -0.02271771 -0.01999926 0.4763708 -0.02622616 -0.01455849 0.463834 -0.02573388 -0.01713198 0.5100001 -0.02820467 -0.0113449 0.4539626 -0.02471363 -0.0157569 0.5100002 -0.02908623 -0.01484918 0.4155917 -0.02222943 -0.01810419 0.4487076 -0.0243448 -0.01479125 0.345881 -0.0189982 -0.03070461 0.3457496 -0.0184068 -0.02939897 0.244664 -0.01282227 -0.03942304 0.3456763 -0.0180338 -0.02828282 0.3629999 -0.01882916 -0.01499998 0.5100004 -0.02799654 -0.009136497 0.3941969 -0.02085709 -0.01800304 0.394493 -0.02084368 -0.02016258 0.395562 -0.02101165 -0.01999998 0.432987 -0.0239734 -0.01999998 -0.141786 0.001587808 -0.03866887 5.04947e-4 -0.001270532 -0.04985564 0.34581 -0.01869297 -0.03007429 0.445438 -0.02524667 -0.01999998 0.3460129 -0.01952582 -0.03160548 0.005408048 -0.00367856 -0.05256372 0.463851 -0.02646106 -0.01927596 0.2695479 -0.0183646 -0.04158484 0.346307 -0.02050715 -0.03291106 0.346974 -0.02221828 -0.03450655 0.34667 -0.02150249 -0.0339207 0.349966 -0.02678167 -0.03638947 0.255792 -0.01898306 -0.04331535 0.302077 -0.02147656 -0.03965216 0.2967406 -0.02440983 -0.04109632 0.255794 -0.02225857 -0.04419088 0.349647 -0.02641797 -0.03633266 0.351166 -0.02800548 -0.03648376 0.351713 -0.02850145 -0.03651475 0.348759 -0.02529036 -0.03606349 -0.04454374 -0.01405405 -0.0570209 0.001525759 -0.01088178 -0.05493801 0.3772478 -0.03868323 -0.03610312 0.02471262 -0.01062345 -0.05405116 0.04826581 -0.01120954 -0.05331176 0.3636175 -0.03488808 -0.03652912 0.3582152 -0.03268033 -0.03660506 0.3125296 -0.02923971 -0.04011076 0.255795 -0.02420657 -0.04427659 0.350636 -0.02749097 -0.03645366 0.001245677 -0.04467993 -0.05495315 0.02446216 -0.03264588 -0.05407637 0.3818666 -0.03968125 -0.03592401 0.354052 -0.03030216 -0.03661888 0.352277 -0.02897804 -0.03655219 0.04659652 -0.04110914 -0.0534172 0.385868 -0.04044234 -0.03575503 0.07080107 -0.03507345 -0.05271625 0.354669 -0.03070956 -0.03662526 -0.1604365 -0.0360279 -0.05291092 -0.1879994 -0.04199993 -0.04834181 0.02401286 -0.05366045 -0.05412691 0.09472858 -0.04429954 -0.05200874 0.07013022 -0.0560311 -0.05278861 0.3927763 -0.0415399 -0.03543317 0.1395416 -0.05096441 -0.05023163 -0.28608 -0.04200297 -0.02696585 -0.2024042 -0.04199999 -0.04584145 0.1168838 -0.05350136 -0.05118435 0.1680675 -0.05624264 -0.04886263 0.3662982 -0.04986608 -0.03787648 -0.289603 -0.04200166 -0.02262425 -0.212317 -0.04199999 -0.04421496 0.04765623 -0.06469321 -0.05342864 0.1865814 -0.07342118 -0.04792433 0.3492298 -0.05167615 -0.03897649 0.1398468 -0.0674104 -0.05018395 0.3281403 -0.05311745 -0.04025381 0.4078957 -0.04899257 -0.03514999 0.4391766 -0.05073124 -0.03298926 -0.29 -0.05115467 -0.0215643 -0.06813037 -0.06113737 -0.05775088 0.3725908 -0.05324059 -0.03750091 0.4184325 -0.05162292 -0.0344538 0.3969736 -0.05271029 -0.03591072 0.4629589 -0.04931724 -0.03123134 0.4854288 -0.04831463 -0.0294941 0.5100005 -0.04684394 -0.02750712 -0.273365 -0.06472629 -0.03338915 -0.29 -0.05383628 -0.02079516 -0.29 -0.0531767 -0.02102249 -0.251909 -0.04803669 -0.0384013 -0.229165 -0.04763078 -0.04175257 0.1176583 -0.09378767 -0.05116134 0.09484267 -0.09530955 -0.05200648 0.1631541 -0.07490402 -0.04909271 -0.273365 -0.06637358 -0.03282207 -0.29 -0.05513137 -0.02027189 -0.29 -0.05448955 -0.02054446 -0.251912 -0.04993849 -0.03843408 -0.273365 -0.06798446 -0.03214919 -0.273365 -0.0695827 -0.03135615 -0.29 -0.05638438 -0.01965975 0.02451074 -0.08238667 -0.05410176 0.1638998 -0.0942341 -0.04912054 0.230435 -0.09032022 -0.04574036 -0.29 -0.05576258 -0.01997709 -0.251915 -0.05184215 -0.03848177 -0.22918 -0.04977917 -0.04193365 0.07288336 -0.09689992 -0.05268001 0.1411547 -0.0955199 -0.05018091 0.4877429 -0.05899959 -0.0292598 -0.29 -0.05699676 -0.01931989 -0.251919 -0.05377858 -0.03854286 -0.29 -0.05984735 -0.01731926 -0.29 -0.05874919 -0.01817977 -0.273365 -0.07119816 -0.03041696 0.04806369 -0.1012775 -0.05332976 0.09820157 -0.0965538 -0.0518952 0.1860849 -0.09295243 -0.04801946 -0.29 -0.05817729 -0.01858085 -0.29 -0.05759316 -0.01896095 -0.251922 -0.05578404 -0.03861719 -0.22921 -0.05434846 -0.04244714 0.04767268 -0.103154 -0.05304086 0.1155157 -0.0970261 -0.05135917 0.2297644 -0.09255278 -0.04550307 0.2624918 -0.09233057 -0.04314851 0.51 -0.06121802 -0.02749985 -0.29 -0.05930745 -0.01775836 -0.251926 -0.05788969 -0.03870534 -0.29 -0.06230926 -0.01485365 0.1666049 -0.09617364 -0.04873192 0.1408541 -0.09771877 -0.05000185 -0.29 -0.06088209 -0.01638245 -0.251929 -0.06012469 -0.03880965 -0.29 -0.06357449 -0.01318556 -0.29 -0.06317287 -0.01375567 0.1309874 -0.09744882 -0.050601 0.1510941 -0.09799808 -0.04927116 0.1713556 -0.09855061 -0.04751431 0.186401 -0.09675288 -0.04723554 0.5100001 -0.06813919 -0.02748101 0.4911697 -0.06916308 -0.02894043 -0.29 -0.06185048 -0.01537907 -0.251933 -0.06261688 -0.03893357 -0.229259 -0.06244617 -0.0436483 -0.206477 -0.08104729 -0.04576706 -0.04498958 -0.09690219 -0.05729997 0.1608354 -0.0982635 -0.04847759 0.186403 -0.0981974 -0.04656046 0.188123 -0.09900909 -0.04574304 0.209528 -0.09825277 -0.04449218 0.454131 -0.08793956 -0.02076905 0.4523469 -0.08806073 -0.02088028 0.440725 -0.0884934 -0.02253997 0.51 -0.07004308 -0.02725899 -0.251937 -0.06561696 -0.03907847 -0.229276 -0.06599038 -0.0442121 -0.2400718 -0.0932458 -0.025204 0.04767245 -0.104443 -0.0525738 0.02453345 -0.10613 -0.0527029 0.193095 -0.09914487 -0.04516297 0.4039477 -0.08947175 -0.02806407 0.5100001 -0.07397431 -0.02619034 -0.25194 -0.06907176 -0.03894335 -0.229293 -0.0700646 -0.04446876 -0.2393973 -0.0935254 -0.02500563 0.08787149 -0.1059479 -0.04875701 0.07079899 -0.1069509 -0.04907125 0.00137633 -0.106103 -0.05355966 -0.02180105 -0.105223 -0.05463069 0.04767215 -0.105482 -0.05201107 0.02453327 -0.107022 -0.05206215 0.0906493 -0.1034218 -0.05070489 0.07079929 -0.104401 -0.05136805 0.0938211 -0.1005374 -0.05173349 0.3999382 -0.09082055 -0.02638953 -0.251944 -0.07284456 -0.03824675 -0.22931 -0.07452267 -0.04405158 -0.04498726 -0.103633 -0.05568307 0.04767197 -0.106366 -0.05137336 0.08987736 -0.1041234 -0.05028676 0.07079917 -0.105359 -0.05069476 0.17817 -0.09873729 -0.04682797 0.3584155 -0.09216344 -0.03188955 0.278919 -0.09286928 -0.04138255 0.3595229 -0.08538568 -0.03715515 0.461439 -0.08751749 -0.02007687 0.463256 -0.08743077 -0.01984566 -0.251948 -0.07683217 -0.03683078 -0.229326 -0.07923799 -0.04277515 -0.137519 -0.09486287 -0.05335634 0.08881962 -0.1050855 -0.04957669 0.07079905 -0.106202 -0.04993289 0.08934277 -0.1046103 -0.04995101 0.183148 -0.09887325 -0.04629808 0.203034 -0.09941625 -0.04392755 0.1980659 -0.09928065 -0.04455786 0.3593496 -0.0873931 -0.03621387 -0.251952 -0.08081507 -0.03458416 -0.229342 -0.0839529 -0.04051029 -0.137519 -0.09816676 -0.05138659 0.04767155 -0.107828 -0.04986387 0.08740168 -0.1063749 -0.04826223 0.08833873 -0.1055231 -0.04918634 0.255786 -0.09568989 -0.04185646 0.3590744 -0.08921915 -0.03499734 0.459618 -0.08761167 -0.02028477 -0.229358 -0.08830147 -0.03728038 -0.160552 -0.09926956 -0.04510688 -0.0218001 -0.108904 -0.05152899 0.08659249 -0.107111 -0.04720097 0.07079887 -0.107618 -0.04808294 0.0869745 -0.1067634 -0.04774188 0.04767179 -0.107139 -0.0506621 0.207999 -0.09955185 -0.04327225 0.3587952 -0.09081757 -0.03353685 0.4045073 -0.08795565 -0.02995723 -0.183543 -0.103769 -0.02010399 0.08606326 -0.1075916 -0.04627174 0.08583408 -0.107801 -0.04576027 0.08631026 -0.107368 -0.04673558 0.217923 -0.09982287 -0.04188627 -0.1376394 -0.1086394 -0.01799815 -0.1454097 -0.1078788 -0.01679527 -0.114443 -0.110203 -0.02058988 -0.09085476 -0.1111749 -0.01398485 0.08558166 -0.10803 -0.04506069 0.235925 -0.0998966 -0.03952729 0.4005782 -0.09175854 -0.02364546 0.4206163 -0.09035855 -0.02256411 0.4377297 -0.08913117 -0.02164983 0.466878 -0.08727997 -0.01931369 -0.218439 -0.09874737 -0.02033728 -0.1621654 -0.1062577 -0.01760959 0.08547639 -0.108126 -0.04469639 0.3777646 -0.09327733 -0.02488654 0.3609473 -0.09436231 -0.02581071 0.465069 -0.08735156 -0.01959127 -0.213438 -0.09954416 -0.02009528 -0.1136656 -0.1101582 -0.01525074 -0.130427 -0.1090732 -0.01606702 -0.0916441 -0.1111521 -0.01413613 0.315661 -0.09712296 -0.02803349 -0.208434 -0.100316 -0.01985305 -0.160543 -0.106432 -0.02725064 0.30421 -0.09777879 -0.02808415 0.310906 -0.0973984 -0.02816408 -0.09124982 -0.1111641 -0.01407015 0.02453166 -0.110379 -0.007227241 0.03783679 -0.1101421 0 0.009724795 -0.1108362 0 0.263135 -0.100032 -0.02039885 -0.0881173 -0.111253 -0.01251316 -0.06999999 -0.005724668 -0.02999997 -0.06999999 0.001773834 -0.02999997 -0.06999999 0.001775503 0 -0.06999999 -0.005724668 0 -0.06999999 -0.005724668 0 -0.05899995 -0.005724668 0 -0.05899995 -0.005724668 -0.02999997 -0.06999999 -0.005724668 -0.02999997 -0.05899995 -0.005724668 0 -0.05899995 -0.007658004 -0.02999997 -0.05899995 -0.005724668 -0.02999997 -0.05899995 -0.007630705 -0.03094011 -0.05899995 -0.007640361 -0.03218591 -0.05899995 -0.00810337 -0.03618729 -0.05899995 -0.00826472 -0.03679406 -0.05899995 -0.007700145 -0.03342586 -0.05899995 -0.007966518 -0.03557807 -0.05899995 -0.007779479 -0.03435146 -0.05899995 -0.007854104 -0.03496646 -0.05899995 -0.008449018 -0.03739374 -0.05899995 -0.008654654 -0.03798097 -0.05899995 -0.008883178 -0.03856056 -0.05899995 -0.009134531 -0.03913259 -0.05899995 -0.009407281 -0.03969329 -0.05899995 -0.009700953 -0.04024106 -0.05899995 -0.01001626 -0.04077839 -0.05899995 -0.01322466 -0.03849995 -0.05899995 -0.01108527 -0.04231107 -0.05899995 -0.01070958 -0.04181587 -0.05899995 -0.01035338 -0.04130506 -0.05899995 -0.01189714 -0.04326009 -0.05899995 -0.01148104 -0.04279255 -0.05899995 -0.01232814 -0.0437085 -0.05899995 -0.01324158 -0.04455459 -0.05899995 -0.01277607 -0.0441398 -0.05899995 -0.01372468 -0.03849995 -0.05899995 -0.01372468 -0.04495298 -0.05899995 -0.01322466 0 -0.137212 -0.00398916 -0.02161157 -0.08099997 -0.006251513 -0.02915477 -0.1372032 -0.003977179 -0.02089995 0.03495156 -0.01164305 -0.03179621 0.01501572 -0.01137918 -0.03000003 0.03495115 -0.01167941 -0.02999961 -0.1372294 -0.004002094 -0.02275562 -0.137262 -0.00402683 -0.02341628 -0.1128309 -0.004565775 -0.02631628 0.003808081 -0.01108741 -0.02999997 -0.08099997 -0.006213009 -0.02848172 -0.1128309 -0.004560053 -0.02283155 -0.08099997 -0.006212413 -0.02505707 -0.00717175 -0.01070737 -0.02999961 -0.01804876 -0.01023948 -0.02999907 -0.11283 -0.004559457 -0.01834827 -0.137224 -0.003997921 -0.01380681 -0.02675598 -0.009800732 -0.02999997 -0.03894084 -0.008988142 -0.03126746 -0.08099997 -0.006211757 -0.0196495 -0.08099997 -0.006211578 -0.01762044 -0.137224 -0.003997862 -0.01260626 -0.112829 -0.00455892 -0.01303589 -0.137223 -0.003997564 -0.005402505 -0.112829 -0.004558384 -0.00793153 -0.04598933 -0.00863564 -0.03000009 -0.137224 -0.003997743 -0.009604871 -0.1372228 -0.003997862 -0.00840801 -0.08099997 -0.006210863 -0.0115149 -0.03894138 -0.008995115 -0.03455197 0.03495067 -0.011684 -0.03529196 -0.05900001 -0.007621586 -0.03140115 -0.05899995 -0.007658004 -0.02999997 0.02494955 -0.01161187 -0.037 0.03494948 -0.01173305 -0.037 -0.139113 -0.005411624 -0.03017145 -0.08099997 -0.007350146 -0.03644984 -0.138863 -0.005224585 -0.02965807 -0.08100014 -0.006567656 -0.03376269 -0.112832 -0.004815816 -0.02921366 -0.05900025 -0.007772922 -0.03435438 -0.112833 -0.00539112 -0.03190028 -0.08099997 -0.00676459 -0.03458106 -0.112834 -0.007355451 -0.03671115 -0.08100008 -0.00900489 -0.03992569 -0.08100008 -0.008116483 -0.03832244 -0.140561 -0.006495296 -0.03255856 -0.127117 -0.01088404 -0.04037028 -0.112836 -0.01020199 -0.04075378 -0.112835 -0.008680522 -0.03882879 -0.1270714 -0.008969247 -0.03815966 -0.08099991 -0.01371496 -0.04505687 -0.127223 -0.01540595 -0.04400634 -0.112838 -0.01582825 -0.04536259 -0.08099997 -0.01265937 -0.04420047 -0.127155 -0.01249867 -0.04188269 -0.1271697 -0.01314562 -0.04243743 -0.1273298 -0.01997125 -0.0462014 -0.03894627 -0.01656377 -0.04629474 -0.112838 -0.01803225 -0.0464797 -0.1272663 -0.01724135 -0.04505783 -0.112841 -0.02833837 -0.04839026 -0.03894776 -0.0211572 -0.04761755 -0.1275215 -0.02812337 -0.04757302 -0.03894728 -0.01938378 -0.04730868 -0.1274539 -0.02525019 -0.04740929 -0.1128399 -0.0254842 -0.04832887 0.02472817 -0.02104085 -0.04510265 -0.03894829 -0.02381908 -0.04769426 -0.03894877 -0.02722465 -0.04769426 -0.03894919 -0.03107416 -0.04769426 -0.1277211 -0.0366221 -0.04756528 -0.112843 -0.03776568 -0.04839026 -0.1276553 -0.03380239 -0.04756999 -0.112843 -0.0345214 -0.04839026 -0.03894966 -0.03534829 -0.04769426 -0.1277931 -0.03968095 -0.04756033 -0.112844 -0.04109275 -0.04839026 0.02447581 -0.03179174 -0.04511141 -0.0389502 -0.04001706 -0.04769426 -0.1278508 -0.04216158 -0.04755616 -0.1185474 -0.04237979 -0.04783451 -0.1067045 -0.04265785 -0.04810565 -0.09743648 -0.04287558 -0.04825305 -0.08879762 -0.04307842 -0.04834592 -0.07668823 -0.04336267 -0.04839193 0.02422755 -0.04237198 -0.04512107 -0.06430238 -0.04365348 -0.04834169 -0.04596161 -0.04408407 -0.0480991 -0.02520352 -0.04457122 -0.04754006 -0.01541227 -0.04480135 -0.04718309 0.02420991 -0.04311376 -0.04511874 -0.003285348 -0.04508602 -0.04665869 0.02418798 -0.04404395 -0.04511702 0.009467542 -0.04538536 -0.04600858 0.02414882 -0.04573023 -0.04512619 -0.112842 -0.03137439 -0.04839026 -0.1275879 -0.03093934 -0.04757499 -0.1370731 -0.008927702 -0.03700309 -0.134669 -0.008715927 -0.037 -0.148954 -0.008840441 -0.03516125 0.02476817 -0.01933795 -0.04502165 -0.1128399 -0.02286469 -0.04798167 -0.1274147 -0.02357935 -0.0471698 -0.112839 -0.02038174 -0.04735869 -0.1273828 -0.02220141 -0.04688328 -0.03894674 -0.01789134 -0.04685884 0.02481198 -0.01747208 -0.04455095 -0.1272904 -0.01827549 -0.04553425 0.02484309 -0.01614814 -0.04392892 -0.03894579 -0.01536256 -0.0456295 -0.112837 -0.01378256 -0.04402625 -0.127209 -0.01480269 -0.04361987 -0.08099997 -0.01318258 -0.04464149 -0.1271293 -0.01142364 -0.04091399 -0.112836 -0.01190495 -0.04248696 -0.08099997 -0.01168197 -0.0432924 -0.08100003 -0.01118445 -0.04277551 -0.1270849 -0.009497404 -0.03885084 -0.08099997 -0.0103268 -0.04176849 -0.08099997 -0.009906232 -0.04122149 -0.1499339 -0.007531523 -0.03299999 -0.127053 -0.008151113 -0.037 -0.08099997 -0.009508192 -0.04066437 -0.146925 -0.007240295 -0.03299999 -0.1496199 -0.007950723 -0.03373789 -0.140244 -0.006258785 -0.03210514 -0.112833 -0.006249308 -0.03440058 -0.1397796 -0.005910992 -0.03138065 -0.1311313 -0.008428752 -0.03700047 -0.1484395 -0.009527921 -0.03615432 -0.1374967 -0.02694571 -0.04671901 -0.17264 -0.02795809 -0.04199999 -0.172779 -0.02826279 -0.04199999 -0.172484 -0.0276615 -0.04199999 -0.172897 -0.028575 -0.04199999 -0.1729969 -0.02889597 -0.04199999 -0.1730729 -0.02922105 -0.04199999 -0.173117 -0.02955257 -0.04199999 -0.1375336 -0.02853208 -0.04678434 -0.1731539 -0.03004193 -0.04200017 -0.1731629 -0.03055417 -0.04199999 -0.1731539 -0.03088897 -0.04199999 -0.1375761 -0.03032827 -0.04677379 -0.176463 -0.03336524 -0.04143667 -0.1376546 -0.03367912 -0.04675281 -0.1797699 -0.03584039 -0.04086059 -0.137701 -0.03566807 -0.04674702 -0.183076 -0.03831446 -0.04027169 -0.1377704 -0.03858613 -0.04674065 -0.18638 -0.04078745 -0.03966999 -0.182669 -0.0408746 -0.04036676 -0.137789 -0.03939205 -0.04673886 -0.178954 -0.0409618 -0.04103797 -0.1737066 -0.04108548 -0.04194337 -0.167787 -0.041224 -0.04289805 -0.137808 -0.04021728 -0.04673707 -0.1626847 -0.04134398 -0.04367208 -0.1541188 -0.04154664 -0.04485285 -0.1378279 -0.04106217 -0.04673528 -0.1378521 -0.04192757 -0.04676371 -0.1374615 -0.02543824 -0.04656505 -0.172313 -0.02737385 -0.04199999 -0.1720287 -0.02695125 -0.04200077 -0.1716231 -0.02643829 -0.04199993 -0.1374251 -0.02393329 -0.04632323 -0.1711775 -0.02594763 -0.04199904 -0.1707113 -0.02549225 -0.04199993 -0.170313 -0.02513688 -0.04199999 -0.1697914 -0.02470576 -0.04199993 -0.1373862 -0.02227485 -0.045951 -0.1691058 -0.024194 -0.04199898 -0.1685858 -0.02383339 -0.04199999 -0.1680334 -0.02347373 -0.04199922 -0.1674817 -0.02313417 -0.04199999 -0.1667162 -0.02269035 -0.04199987 -0.13736 -0.02109766 -0.04560536 -0.1658065 -0.02219885 -0.04199999 -0.1650884 -0.02183461 -0.04200077 -0.1373371 -0.02019256 -0.04529076 -0.1642055 -0.02140867 -0.04199993 -0.1631064 -0.02091211 -0.04199987 -0.1621716 -0.02051293 -0.04199999 -0.1609696 -0.0200271 -0.04199922 -0.137139 -0.01169222 -0.04008358 -0.1470659 -0.01136398 -0.03841465 -0.147825 -0.01193225 -0.03884005 -0.1371705 -0.01304799 -0.04127144 -0.1504979 -0.01393258 -0.040138 -0.137308 -0.01890778 -0.04479527 -0.1489484 -0.01277297 -0.03942507 -0.1372094 -0.01472204 -0.04251968 -0.1597404 -0.01956063 -0.04199999 -0.1520705 -0.01510959 -0.04075974 -0.1586158 -0.01915538 -0.04199892 -0.1372878 -0.01804059 -0.04441505 -0.1573135 -0.01870959 -0.04200094 -0.156547 -0.01845979 -0.04199999 -0.1372476 -0.01633262 -0.0435357 -0.1553094 -0.01753377 -0.04173398 -0.1536695 -0.01630687 -0.0412907 -0.1371084 -0.01039952 -0.03878563 -0.1476987 -0.01051849 -0.03743618 -0.149294 -0.008387029 -0.03445827 -0.139376 -0.005608558 -0.03067284 -0.138626 -0.00504738 -0.0291326 -0.138409 -0.004884779 -0.02859818 -0.138024 -0.004597127 -0.02749836 -0.138208 -0.004734873 -0.02805358 -0.137856 -0.004471421 -0.02693265 -0.137709 -0.004361331 -0.0263617 -0.137582 -0.004265964 -0.02578419 -0.08099997 -0.006405591 -0.0318467 -0.137473 -0.004184484 -0.02519899 -0.137383 -0.004116952 -0.02460598 -0.137313 -0.00406444 -0.02401196 -0.08099997 -0.006367087 -0.0311737 -0.137224 -0.003998041 -0.01680868 -0.137224 -0.003998339 -0.0180093 -0.08099997 -0.006212234 -0.02369612 -0.08099997 -0.006211042 -0.01287299 -0.08099997 -0.006210386 -0.007461071 -0.137223 -0.003997504 -0.004201769 -0.08099997 -0.006210207 -0.006110608 -0.112828 -0.004557788 -0.003542363 -0.08099997 -0.006209731 -0.002722561 -0.137223 -0.003997385 -0.001800239 -0.08915317 -0.005687534 0 -0.08100056 -0.006219804 -0.001346588 -0.137223 -0.003997385 -0.001200079 -0.09850376 -0.005171954 -4.89237e-7 -0.1093235 -0.004701733 1.551e-6 -0.1182633 -0.004391372 1.19712e-6 -0.137223 -0.003997325 -6.00012e-4 -0.1290122 -0.004117667 0 -0.137223 -0.003997266 0 -0.08099997 -0.006209254 0 -0.1372238 -0.00399816 -0.01931571 -0.03894186 -0.009217679 -0.03660279 -0.05900019 -0.008105039 -0.03619599 0.02494388 -0.0118528 -0.03837919 -0.05899995 -0.008362472 -0.03709298 -0.03894239 -0.009624838 -0.03823685 -0.05900001 -0.008651494 -0.03799641 -0.03894287 -0.01016288 -0.03965836 0.02493679 -0.01215696 -0.03927302 -0.05899995 -0.009414315 -0.03969478 0.02492743 -0.01255577 -0.04019385 -0.05900013 -0.009970486 -0.04069298 -0.05899989 -0.01097589 -0.0421974 -0.1439099 -0.006977021 -0.03299999 -0.03894388 -0.01154607 -0.04206377 -0.03894436 -0.01236879 -0.0430935 0.0249046 -0.0135312 -0.04167616 -0.05900001 -0.01209717 -0.04349017 0.02488273 -0.01445913 -0.04269301 -0.03894478 -0.01327484 -0.04402685 -0.05899995 -0.01324176 -0.04455459 -0.03894525 -0.01427006 -0.04487186 -0.07033509 -0.01372539 -0.04509013 0.02486807 -0.01508468 -0.04321068 -0.05900013 -0.01372808 -0.0449478 -0.14089 -0.006741702 -0.03299999 0.08439826 -0.009134054 -0.02999997 0.07340127 -0.008875906 -0.06499999 0.07340127 -0.008875906 -0.02999997 0.08439826 -0.009134054 -0.06499999 0.07340127 -0.008875906 -0.02999997 0.07363599 0.001121282 -0.06499999 0.07363599 0.001121282 -0.02999997 0.07340127 -0.008875906 -0.06499999 0.07363599 0.001121282 -0.02999997 0.08463299 8.63139e-4 -0.06499999 0.08463299 8.63139e-4 -0.02999997 0.07363599 0.001121282 -0.06499999 0.08463299 8.63139e-4 -0.02999997 0.08439826 -0.009134054 -0.06499999 0.08439826 -0.009134054 -0.02999997 0.08463299 8.63139e-4 -0.06499999 0.03414589 -0.04596477 -0.037 0.177106 -0.04932105 -0.037 0.177106 -0.04932105 -0.04499995 0.03414589 -0.04596477 -0.04499995 0.177838 -0.01815819 -0.03558576 0.177928 -0.01433068 -0.04499995 0.17783 -0.01850569 -0.03597676 0.177928 -0.01433068 -0.02999997 0.177896 -0.01569157 -0.03052139 0.177898 -0.01559758 -0.02999997 0.177893 -0.01580715 -0.03103208 0.177886 -0.01610338 -0.03202116 0.17789 -0.01594436 -0.03153198 0.177877 -0.01648616 -0.03296738 0.177882 -0.01628398 -0.03249967 0.177872 -0.01671087 -0.03342747 0.17786 -0.01722788 -0.03432655 0.177866 -0.01695817 -0.03388094 0.177846 -0.01782816 -0.03517955 0.177853 -0.01751857 -0.03476095 0.1778039 -0.01959508 -0.037 0.177106 -0.04932105 -0.04499995 0.177106 -0.04932105 -0.037 0.1778129 -0.01922005 -0.0366798 0.1778219 -0.018857 -0.03633868 0.174816 -0.01425766 -0.02999997 0.177928 -0.01433068 -0.04499995 0.177928 -0.01433068 -0.02999997 0.174816 -0.01425766 -0.04499995 0.1716981 -0.01309067 -0.04499995 0.1713781 -0.01278555 -0.02999997 0.1699337 -0.009141683 -0.04499995 0.169933 -0.009141683 -0.02999997 0.1722006 -0.01345539 -0.02999997 0.1727347 -0.01375824 -0.04499995 0.1729705 -0.01386052 -0.02999997 0.1738923 -0.01416462 -0.04499995 0.1739894 -0.01418423 -0.02999997 0.174816 -0.01425766 -0.04499995 0.174816 -0.01425766 -0.02999997 0.1708675 -0.01218223 -0.04499995 0.1708138 -0.0120967 -0.02999997 0.1703842 -0.01135176 -0.02999997 0.1702705 -0.01110386 -0.04499995 0.1700041 -0.01018035 -0.02999997 0.1699687 -0.009916067 -0.04499995 0.170091 -0.00248754 -0.02999997 0.169935 -0.009141683 -0.04499995 0.169935 -0.009141683 -0.02999997 0.170091 -0.00248754 -0.04499995 0.1666712 0.001277863 -0.04499995 0.1659471 0.001316368 -0.02999997 0.1654066 0.001259386 -0.04499995 0.1672062 0.001163005 -0.02999997 0.1677286 9.64602e-4 -0.04499995 0.1683522 6.26009e-4 -0.02999997 0.1686798 3.7832e-4 -0.04499995 0.1691681 -1.20857e-4 -0.02999997 0.1695088 -5.78935e-4 -0.04499995 0.1696882 -9.17212e-4 -0.02999997 0.1699472 -0.001583814 -0.04499995 0.1700069 -0.001816153 -0.02999997 0.1700974 -0.002486944 -0.04499995 0.170091 -0.00248754 -0.02999997 0.1648629 0.001117289 -0.02999997 0.164207 8.4687e-4 -0.04499995 0.1638565 6.36434e-4 -0.02999997 0.1633136 1.87804e-4 -0.04499995 0.163156 1.96352e-5 -0.02999997 0.1627137 -5.46898e-4 -0.04499995 0.1626698 -6.1765e-4 -0.02999997 0.1623029 -0.001403093 -0.04499995 0.1622771 -0.001481652 -0.02999997 0.1621268 -0.002185761 -0.04499995 0.1620759 -0.002694547 -0.02999997 0.162097 -0.0026955 -0.04499995 0.1619499 -0.008954226 -0.02999997 0.162097 -0.0026955 -0.04499995 0.162097 -0.0026955 -0.02999997 0.1619499 -0.008954226 -0.04499995 0.1602442 -0.01262003 -0.04499995 0.1606869 -0.01217216 -0.02999997 0.1597567 -0.0129944 -0.02999997 0.1590461 -0.01339411 -0.04499995 0.1586335 -0.01355385 -0.02999997 0.1575925 -0.01380378 -0.02999997 0.1576757 -0.01379972 -0.04499995 0.156834 -0.01383548 -0.02999997 0.156834 -0.01383548 -0.04499995 0.1610708 -0.01168477 -0.04499995 0.1614052 -0.01114279 -0.02999997 0.1615131 -0.01089072 -0.04499995 0.1618059 -0.01006728 -0.04499995 0.1618273 -0.009977161 -0.02999997 0.1619605 -0.008954882 -0.04499995 0.1619566 -0.008954644 -0.02999997 0.04857718 -0.001291155 -0.02999997 0.04863119 0.001011312 -0.04499995 0.04863119 0.001011312 -0.02999997 0.04857718 -0.001291155 -0.04499995 0.04479044 -0.008903801 -0.02999997 0.04508155 -0.008664429 -0.04499995 0.04587477 -0.007907509 -0.02999997 0.04357212 -0.009729981 -0.02999997 0.04389333 -0.009536981 -0.04499995 0.04202687 -0.01045918 -0.02999997 0.04258978 -0.01022559 -0.04499995 0.0409584 -0.01078444 -0.04499995 0.04035919 -0.01090455 -0.02999997 0.03912824 -0.01104408 -0.02999997 0.0392701 -0.01104027 -0.04499995 0.03834515 -0.01105368 -0.02999997 0.03834515 -0.01105368 -0.04499995 0.04612767 -0.007627844 -0.04499995 0.04680126 -0.006762683 -0.02999997 0.04701012 -0.006449401 -0.04499995 0.04766649 -0.005266606 -0.02999997 0.04781025 -0.004941344 -0.04499995 0.04833376 -0.00329566 -0.04499995 0.04824262 -0.003660857 -0.02999997 0.04853081 -0.002072274 -0.04499995 0.04852014 -0.002215862 -0.02999997 0.04857718 -0.001291155 -0.04499995 0.04857718 -0.001291155 -0.02999997 0.03496736 -0.01097434 -0.02999997 0.03834515 -0.01105368 -0.04499995 0.03834515 -0.01105368 -0.02999997 0.03496736 -0.01097434 -0.04499995 0.03494948 -0.01173305 -0.037 0.03414589 -0.04596477 -0.04499995 0.03496736 -0.01097434 -0.04499995 0.03496736 -0.01097434 -0.02999997 0.03495156 -0.01164478 -0.03179198 0.03495138 -0.01165449 -0.03355598 0.03495067 -0.011684 -0.03529196 0.03495138 -0.01165467 -0.02999997 0.03414589 -0.04596477 -0.037 0.1631312 -0.002194821 -0.04499995 0.1631046 -0.00239098 -0.06499999 0.1632484 -0.001744687 -0.06499999 0.1633722 -0.001422405 -0.04499995 0.1638896 -6.42138e-4 -0.04499995 0.1635329 -0.001123249 -0.06499999 0.1641429 -4.00148e-4 -0.06499999 0.1647542 3.12134e-6 -0.04499995 0.1648186 2.11488e-5 -0.06499999 0.1657876 3.02845e-4 -0.04499995 0.1655983 2.77136e-4 -0.06499999 0.1666722 2.63182e-4 -0.06499999 0.1667315 2.43948e-4 -0.04499995 0.1674228 -1.78925e-6 -0.06499999 0.1674889 -2.98164e-5 -0.04499995 0.1681455 -4.93774e-4 -0.04499995 0.168002 -3.68355e-4 -0.06499999 0.1685508 -9.57346e-4 -0.06499999 0.1686589 -0.001120269 -0.04499995 0.1688695 -0.001542866 -0.06499999 0.1689424 -0.001738607 -0.04499995 0.1690891 -0.002388238 -0.04499995 0.1690628 -0.002194583 -0.06499999 0.1689423 -0.003653407 -0.06499999 0.1690628 -0.003197312 -0.04499995 0.1690891 -0.003003656 -0.06499999 0.1686589 -0.004271686 -0.06499999 0.1685508 -0.004434645 -0.04499995 0.1688695 -0.003849089 -0.04499995 0.168002 -0.005023598 -0.04499995 0.1681454 -0.00489819 -0.06499999 0.1674889 -0.005362153 -0.06499999 0.1674228 -0.005390167 -0.04499995 0.1667315 -0.005635917 -0.06499999 0.1666722 -0.005655109 -0.04499995 0.1655983 -0.005669116 -0.04499995 0.1657876 -0.005694806 -0.06499999 0.1647542 -0.005395054 -0.06499999 0.1648185 -0.005413055 -0.04499995 0.1641429 -0.004991829 -0.04499995 0.1638896 -0.004749834 -0.06499999 0.1635329 -0.004268646 -0.04499995 0.1633722 -0.00396955 -0.06499999 0.1632484 -0.003647267 -0.04499995 0.1631046 -0.003000974 -0.04499995 0.1631312 -0.003197073 -0.06499999 0.0521844 0.001834213 -0.04499995 0.05217874 0.001753211 -0.06499999 0.0521326 7.07914e-4 -0.06499999 0.0521388 6.19122e-4 -0.04499995 0.05250042 0.002936005 -0.06499999 0.05248063 0.002855062 -0.04499995 0.05286031 0.003626048 -0.04499995 0.0536803 0.004633247 -0.06499999 0.05339115 0.004333913 -0.04499995 0.05310767 0.003992617 -0.06499999 0.05436974 0.005188882 -0.06499999 0.05401253 0.004929363 -0.04499995 0.05489403 0.005491554 -0.04499995 0.05529755 0.005671262 -0.06499999 0.05612313 0.005911469 -0.06499999 0.05604016 0.005906045 -0.04499995 0.05700165 0.006017386 -0.06499999 0.05726087 0.006017386 -0.04499995 0.05813932 0.005911469 -0.04499995 0.05785989 0.005960762 -0.06499999 0.05896514 0.005671143 -0.04499995 0.05872172 0.005759775 -0.06499999 0.0598306 0.005237638 -0.06499999 0.06044816 0.004763007 -0.04499995 0.05975437 0.005271255 -0.04499995 0.06115484 0.003992617 -0.04499995 0.06076598 0.004456043 -0.06499999 0.06140178 0.003626585 -0.06499999 0.06176221 0.002935528 -0.04499995 0.06191545 0.0025146 -0.06499999 0.06208372 0.001752674 -0.04499995 0.06212967 0.001315772 -0.06499999 0.06210285 4.54471e-4 -0.06499999 0.06212961 7.06486e-4 -0.04499995 0.06193226 -4.12471e-4 -0.06499999 0.06191551 -4.91447e-4 -0.04499995 0.06147956 -0.001462399 -0.04499995 0.06144881 -0.001539409 -0.06499999 0.06070154 -0.002499997 -0.06499999 0.06099653 -0.00217235 -0.04499995 0.06004571 -0.003054678 -0.06499999 0.05967414 -0.003302633 -0.04499995 0.06037187 -0.002799868 -0.04499995 0.05928599 -0.003509044 -0.06499999 0.05812507 -0.003903985 -0.06499999 0.05856138 -0.003795206 -0.04499995 0.05691117 -0.003991484 -0.06499999 0.05735135 -0.003991484 -0.04499995 0.05613732 -0.003903985 -0.04499995 0.05570125 -0.003795266 -0.06499999 0.05497664 -0.003509104 -0.04499995 0.05458801 -0.003302454 -0.06499999 0.05394637 -0.002862274 -0.04499995 0.05361169 -0.002560913 -0.06499999 0.0531063 -0.001968145 -0.04499995 0.05286061 -0.001603782 -0.06499999 0.05264872 -0.001210033 -0.04499995 0.05233025 -4.1265e-4 -0.04499995 0.05234682 -4.91187e-4 -0.06499999 0.05673313 0.009509921 -0.04499995 0.05752938 0.009509921 -0.02999997 0.05811333 0.009462296 -0.04499995 0.05890101 0.009333133 -0.02999997 0.05969607 0.009130954 -0.04499995 0.06043237 0.008860468 -0.02999997 0.06116914 0.008499979 -0.04499995 0.06185364 0.008088171 -0.02999997 0.06232839 0.007747292 -0.04499995 0.06293696 0.00723046 -0.02999997 0.06335091 0.006816446 -0.04499995 0.06386727 0.006208419 -0.02999997 0.06420773 0.005734264 -0.04499995 0.06462025 0.005048573 -0.02999997 0.06498014 0.004312872 -0.04499995 0.06525087 0.00357604 -0.02999997 0.06545305 0.002781033 -0.04499995 0.06558215 0.001993775 -0.02999997 0.06565243 0.001011967 -0.04499995 0.06563121 0.001011312 -0.02999997 0.056149 0.009462296 -0.02999997 0.05536162 0.009333193 -0.04499995 0.05456596 0.009130835 -0.02999997 0.05403715 0.008936703 -0.04499995 0.05260324 0.008222758 -0.04499995 0.05309319 0.00849992 -0.02999997 0.05193352 0.007746934 -0.02999997 0.05132639 0.007231295 -0.04499995 0.0509116 0.006816506 -0.02999997 0.05039578 0.006209254 -0.04499995 0.0499199 0.005539476 -0.02999997 0.04964226 0.005048692 -0.04499995 0.04920583 0.004105389 -0.02999997 0.04901164 0.003576397 -0.04499995 0.04886925 0.003020286 -0.02999997 0.04868024 0.001993656 -0.04499995 0.04866772 0.001878798 -0.02999997 0.04863119 0.001011312 -0.04499995 0.04863119 0.001011312 -0.02999997 0.190874 -0.01656538 -0.02999997 0.197359 -0.017084 -0.02999997 0.2319384 -0.01018166 -0.02999997 0.04029858 -0.01090759 -0.02999997 0.04077887 -0.01081144 -0.02999997 0.03834515 -0.01105368 -0.02999997 0.177928 -0.01433068 -0.02999997 0.177898 -0.01559758 -0.02999997 0.184387 -0.01606988 -0.02999997 0.223275 -0.0193901 -0.02999997 0.257468 -0.01179307 -0.02999997 0.216799 -0.0187788 -0.02999997 0.0732429 0.01620966 -0.02999997 0.0598855 0.01614201 -0.02999997 0.02388638 -0.01153767 -0.02999997 0.02941846 -0.011608 -0.02999997 0.03496736 -0.01097434 -0.02999997 -0.003762245 -0.0108332 -0.02999997 0.04676097 -0.006807029 -0.02999997 0.04703265 -0.006399393 -0.02999997 0.210321 -0.01819068 -0.02999997 0.203841 -0.01762574 -0.02999997 0.04582846 -0.007945358 -0.02999997 0.007294774 -0.01118564 -0.02999997 0.04548305 -0.008291542 -0.02999997 -0.01481616 -0.01038658 -0.02999997 1.06042e-5 -2.6572e-7 -0.02999997 -0.02034187 -0.0101279 -0.02999997 0.275 -0.02147608 -0.02999997 0.283 -0.02147608 -0.02999997 0.283 -0.01344305 -0.02999997 -0.02586686 -0.009845674 -0.02999997 0.08463299 8.63139e-4 -0.02999997 0.162209 -0.001754939 -0.02999997 0.1622959 -0.001449942 -0.02999997 0.236219 -0.02068209 -0.02999997 0.229748 -0.02002447 -0.02999997 -0.03139108 -0.009539961 -0.02999997 -0.03691446 -0.009210646 -0.02999997 0.242688 -0.0213629 -0.02999997 0.1621067 -0.002411246 -0.02999997 0.162147 -0.002064168 -0.02999997 -0.05899995 -0.005724668 -0.02999997 -0.04243695 -0.008857786 -0.02999997 0.249155 -0.02206677 -0.02999997 0.25562 -0.02279376 -0.02999997 0.162371 0.003913342 -0.02999997 0.164901 0.001121103 -0.02999997 0.165207 0.001203775 -0.02999997 0.165834 0.001295208 -0.02999997 0.166151 0.001303613 -0.02999997 0.268542 -0.0243175 -0.02999997 0.275 -0.02511399 -0.02999997 0.159243 -0.01328057 -0.02999997 0.156834 -0.01383548 -0.02999997 0.1589199 -0.01343286 -0.02999997 0.262082 -0.02354407 -0.02999997 0.170045 -0.0103054 -0.02999997 0.17013 -0.01064568 -0.02999997 0.2276086 -0.009255111 -0.02999997 0.17024 -0.0109812 -0.02999997 0.170527 -0.01162159 -0.02999997 0.169983 -0.00996077 -0.02999997 0.2224724 -0.00818783 -0.02999997 0.169946 -0.009612023 -0.02999997 0.1699336 -0.009238541 -0.02999997 0.2151712 -0.006696045 -0.02999997 0.170091 -0.00248754 -0.02999997 0.158246 -0.01366615 -0.02999997 0.158587 -0.01356154 -0.02999997 0.157192 -0.01383095 -0.02999997 0.1575469 -0.01380127 -0.02999997 0.159554 -0.01310598 -0.02999997 0.140594 -0.01345425 -0.02999997 0.170902 -0.01221555 -0.02999997 0.160403 -0.01245439 -0.02999997 0.160651 -0.01219975 -0.02999997 0.130342 -0.01300829 -0.02999997 0.135468 -0.01322269 -0.02999997 0.161449 -0.01102089 -0.02999997 0.161092 -0.01163887 -0.02999997 0.161282 -0.01133614 -0.02999997 0.161929 -0.009311735 -0.02999997 0.1252149 -0.01281118 -0.02999997 0.161882 -0.009664714 -0.02999997 0.07340127 -0.008875906 -0.02999997 0.06732589 -0.007591843 -0.02999997 0.06762117 -0.007998704 -0.02999997 0.109831 -0.01232337 -0.02999997 0.114959 -0.01246869 -0.02999997 0.08439826 -0.009134054 -0.02999997 0.06617701 -0.005368888 -0.02999997 0.06636166 -0.005835771 -0.02999997 0.07363599 0.001121282 -0.02999997 0.06567829 -0.003425359 -0.02999997 0.06576657 -0.003921508 -0.02999997 0.06587898 -0.004410564 -0.02999997 0.1703553 0.002341449 -0.02999997 0.1655189 0.001261949 -0.02999997 0.06561565 -0.002929031 -0.02999997 0.04351615 -0.009753048 -0.02999997 0.04393708 -0.009500265 -0.02999997 0.01282447 -0.01132655 -0.02999997 0.04125607 -0.01069158 -0.02999997 0.0475164 -0.005544066 -0.02999997 0.04772526 -0.005101263 -0.02999997 0.001765847 -0.01102119 -0.02999997 0.04646944 -0.007200837 -0.02999997 0.04855328 -0.001783728 -0.02999997 0.04857718 -0.001291155 -0.02999997 0.04807829 -0.004183888 -0.02999997 0.04821979 -0.003715455 -0.02999997 3.94411e-4 0.001166701 -0.02999997 0.04864299 0.00145924 -0.02999997 6.34983e-4 0.001500666 -0.02999997 0.06416475 0.005783677 -0.02999997 0.001025974 0.001970827 -0.02999997 0.04868137 0.00193274 -0.02999997 0.04894047 0.003282487 -0.02999997 0.002743959 0.003620266 -0.02999997 0.04882955 0.002836883 -0.02999997 0.04874324 0.002386987 -0.02999997 0.001902341 0.002869606 -0.02999997 0.001499652 0.002472937 -0.02999997 0.04907578 0.0037238 -0.02999997 0.003633856 0.004313886 -0.02999997 0.003182888 0.003974199 -0.02999997 0.06227296 0.007779479 -0.02999997 0.1243683 0.01091343 -0.02999997 0.06189906 0.008047997 -0.02999997 0.005232036 0.005349814 -0.02999997 0.004571974 0.004950523 -0.02999997 0.04941576 0.004577815 -0.02999997 0.004096865 0.004639327 -0.02999997 0.04923444 0.004156351 -0.02999997 0.1197237 0.01166719 -0.02999997 0.1158432 0.01226437 -0.02999997 0.06027615 0.008908092 -0.02999997 0.04962044 0.004990756 -0.02999997 0.05009448 0.005779206 -0.02999997 0.007787525 0.006698429 -0.02999997 0.009287953 0.007383406 -0.02999997 0.05036306 0.006153106 -0.02999997 0.01163572 0.008339047 -0.02999997 0.01042383 0.007863402 -0.02999997 0.05128389 0.007180213 -0.02999997 0.1105226 0.01303452 -0.02999997 0.0589568 0.009312927 -0.02999997 0.0594024 0.009202063 -0.02999997 0.05162805 0.007489323 -0.02999997 0.01254087 0.008678793 -0.02999997 0.05235886 0.008044898 -0.02999997 0.01392823 0.009167194 -0.02999997 0.0519858 0.007776916 -0.02999997 0.05804735 0.009461581 -0.02999997 0.09724402 0.01465296 -0.02999997 0.05274796 0.008293807 -0.02999997 0.01954478 0.01085716 -0.02999997 0.05485469 0.009200632 -0.02999997 0.0208382 0.01119387 -0.02999997 0.01825547 0.01050448 -0.02999997 0.01697176 0.01013225 -0.02999997 0.05398327 0.008906722 -0.02999997 0.0227459 0.01166129 -0.02999997 0.05575555 0.009399294 -0.02999997 0.05530166 0.009311854 -0.02999997 0.0562098 0.009461104 -0.02999997 0.0566684 0.009498476 -0.02999997 0.02793151 0.01276731 -0.02999997 0.02533698 0.01224106 -0.02999997 0.05758929 0.009498894 -0.02999997 0.08123975 0.01591217 -0.02999997 0.07857072 0.016038 -0.02999997 0.03059035 0.01325654 -0.02999997 0.04125154 0.0147866 -0.02999997 0.03857594 0.01446127 -0.02999997 0.05713117 0.009511351 -0.02999997 0.0359162 0.01410073 -0.02999997 0.04787731 0.0154432 -0.02999997 0.04588085 0.0152657 -0.02999997 0.0439096 0.01507449 -0.02999997 0.05722051 0.01603943 -0.02999997 0.05521196 0.01594156 -0.02999997 0.05054259 0.01565146 -0.02999997 0.06188976 0.01619845 -0.02999997 0.07056987 0.01625442 -0.02999997 0.06589907 0.01626259 -0.02999997 0.06390106 0.01623994 -0.02999997 0.06790369 0.01627051 -0.02999997 0.07590764 0.01613736 -0.02999997 0.05321705 0.01582938 -0.02999997 0.03325742 0.01370078 -0.02999997 0.08660739 0.01558315 -0.02999997 0.05441617 0.009066045 -0.02999997 0.09194839 0.01516032 -0.02999997 0.05355966 0.008724331 -0.02999997 0.05314844 0.008520483 -0.02999997 0.01569205 0.009742915 -0.02999997 0.1025311 0.01406478 -0.02999997 0.05850535 0.009399414 -0.02999997 0.1078584 0.01339584 -0.02999997 0.1051825 0.01374101 -0.02999997 0.05095875 0.00685507 -0.02999997 0.05065268 0.006513893 -0.02999997 0.1131961 0.01265525 -0.02999997 0.05984365 0.00906676 -0.02999997 0.006809294 0.006210863 -0.02999997 0.0498476 0.005392909 -0.02999997 0.06069767 0.008726716 -0.02999997 0.00231713 0.003252089 -0.02999997 0.06297498 0.00718379 -0.02999997 0.06330007 0.006858646 -0.02999997 2.0015e-4 8.25737e-4 -0.02999997 4.488e-5 3.7929e-4 -0.02999997 9.54136e-5 5.63601e-4 -0.02999997 1.63217e-5 1.91332e-4 -0.02999997 0.04850566 -0.002272009 -0.02999997 0.04843449 -0.002755939 -0.02999997 0.04833859 -0.003239035 -0.02999997 0.04791289 -0.004647016 -0.02999997 0.04728525 -0.005977213 -0.02999997 -0.009289622 -0.01062166 -0.02999997 0.0461573 -0.00758183 -0.02999997 0.04473894 -0.008934557 -0.02999997 0.04511785 -0.008622944 -0.02999997 0.161593 -0.01069468 -0.02999997 0.06862229 -0.009121596 -0.02999997 0.06826949 -0.008764028 -0.02999997 0.03981506 -0.01097989 -0.02999997 0.03932827 -0.01102834 -0.02999997 0.04172575 -0.01054877 -0.02999997 0.04218655 -0.01038324 -0.02999997 0.03883838 -0.01105296 -0.02999997 0.01835495 -0.01144385 -0.02999997 0.03495138 -0.01165467 -0.02999997 0.04264038 -0.01019477 -0.02999997 0.04308485 -0.009984254 -0.02999997 0.06937837 -0.009781301 -0.02999997 0.06556457 -0.001886844 -0.02999997 0.163287 1.5081e-4 -0.02999997 0.163071 -7.98112e-5 -0.02999997 -0.01749116 4.75366e-4 -0.02999997 -0.03499358 9.2959e-4 -0.02999997 -0.05249649 0.001362383 -0.02999997 -0.06999999 0.001773774 -0.02999997 -0.06999999 -0.005724668 -0.02999997 -0.05347979 -0.008081495 -0.02999997 -0.04795879 -0.008481442 -0.02999997 -0.05899995 -0.007658004 -0.02999997 0.0697804 -0.01008164 -0.02999997 0.1664659 0.001286745 -0.02999997 0.06601536 -0.004891932 -0.02999997 0.07019805 -0.01036238 -0.02999997 0.06656879 -0.006291329 -0.02999997 0.06679999 -0.006738245 -0.02999997 0.162406 -0.00115323 -0.02999997 0.163771 5.58458e-4 -0.02999997 0.163522 3.64961e-4 -0.02999997 0.161714 -0.01035827 -0.02999997 0.16181 -0.01001524 -0.02999997 0.154433 0.005455017 -0.02999997 0.04434639 -0.009226381 -0.02999997 0.06793648 -0.008390188 -0.02999997 0.06543177 0.002840876 -0.02999997 0.1473798 0.006797969 -0.02999997 0.1619499 -0.008954226 -0.02999997 0.06502658 0.004159271 -0.02999997 0.0651859 0.003726363 -0.02999997 0.1407272 0.00803852 -0.02999997 0.120087 -0.01263135 -0.02999997 0.0646404 0.004994094 -0.02999997 0.06441366 0.005394577 -0.02999997 0.1341601 0.009226143 -0.02999997 0.06389677 0.006156802 -0.02999997 0.06360918 0.00651443 -0.02999997 0.1288828 0.01015055 -0.02999997 0.06263375 0.00748986 -0.02999997 0.06151276 0.008294999 -0.02999997 0.164604 0.001014769 -0.02999997 0.06111055 0.008522033 -0.02999997 0.06563121 0.001011312 -0.02999997 0.164037 7.33008e-4 -0.02999997 0.164314 8.84626e-4 -0.02999997 0.06532049 0.003287851 -0.02999997 0.06484431 0.004582881 -0.02999997 0.09988892 0.01436847 -0.02999997 0.09458309 0.01491844 -0.02999997 0.08928322 0.01538282 -0.02999997 0.08391624 0.01576048 -0.02999997 0.06551915 0.002386987 -0.02999997 0.06558096 0.00193274 -0.02999997 0.06557786 -0.002428889 -0.02999997 0.166781 0.001245021 -0.02999997 0.167689 9.73439e-4 -0.02999997 0.1673949 0.001087605 -0.02999997 0.09957337 -0.01208436 -0.02999997 0.104703 -0.01219528 -0.02999997 0.09444379 -0.01199078 -0.02999997 0.06899285 -0.009461581 -0.02999997 0.08931368 -0.01191437 -0.02999997 0.07062739 -0.01062065 -0.02999997 0.08418327 -0.0118553 -0.02999997 0.07905226 -0.0118134 -0.02999997 0.07106935 -0.01085716 -0.02999997 0.07152479 -0.01107209 -0.02999997 0.07342576 -0.01169306 -0.02999997 0.07392096 -0.01178866 -0.02999997 0.07245939 -0.01143026 -0.02999997 0.07293856 -0.01157355 -0.02999997 0.0719881 -0.01126307 -0.02999997 0.1608819 -0.01192677 -0.02999997 0.170062 -0.00217086 -0.02999997 0.1813483 1.49909e-4 -0.02999997 0.160135 -0.01269215 -0.02999997 0.159853 -0.01290899 -0.02999997 0.1994526 -0.003503262 -0.02999997 0.157898 -0.01374638 -0.02999997 0.172778 -0.01377028 -0.02999997 0.173101 -0.01391118 -0.02999997 0.173771 -0.01412177 -0.02999997 0.174116 -0.01419168 -0.02999997 0.174816 -0.01425766 -0.02999997 0.170372 -0.01130557 -0.02999997 0.172167 -0.01342356 -0.02999997 0.1724669 -0.01360827 -0.02999997 0.171611 -0.01299506 -0.02999997 0.171881 -0.01321905 -0.02999997 0.17112 -0.01249259 -0.02999997 0.171356 -0.01275169 -0.02999997 0.170704 -0.01192539 -0.02999997 0.170008 -0.001859724 -0.02999997 0.16993 -0.001551866 -0.02999997 0.169827 -0.00125283 -0.02999997 0.169701 -9.61596e-4 -0.02999997 0.06705266 -0.007172405 -0.02999997 0.169553 -6.82187e-4 -0.02999997 0.169382 -4.14805e-4 -0.02999997 0.169192 -1.62009e-4 -0.02999997 0.168982 7.48203e-5 -0.02999997 0.168753 2.9463e-4 -0.02999997 0.168509 4.95057e-4 -0.02999997 0.1682479 6.76295e-4 -0.02999997 0.167975 8.35428e-4 -0.02999997 0.162873 -3.28075e-4 -0.02999997 0.162696 -5.90147e-4 -0.02999997 0.06561839 0.001474201 -0.02999997 0.1670899 0.001178622 -0.02999997 0.1734319 -0.01402807 -0.02999997 0.174464 -0.01423674 -0.02999997 0.16254 -8.66177e-4 -0.02999997 0.08386594 -0.01197534 -0.03518593 0.07904887 -0.01181316 -0.03337466 0.1405869 -0.01345413 -0.03046888 0.1401436 -0.01344364 -0.03092843 0.1402881 -0.01344728 -0.0308398 0.1404241 -0.01345032 -0.03073441 0.1399184 -0.01343917 -0.03104305 0.140554 -0.0134533 -0.03057026 0.1405079 -0.01345217 -0.0306434 0.135468 -0.01322269 -0.02999997 0.1394783 -0.01342803 -0.03122347 0.1389265 -0.01341509 -0.03140753 0.1384368 -0.01340353 -0.03155153 0.1378544 -0.01338988 -0.03170675 0.1371667 -0.01337373 -0.03187263 0.1362638 -0.01335251 -0.03207099 0.135237 -0.01332849 -0.0322737 0.1343024 -0.01330655 -0.03244388 0.1295197 -0.01297843 -0.02999985 0.128834 -0.01306676 -0.03269612 0.1334733 -0.01328665 -0.03258514 0.1323539 -0.0132606 -0.03276467 0.1296287 -0.01319754 -0.0331577 0.1264656 -0.01312237 -0.03355538 0.1164458 -0.01250612 -0.03128248 0.1232901 -0.01304769 -0.03390836 0.1170718 -0.01264888 -0.03331863 0.1201568 -0.01297444 -0.03421968 0.1170467 -0.012901 -0.03449755 0.1138957 -0.01282763 -0.03475069 0.1018689 -0.0122385 -0.0341463 0.1075699 -0.01267898 -0.03518134 0.1107391 -0.0127533 -0.03497815 0.1044274 -0.01260507 -0.0353589 0.1012762 -0.01253122 -0.0355125 0.09813207 -0.01245707 -0.03564161 0.09496933 -0.01238298 -0.03574514 0.09182727 -0.01230913 -0.0358209 0.08865672 -0.0122348 -0.03586792 0.08552747 -0.01216197 -0.03588312 0.08233344 -0.01208567 -0.03586304 0.07913869 -0.01201087 -0.03579938 0.07690238 -0.01195895 -0.03571796 0.07514858 -0.01191556 -0.03561466 0.07533025 -0.011922 -0.03563886 0.0749709 -0.0119065 -0.03557145 0.07412147 -0.01182007 -0.03491795 0.07403737 -0.01180738 -0.03475528 0.0747978 -0.01189535 -0.0355131 0.07463461 -0.01188135 -0.03542965 0.07448345 -0.01186615 -0.03532689 0.07434648 -0.01185035 -0.03520596 0.07422518 -0.01183468 -0.03506898 0.07397568 -0.01179766 -0.03458297 0.0739367 -0.01179134 -0.03440368 0.07391947 -0.01178842 -0.03421896 0.09260928 -0.01195091 -0.02999997 0.07392102 -0.01178795 -0.02999997 0.08929634 -0.01190829 -0.03280693 0.1021119 -0.01213502 -0.03209489 0.1123946 -0.01238507 -0.02999997 0.140594 -0.01345425 -0.02999997 0.1405869 -0.01345402 -0.03046888 0.156834 -0.01383548 -0.02999997 0.140594 -0.01345425 -0.02999997 0.1359251 -0.01334452 -0.03213965 0.120157 -0.0129745 -0.03421968 0.1170485 -0.01290142 -0.03449732 0.156834 -0.01383548 -0.04499995 0.1232863 -0.01304793 -0.03390872 0.140554 -0.0134533 -0.03057026 0.1405079 -0.01345217 -0.0306434 0.1404241 -0.01345026 -0.03073441 0.1402881 -0.01344686 -0.03083974 0.1401436 -0.01344358 -0.03092843 0.1399179 -0.01343834 -0.03104329 0.1394783 -0.01342803 -0.03122347 0.1389264 -0.01341509 -0.03140759 0.1383563 -0.01340162 -0.0315743 0.1376425 -0.01338505 -0.03175961 0.136793 -0.01336497 -0.03195732 0.1351296 -0.01332598 -0.03229367 0.1341204 -0.0133022 -0.03247606 0.1330158 -0.01327633 -0.0326597 0.1320999 -0.01325482 -0.03280335 0.1296263 -0.0131967 -0.03315818 0.1264641 -0.01312249 -0.03355556 0.1138911 -0.01282733 -0.03475111 0.1107375 -0.0127533 -0.03497821 0.1075698 -0.01267892 -0.03518134 0.1044274 -0.01260507 -0.0353589 0.07533025 -0.011922 -0.04499995 0.1012753 -0.01253116 -0.03551256 0.09812855 -0.01245725 -0.03564167 0.09496557 -0.01238292 -0.03574526 0.09182935 -0.01230937 -0.03582078 0.08866 -0.01223498 -0.03586786 0.08553093 -0.01216149 -0.03588318 0.08233588 -0.01208651 -0.03586292 0.07913953 -0.01201146 -0.03579926 0.07690238 -0.01195895 -0.03571796 0.07533025 -0.011922 -0.03563886 0.03414589 -0.04596477 -0.04499995 0.03834515 -0.01105368 -0.04499995 0.03496736 -0.01097434 -0.04499995 0.177106 -0.04932105 -0.04499995 0.177928 -0.01433068 -0.04499995 0.174816 -0.01425766 -0.04499995 0.1582469 -0.01366585 -0.04499995 0.1579 -0.0137459 -0.04499995 0.173435 -0.01402896 -0.04499995 0.161282 -0.01133495 -0.04499995 0.161094 -0.01163697 -0.04499995 0.1705279 -0.01162296 -0.04499995 0.174464 -0.01423674 -0.04499995 0.159853 -0.01290845 -0.04499995 0.159556 -0.01310485 -0.04499995 0.171883 -0.01322066 -0.04499995 0.159245 -0.01327979 -0.04499995 0.158922 -0.0134322 -0.04499995 0.172468 -0.01360887 -0.04499995 0.171121 -0.01249325 -0.04499995 0.170903 -0.01221776 -0.04499995 0.1606529 -0.01219797 -0.04499995 0.171612 -0.01299577 -0.04499995 0.171358 -0.0127539 -0.04499995 0.1601369 -0.01269066 -0.04499995 0.170705 -0.01192736 -0.04499995 0.160883 -0.01192617 -0.04499995 0.170373 -0.01130837 -0.04499995 0.17024 -0.01098167 -0.04499995 0.16145 -0.01101905 -0.04499995 0.170131 -0.01064848 -0.04499995 0.161594 -0.01069289 -0.04499995 0.161715 -0.0103569 -0.04499995 0.170045 -0.01030749 -0.04499995 0.161882 -0.009664714 -0.04499995 0.169946 -0.009612023 -0.04499995 0.161929 -0.009311735 -0.04499995 0.169983 -0.00996077 -0.04499995 0.1618109 -0.0100131 -0.04499995 0.168905 -0.001641333 -0.04499995 0.16993 -0.001554131 -0.04499995 0.168799 -0.001393795 -0.04499995 0.1699336 -0.009238541 -0.04499995 0.1619499 -0.008954226 -0.04499995 0.163205 -0.001898705 -0.04499995 0.1632879 -0.001642167 -0.04499995 0.16221 -0.001752614 -0.04499995 0.1621067 -0.002411246 -0.04499995 0.163109 -0.002426207 -0.04499995 0.163145 -0.002160489 -0.04499995 0.163521 -0.00115776 -0.04499995 0.162541 -8.64551e-4 -0.04499995 0.162407 -0.001151263 -0.04499995 0.163394 -0.001395046 -0.04499995 0.165169 1.56851e-4 -0.04499995 0.1654289 2.28718e-4 -0.04499995 0.164037 7.33008e-4 -0.04499995 0.165962 3.00953e-4 -0.04499995 0.1652089 0.001204133 -0.04499995 0.1649039 0.001121759 -0.04499995 0.165693 2.76681e-4 -0.04499995 0.1643159 8.85726e-4 -0.04499995 0.164604 0.001015067 -0.04499995 0.165521 0.001262187 -0.04499995 0.165835 0.001295387 -0.04499995 0.163773 5.59926e-4 -0.04499995 0.164918 6.2542e-5 -0.04499995 0.163522 3.65381e-4 -0.04499995 0.1646749 -5.4655e-5 -0.04499995 0.163289 1.52518e-4 -0.04499995 0.164444 -1.9235e-4 -0.04499995 0.163072 -7.88719e-5 -0.04499995 0.1642259 -3.5102e-4 -0.04499995 0.06557786 -0.002426624 -0.04499995 0.06072878 -0.002460777 -0.04499995 0.06561529 -0.002924263 -0.04499995 0.162874 -3.26305e-4 -0.04499995 0.162697 -5.88672e-4 -0.04499995 0.164023 -5.27935e-4 -0.04499995 0.0693354 -0.009747207 -0.04499995 0.06895345 -0.00942713 -0.04499995 0.04434728 -0.009225666 -0.04499995 0.05963218 -0.00331813 -0.04499995 0.05932408 -0.003481924 -0.04499995 0.06587427 -0.00439167 -0.04499995 0.163669 -9.33195e-4 -0.04499995 0.169384 -4.16226e-4 -0.04499995 0.168355 -7.21587e-4 -0.04499995 0.1695539 -6.83772e-4 -0.04499995 0.163837 -7.22707e-4 -0.04499995 0.1622959 -0.00144869 -0.04499995 0.162147 -0.002064168 -0.04499995 0.1697019 -9.63498e-4 -0.04499995 0.168672 -0.001156687 -0.04499995 0.1698279 -0.001254081 -0.04499995 0.163097 -0.002695977 -0.04499995 0.168988 -0.001897156 -0.04499995 0.170008 -0.001859724 -0.04499995 0.174116 -0.01419168 -0.04499995 0.157192 -0.01383095 -0.04499995 0.160403 -0.01245439 -0.04499995 0.172169 -0.01342505 -0.04499995 0.172781 -0.01377165 -0.04499995 0.158589 -0.01356089 -0.04499995 0.173102 -0.01391136 -0.04499995 0.1575469 -0.01380127 -0.04499995 0.173773 -0.01412236 -0.04499995 0.156834 -0.01383548 -0.04499995 0.07533025 -0.011922 -0.04499995 0.07482886 -0.01189738 -0.04499995 0.07433229 -0.01184839 -0.04499995 0.07384049 -0.01177495 -0.04499995 0.07286536 -0.01155328 -0.04499995 0.04078358 -0.01081049 -0.04499995 0.04030209 -0.01090687 -0.04499995 0.07335031 -0.01167619 -0.04499995 0.07145935 -0.01104277 -0.04499995 0.04172849 -0.01054769 -0.04499995 0.0719217 -0.01123738 -0.04499995 0.04125809 -0.01069116 -0.04499995 0.07238936 -0.01140707 -0.04499995 0.04308664 -0.009983181 -0.04499995 0.04264318 -0.01019364 -0.04499995 0.07057285 -0.01058959 -0.04499995 0.04219108 -0.01038157 -0.04499995 0.07100975 -0.01082688 -0.04499995 0.04394018 -0.009498417 -0.04499995 0.06973236 -0.01004737 -0.04499995 0.0701456 -0.01032865 -0.04499995 0.04352027 -0.009750664 -0.04499995 0.04512107 -0.008620321 -0.04499995 0.04474246 -0.008931696 -0.04499995 0.06858599 -0.00908631 -0.04499995 0.06790846 -0.008357286 -0.04499995 0.0458312 -0.007942318 -0.04499995 0.04548305 -0.008291542 -0.04499995 0.0682376 -0.008729696 -0.04499995 0.06703406 -0.007142186 -0.04499995 0.04647016 -0.007200002 -0.04499995 0.06730425 -0.007559955 -0.04499995 0.04616028 -0.007578432 -0.04499995 0.06759607 -0.007965445 -0.04499995 0.05867767 -0.00374335 -0.04499995 0.05834084 -0.003840088 -0.04499995 0.0661692 -0.005347788 -0.04499995 0.05765467 -0.003961026 -0.04499995 0.06635087 -0.00581032 -0.04499995 0.0580008 -0.003912329 -0.04499995 0.06047707 -0.002704143 -0.04499995 0.0656771 -0.00341767 -0.04499995 0.06117689 -0.0019266 -0.04499995 0.0609619 -0.002201914 -0.04499995 0.06556457 -0.001886963 -0.04499995 0.06169945 -0.001020967 -0.04499995 0.0618298 -6.98342e-4 -0.04499995 0.0613721 -0.00163716 -0.04499995 0.05433547 -0.003133952 -0.04499995 0.04822099 -0.003710865 -0.04499995 0.05463248 -0.003319323 -0.04499995 0.06208246 3.1494e-4 -0.04499995 0.06202208 -2.72721e-5 -0.04499995 0.06563121 0.001011312 -0.04499995 0.04868137 0.00193274 -0.04499995 0.04864299 0.00145924 -0.04499995 0.05217999 0.00170803 -0.04499995 0.05214369 0.001361787 -0.04499995 0.05232459 0.002387881 -0.04499995 0.04874324 0.002386987 -0.04499995 0.05224025 0.002050042 -0.04499995 0.06020849 0.004952073 -0.04499995 0.06047618 0.004727602 -0.04499995 0.06441485 0.005392909 -0.04499995 0.04923576 0.004159271 -0.04499995 0.05289059 0.003660202 -0.04499995 0.05308526 0.003948807 -0.04499995 0.05330097 0.004225254 -0.04499995 0.04962205 0.004994094 -0.04499995 0.04941815 0.004582881 -0.04499995 0.05096238 0.006858646 -0.04499995 0.05065315 0.00651443 -0.04499995 0.05525708 0.005646646 -0.04499995 0.05463117 0.00534147 -0.04499995 0.05493807 0.005504608 -0.04499995 0.05198937 0.007779479 -0.04499995 0.05591994 0.005862295 -0.04499995 0.05626296 0.00593537 -0.04499995 0.05558526 0.005766332 -0.04499995 0.05128747 0.00718379 -0.04499995 0.05398619 0.008908092 -0.04499995 0.05356478 0.008726716 -0.04499995 0.05695545 0.006008148 -0.04499995 0.05236339 0.008047997 -0.04499995 0.05660706 0.00598371 -0.04499995 0.05274969 0.008294999 -0.04499995 0.05575698 0.009399414 -0.04499995 0.05530565 0.009312927 -0.04499995 0.05896079 0.009311854 -0.04499995 0.05486005 0.009202063 -0.04499995 0.05940777 0.009200632 -0.04499995 0.05759406 0.009498476 -0.04499995 0.05713117 0.009511351 -0.04499995 0.05667316 0.009498894 -0.04499995 0.0585069 0.009399294 -0.04499995 0.05805265 0.009461104 -0.04499995 0.05621504 0.009461581 -0.04499995 0.05984628 0.009066045 -0.04499995 0.05315178 0.008522033 -0.04499995 0.0544188 0.00906676 -0.04499995 0.05162858 0.00748986 -0.04499995 0.05036568 0.006156802 -0.04499995 0.05433386 0.005155444 -0.04499995 0.05405229 0.004950821 -0.04499995 0.04984879 0.005394577 -0.04499995 0.05378466 0.004726111 -0.04499995 0.0500977 0.005783677 -0.04499995 0.05353355 0.00448352 -0.04499995 0.04907649 0.003726363 -0.04499995 0.06154555 0.003359436 -0.04499995 0.06532198 0.003282487 -0.04499995 0.06518656 0.0037238 -0.04499995 0.05271595 0.003357529 -0.04499995 0.04883068 0.002840876 -0.04499995 0.05243277 0.002721428 -0.04499995 0.04894185 0.003287851 -0.04499995 0.05256295 0.003043651 -0.04499995 0.06551915 0.002386987 -0.04499995 0.06543278 0.002836883 -0.04499995 0.06193709 0.002390921 -0.04499995 0.06389939 0.006153106 -0.04499995 0.05992585 0.005157291 -0.04499995 0.06416785 0.005779206 -0.04499995 0.06464189 0.004990756 -0.04499995 0.0607267 0.004485785 -0.04499995 0.06096148 0.004225254 -0.04499995 0.0611754 0.00395143 -0.04499995 0.06502795 0.004156351 -0.04499995 0.06484657 0.004577815 -0.04499995 0.06137067 0.00366193 -0.04499995 0.06169807 0.003046512 -0.04499995 0.06558096 0.00193274 -0.04499995 0.06208235 0.00170803 -0.04499995 0.06561839 0.001474201 -0.04499995 0.06182968 0.002721428 -0.04499995 0.06193774 -3.65482e-4 -0.04499995 0.06154608 -0.00133568 -0.04499995 0.06021058 -0.00292772 -0.04499995 0.05992758 -0.003133416 -0.04499995 0.06576347 -0.003906786 -0.04499995 0.06600958 -0.004872262 -0.04499995 0.0590049 -0.00362426 -0.04499995 0.06655597 -0.006264388 -0.04499995 0.05730664 -0.003985464 -0.04499995 0.05695807 -0.003985464 -0.04499995 0.03981506 -0.01097989 -0.04499995 0.03883838 -0.01105296 -0.04499995 0.03932827 -0.01102834 -0.04499995 0.167277 -0.005454063 -0.04499995 0.167519 -0.005337536 -0.04499995 0.169085 -0.002426207 -0.04499995 0.169097 -0.002695977 -0.04499995 0.170091 -0.00248754 -0.04499995 0.168524 -9.3229e-4 -0.04499995 0.169049 -0.002159953 -0.04499995 0.16817 -5.27432e-4 -0.04499995 0.167967 -3.50003e-4 -0.04499995 0.169193 -1.63714e-4 -0.04499995 0.168983 7.39299e-5 -0.04499995 0.1687549 2.93011e-4 -0.04499995 0.167518 -5.38516e-5 -0.04499995 0.167276 6.26602e-5 -0.04499995 0.168509 4.94668e-4 -0.04499995 0.16825 6.74934e-4 -0.04499995 0.167023 1.57378e-4 -0.04499995 0.166764 2.28854e-4 -0.04499995 0.1676909 9.72457e-4 -0.04499995 0.167975 8.35428e-4 -0.04499995 0.1673949 0.001087367 -0.04499995 0.166499 2.7692e-4 -0.04499995 0.167749 -1.92235e-4 -0.04499995 0.166231 3.00953e-4 -0.04499995 0.167092 0.001178085 -0.04499995 0.166469 0.001286625 -0.04499995 0.166782 0.001244723 -0.04499995 0.166152 0.001303493 -0.04499995 0.170062 -0.00217086 -0.04499995 0.169085 -0.002965867 -0.04499995 0.163522 -0.004234969 -0.04499995 0.16367 -0.004460036 -0.04499995 0.169049 -0.003231585 -0.04499995 0.168989 -0.00349307 -0.04499995 0.168906 -0.003749966 -0.04499995 0.1687999 -0.00399667 -0.04499995 0.168672 -0.004234433 -0.04499995 0.168356 -0.004669547 -0.04499995 0.168524 -0.004458427 -0.04499995 0.167968 -0.005041241 -0.04499995 0.168171 -0.004863619 -0.04499995 0.16775 -0.005199074 -0.04499995 0.167024 -0.005548954 -0.04499995 0.166765 -0.005620479 -0.04499995 0.1665 -0.005668699 -0.04499995 0.166232 -0.005692839 -0.04499995 0.1659629 -0.005692958 -0.04499995 0.16543 -0.005620896 -0.04499995 0.165695 -0.005668818 -0.04499995 0.164918 -0.005454838 -0.04499995 0.165171 -0.005549311 -0.04499995 0.164445 -0.005200088 -0.04499995 0.164676 -0.005338013 -0.04499995 0.1640239 -0.004864871 -0.04499995 0.164227 -0.005041778 -0.04499995 0.163838 -0.004670143 -0.04499995 0.163394 -0.003998398 -0.04499995 0.163205 -0.003494977 -0.04499995 0.1632879 -0.003750324 -0.04499995 0.163109 -0.002965867 -0.04499995 0.163145 -0.003231763 -0.04499995 0.05256408 -0.001023471 -0.04499995 0.05243307 -6.99361e-4 -0.04499995 0.04857718 -0.001291155 -0.04499995 0.05213117 0.001011312 -0.04499995 0.06360977 0.006513893 -0.04499995 0.05963116 0.00534147 -0.04499995 0.05932146 0.005505919 -0.04499995 0.0633037 0.00685507 -0.04499995 0.05900347 0.00564754 -0.04499995 0.05867505 0.005766868 -0.04499995 0.0629785 0.007180213 -0.04499995 0.06263428 0.007489323 -0.04499995 0.05833935 0.00586313 -0.04499995 0.05799949 0.00593537 -0.04499995 0.06227666 0.007776916 -0.04499995 0.06190359 0.008044898 -0.04499995 0.05765217 0.005984008 -0.04499995 0.06151449 0.008293807 -0.04499995 0.05730485 0.006008327 -0.04499995 0.06111395 0.008520483 -0.04499995 0.0607028 0.008724331 -0.04499995 0.06027907 0.008906722 -0.04499995 0.06202155 0.002052128 -0.04499995 0.06211876 0.001361787 -0.04499995 0.06213116 0.001011312 -0.04499995 0.06211876 6.61153e-4 -0.04499995 0.0483396 -0.003235518 -0.04499995 0.05405408 -0.002929449 -0.04499995 0.05494016 -0.003482937 -0.04499995 0.04807877 -0.004181802 -0.04499995 0.04791408 -0.004644334 -0.04499995 0.05558735 -0.003744184 -0.04499995 0.05525916 -0.003624796 -0.04499995 0.04772716 -0.005096793 -0.04499995 0.05592179 -0.003840088 -0.04499995 0.04751759 -0.005541324 -0.04499995 0.0562644 -0.003912806 -0.04499995 0.04728645 -0.005975425 -0.04499995 0.05660909 -0.003961265 -0.04499995 0.04703527 -0.006395399 -0.04499995 0.046763 -0.006803929 -0.04499995 0.06678456 -0.006710112 -0.04499995 0.04843449 -0.002755939 -0.04499995 0.05378586 -0.00270462 -0.04499995 0.05330175 -0.002203345 -0.04499995 0.0535354 -0.002462685 -0.04499995 0.05308657 -0.001928091 -0.04499995 0.04850566 -0.002272009 -0.04499995 0.04855328 -0.001783728 -0.04499995 0.05289179 -0.001639366 -0.04499995 0.05271655 -0.001336097 -0.04499995 0.05232524 -3.67822e-4 -0.04499995 0.05224084 -2.94072e-5 -0.04499995 0.05214357 6.61153e-4 -0.04499995 0.05217999 3.1494e-4 -0.04499995 0.06563121 0.001011312 -0.02999997 0.06556779 -0.001690089 -0.04499995 0.06556779 -0.001690089 -0.02999997 0.06563121 0.001011312 -0.04499995 0.07309186 -0.01162672 -0.02999997 0.07392078 -0.01178967 -0.02999997 0.06556558 -0.00169003 -0.04499995 0.06556433 -0.00169003 -0.02999997 0.07391935 -0.01178866 -0.03421795 0.07339346 -0.01169753 -0.04499995 0.07397568 -0.01179766 -0.03458297 0.0739367 -0.01179134 -0.03440368 0.07412147 -0.01182007 -0.03491795 0.07403737 -0.01180738 -0.03475528 0.0745908 -0.01188033 -0.04499995 0.07422518 -0.01183468 -0.03506898 0.07448345 -0.01186615 -0.03532689 0.07434648 -0.01185035 -0.03520596 0.07463461 -0.01188135 -0.03542965 0.0749709 -0.0119065 -0.03557145 0.0747978 -0.01189535 -0.0355131 0.07533025 -0.011922 -0.04499995 0.07514858 -0.01191556 -0.03561466 0.07533025 -0.011922 -0.03563886 0.07178592 -0.0111863 -0.02999997 0.0721215 -0.01131629 -0.04499995 0.07096004 -0.01081043 -0.04499995 0.07066559 -0.01065164 -0.02999997 0.06947606 -0.009876549 -0.04499995 0.06960237 -0.00995624 -0.02999997 0.06865167 -0.009161174 -0.02999997 0.06819385 -0.008694291 -0.04499995 0.06779766 -0.008227467 -0.02999997 0.06711953 -0.007307767 -0.04499995 0.06707537 -0.00722438 -0.02999997 0.066477 -0.006103873 -0.02999997 0.06632071 -0.005759 -0.04499995 0.065948 -0.004720985 -0.02999997 0.06578564 -0.004084765 -0.04499995 0.06561416 -0.002991974 -0.02999997 0.06558746 -0.002631723 -0.04499995 + + + + + + + + + + -0.1264415 -0.813645 0.5674456 -0.3206318 -0.8124441 0.4869598 -0.1196663 -0.9187235 0.3763339 -0.3521035 -0.7433026 0.5687921 -0.2860268 -0.9312049 0.2259343 -0.1181392 -0.9799054 0.1607133 -0.5509644 -0.7939894 0.2569417 -0.8089522 -0.545446 0.2192832 -0.6614845 -0.6212289 0.4201345 -0.654277 -0.7493453 0.1019961 -0.9328238 -0.3463336 0.0994625 -0.9181677 -0.3426687 0.1988626 -0.2904212 -0.9514378 0.1020869 -0.9753078 -0.1909292 0.1109989 0 0 -1 -4.81956e-6 0 -1 -2.48193e-6 0 -1 1.6934e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.88817e-7 0 -1 2.93207e-7 0 -1 0 0 -1 -1.62095e-7 0 -1 -8.87684e-7 0 -1 -2.19288e-7 0 -1 5.86021e-7 0 -1 -5.65506e-7 0 -1 1.85655e-7 0 -1 3.69155e-7 0 -1 8.14884e-7 0 -1 -4.20762e-6 0 -1 2.56568e-5 0 -1 2.90833e-6 0 -1 -1.52894e-6 0 -1 1.27563e-6 0 -1 -1.98202e-6 0 -1 -2.74123e-6 0 -1 1.13256e-6 0 -1 -2.97336e-6 0 -1 2.38875e-6 0 -1 6.3919e-6 0 -1 8.48338e-7 0 -1 2.57941e-6 0 -1 -9.39059e-7 0 -1 -0.5162121 -0.7643991 -0.3862892 -0.7278879 -0.6409991 -0.2435143 -0.6620597 -0.6087421 -0.4371614 -0.8275604 -0.5393059 -0.1558619 -0.8141534 -0.5706429 -0.107335 -0.8700897 -0.4903143 -0.05035591 -0.1729214 -0.7597737 -0.6267713 -0.3181305 -0.7965165 -0.5141543 -0.2516639 -0.6510728 -0.7160794 -0.4416751 -0.8880503 -0.1276316 -0.2487937 -0.942346 -0.2237984 -0.2243164 -0.969352 -0.1001946 -0.1134408 -0.9810484 -0.1570837 -0.1125554 -0.9914522 -0.06598287 -0.5956099 -0.5234018 -0.6093435 -0.4599233 -0.6726112 -0.579711 -0.04931974 -0.8230846 -0.5657734 -0.1554649 -0.8672952 -0.4728953 -0.7159639 -0.4936271 -0.4936882 -0.3822187 -0.5374379 -0.7517111 -0.1942832 -0.4470101 -0.8731758 -0.3014137 -0.3438973 -0.8893169 -0.1933684 -0.1900723 -0.9625389 -0.07824981 -0.3078416 -0.9482145 0.01153618 -0.05252325 -0.9985531 -0.0323503 -0.1543966 -0.9874792 -0.07611435 -0.1116384 -0.9908298 -0.009460747 -0.3844443 -0.9230998 -0.3546633 -0.2410099 -0.9033982 -0.05041766 -0.6720938 -0.7387477 -0.05911505 -0.5531243 -0.8309988 -0.488555 -0.3976376 -0.7766585 -0.09430521 -0.9298984 -0.3555216 -0.3336697 -0.8762453 -0.3476476 -0.5604868 -0.3383979 -0.7558713 -0.558355 -0.8070282 -0.1922121 -0.6444464 -0.4328864 -0.630316 -0.6907098 -0.7161017 -0.1005911 -0.7812346 -0.5314642 -0.3274422 0 0 -1 1 0 0 1 1.37455e-4 0 1 1.06322e-4 0 -0.02313458 -0.7067115 0.7071236 -0.02313613 -0.7067346 0.7071004 -1 0 0 0.6728851 -0.7397471 3.54014e-6 0.6728557 -0.7397738 0 0.6726024 -0.7400041 -4.55326e-6 0.6728773 -0.7397541 1.22764e-6 0.6728673 -0.7397632 3.7585e-6 0.6727728 -0.7398492 -2.65705e-6 0.6727544 -0.739866 -3.44713e-6 0.6728179 -0.7398082 0 0.6729168 -0.7397183 1.15073e-5 0.6727419 -0.7398773 -6.60825e-6 0.6728098 -0.7398155 -1.0107e-6 0.672812 -0.7398135 2.08037e-6 0.6728906 -0.7397421 1.95334e-5 0.6727139 -0.7399027 -1.58839e-5 0.6727038 -0.7399119 -2.71113e-5 0.6727277 -0.7398903 -1.53453e-5 0.6728302 -0.739797 9.38789e-6 0.6728748 -0.7397565 1.89231e-5 0.672785 -0.7398381 -8.02546e-6 0.6727682 -0.7398534 -7.51181e-6 0.6731373 -0.7395176 1.12003e-4 0.6726753 -0.7399379 -1.21247e-4 0.6727101 -0.7399062 2.83677e-5 0.6727581 -0.7398626 7.15796e-6 0.6728575 -0.7397722 -1.89705e-5 0.6728203 -0.7398061 -1.41372e-5 0.6728656 -0.7397647 -1.43291e-5 0.6727253 -0.7398923 1.00897e-5 0.6728816 -0.7397503 -2.46072e-5 0.6727976 -0.7398266 -9.11597e-6 0.6726531 -0.739958 2.37545e-5 0.6727557 -0.7398648 0 0.6728283 -0.7397988 -7.72254e-6 0.6728867 -0.7397456 -1.27374e-5 0.672772 -0.7398499 0 0.6727245 -0.7398931 0 0.6728177 -0.7398084 -5.88195e-6 0.6729068 -0.7397274 -4.32698e-6 0.672634 -0.7399754 3.26498e-6 0.6724626 -0.7401311 9.21625e-7 0.6729241 -0.7397116 -5.15603e-5 0.6732787 -0.7393888 2.62697e-4 0.6840796 -0.7294053 0.001788914 0.6705706 -0.7418457 -2.92332e-4 0.6719084 -0.7406343 2.83406e-4 0.6726113 -0.7399961 -2.57587e-5 0.6736375 -0.739062 2.11512e-4 0.6729628 -0.7396764 1.44762e-4 0.6732416 -0.7394226 1.6647e-4 0.6726614 -0.7399505 -1.08117e-4 0.672649 -0.7399618 -5.69096e-6 0.6726716 -0.7399411 -9.45129e-5 0.6726114 -0.739996 -1.11485e-4 0.6728885 -0.739744 1.26222e-4 0.6727444 -0.739875 -4.42668e-5 0.6727827 -0.7398402 3.53936e-6 0.6729691 -0.7396706 1.42266e-4 0.6729012 -0.7397325 -2.33747e-5 0.6726691 -0.7399435 2.02539e-5 0.6727153 -0.7399014 1.58661e-5 0.6728732 -0.7397579 -7.83675e-6 0.6727988 -0.7398256 -5.72286e-7 0 0 -1 3.07317e-7 0 -1 -8.85206e-7 0 -1 6.92421e-7 0 -1 1.19289e-7 0 -1 4.27387e-7 0 -1 1.17464e-6 0 -1 -1.96887e-6 0 -1 -1.42468e-6 0 -1 -1.07402e-6 0 -1 1.97571e-6 0 -1 -0.4207296 -0.4497222 -0.7878684 -0.2463237 -0.4319439 -0.8676112 -0.3044268 -0.3172752 -0.8981429 -0.3433712 -0.5234649 -0.7797954 -0.5675373 -0.519683 -0.6386168 -0.4261736 -0.6035528 -0.6738696 -0.5056747 -0.608189 -0.6118819 -0.3683097 -0.7150726 -0.5941542 -0.1173769 -0.3394347 -0.9332775 -0.1682531 -0.1946523 -0.966334 0.001342833 -0.2239208 -0.9746065 -0.043886 -0.08334684 -0.9955538 -0.2321577 -0.7529637 -0.6157504 -0.08273822 -0.8597328 -0.5039981 0.03470069 -0.8614144 -0.5067161 0.1250662 -0.1097152 -0.9860635 0.07953161 0.02923685 -0.9964036 0.02896302 -0.7700386 -0.6373396 0.1177123 -0.6913504 -0.7128664 -0.1587293 -0.6649783 -0.7298007 0.4515007 -0.4587643 -0.765299 0.2868785 -0.2753118 -0.9175534 0.1703256 -0.3830114 -0.907905 0.2517477 0.01239049 -0.9677136 0.3800547 0.1235719 -0.9166725 0.2568513 0.187206 -0.9481463 0.7318096 -0.6692766 -0.128545 0.7041145 -0.7087535 -0.04349023 0.7589684 -0.6446455 -0.0916475 0.3705657 0.2901778 -0.882314 0.4929134 0.2240404 -0.8407391 0.3491735 -0.5506936 -0.7581651 0.5109566 -0.3278399 -0.7946348 0.6359601 -0.2899328 -0.715188 0.3937239 -0.1651375 -0.9042739 0.8731608 -0.07519984 -0.4815965 0.8038184 -0.1388935 -0.578433 0.8809021 -0.2977134 -0.3679378 0.7253237 -0.2102175 -0.6555259 0.6178041 0.02398824 -0.785966 0.5135131 -0.0709567 -0.855143 0.5939412 0.3146262 -0.7404351 0.473723 0.3871698 -0.7910032 0.563635 0.4725952 -0.6774729 0.6811563 0.3918656 -0.6184396 0.9592784 -0.2661576 -0.09457886 0.9661957 -0.003021359 -0.2577925 0.9329136 -0.3151422 -0.1742346 0.9915923 0.02942025 -0.1260129 0.9071263 0.2870344 -0.3077875 0.7993254 0.5041448 -0.3269815 0.7515786 0.4541334 -0.4784271 0.9326909 0.3253934 -0.1555858 0.8293666 0.5321375 -0.1702376 0.8202415 0.567998 -0.06769216 0.7261303 0.6397625 -0.2518704 0.6935818 0.6007115 -0.3976055 0.7331696 0.6736872 -0.09277921 0.9238917 0.3736096 -0.08270555 0.7654494 0.6415419 -0.0501123 0.6384286 0.5441247 -0.5443688 0.7051996 -0.7073359 -0.04867756 0.7017475 -0.7113304 -0.03949123 0.7182068 -0.6939135 -0.05160784 0.7219305 -0.6901906 -0.04953253 0.8141505 -0.5017293 -0.2922787 0.7122498 -0.7013546 -0.0283215 0.7183058 -0.6948059 -0.03579926 0.717226 -0.6959238 -0.03573769 0.7076485 -0.702796 -0.07287979 0.7031296 -0.7074633 -0.07144522 0.2093616 -0.6041579 -0.76887 0.04712152 -0.480188 -0.8758991 0.5596387 -0.5898837 -0.5821012 0.6693503 -0.6325745 -0.3896405 0.6125177 -0.4896784 -0.6205137 0.4862302 -0.6581443 -0.5748271 0.6328218 -0.665142 -0.3963872 0.3773074 -0.7033733 -0.6024162 -0.06012272 -0.575622 -0.8155027 0.3008285 -0.7715274 -0.5605781 0.5754967 -0.723117 -0.3819757 0.2294759 -0.8354707 -0.4993292 0.5268815 -0.7543402 -0.3916209 0.4761293 -0.8082388 -0.346484 0.1959921 0.08185154 -0.9771835 0.2967072 -0.8929905 -0.338427 0.4078258 -0.8423252 -0.3523727 0.2060315 -0.9083881 -0.3638436 0.6174685 -0.7732701 -0.1441736 0.6453329 -0.7619171 -0.05502647 0.6448935 -0.7620859 -0.05777215 0.5518778 -0.8197139 -0.1532977 0.6277469 -0.7753067 -0.06952244 0.6341317 -0.7704618 -0.06531149 0.4596207 -0.8654664 -0.199291 0.6217028 -0.7800049 -0.07126188 0.6180069 -0.7832055 -0.06824016 0.5875262 -0.8035109 -0.09583044 0.6267156 -0.7781223 -0.04187256 0.6182947 -0.7835272 -0.06161886 0.8007979 -0.5800513 0.1492092 0.7230615 -0.6884222 0.05707091 0.6492614 -0.7565357 -0.07818967 0.644443 -0.7603243 -0.08124202 0.6426724 -0.7631314 -0.06784403 0.6562542 -0.7377405 -0.1583335 0.6625778 -0.7440037 -0.08630907 0.6657787 -0.740612 -0.09073388 0.6607508 -0.7477319 -0.06561726 0.6607902 -0.7482872 -0.05850428 0.6544805 -0.7527822 -0.07052946 0.6404773 -0.7656368 -0.05990928 0.6748943 -0.734986 -0.06567656 0.6776002 -0.7338177 -0.04867905 0.6712062 -0.7368221 -0.08108919 0.6611188 -0.7463604 -0.07660454 0.6419539 -0.7629345 -0.07633006 0.695597 -0.7020061 -0.1527493 0.6829307 -0.7254136 -0.08591187 0.6863483 -0.7219644 -0.0877124 0.6768166 -0.7334596 -0.06289935 0.6590366 -0.7495573 -0.06192392 0.6912053 -0.7201378 -0.06030648 0.690312 -0.7217468 -0.05050909 0.731757 -0.574675 -0.366443 0.7034934 -0.4606232 -0.5412239 0.6914545 -0.7202956 -0.0553627 0.8373975 -0.4883446 -0.2455304 0.828515 -0.3440167 -0.441832 0.7633786 -0.5532839 -0.333362 0.6904551 -0.718929 -0.08008104 0.6914993 -0.7188748 -0.0710482 0.7686007 -0.3984918 -0.5004571 0.6980168 -0.7130631 -0.06567847 0.7120158 0.1094422 -0.6935821 0.9290874 -0.2005398 -0.3107741 0.7125313 -0.6998963 -0.04944103 0.7094241 -0.7015501 -0.06741738 0.7081263 -0.7036401 -0.05871802 0.793309 0.1852499 -0.5799512 0.7209461 -0.6916481 -0.04312306 0.9152559 0.0398879 -0.4008936 0.8535443 0.2530998 -0.4554149 0.8808243 -0.4322482 -0.1931581 0.9109256 -0.4092878 -0.051943 0.8624362 -0.4933395 -0.1132255 0.9894073 0.1231761 -0.07681721 0.9870739 -0.1471318 -0.06354039 0.9554551 -0.2901737 -0.05389636 -0.02348411 -0.9997242 0 -0.02347689 -0.9997245 -1.52581e-6 -0.02347385 -0.9997245 -8.30644e-6 -0.02347552 -0.9997245 -3.03982e-6 -0.02346247 -0.9997248 -3.99684e-5 -0.02346855 -0.9997246 -1.19753e-5 -0.02346265 -0.9997248 -4.81878e-5 -0.02347922 -0.9997244 2.92142e-5 -0.02346873 -0.9997246 -2.70268e-5 -0.02347224 -0.9997245 0 -0.0234676 -0.9997246 -6.03387e-5 -0.02348071 -0.9997243 8.68483e-5 -0.02346801 -0.9997247 -1.12839e-4 -0.02347546 -0.9997245 6.21161e-5 -0.02347135 -0.9997246 0 -0.02347177 -0.9997246 1.96296e-5 -0.9997243 0.0234726 -7.66822e-4 -0.9997248 0.02346205 -1.34759e-4 -0.999724 0.02349311 -4.7645e-4 -0.9997251 0.02344125 5.00262e-4 -0.9997224 0.02354496 -8.64537e-4 -0.9997253 0.02344185 1.87436e-4 -0.99972 0.02363127 -0.001217305 -0.9997283 0.02326279 0.001553535 -0.9997164 0.02376508 -0.001588463 -0.9997287 0.02326089 0.001224756 -0.9997299 0.02321302 0.001109957 -0.9997277 0.02332997 5.51966e-4 -0.9997153 0.02382564 -0.001329958 -0.9997239 0.02350395 -1.05581e-4 -0.9997172 0.02374351 0.001333057 -0.9997271 0.02333766 -0.001084566 -0.9997348 0.0226143 -0.004344105 -0.9997251 0.02340269 -0.001439571 -0.9993115 0.02093279 -0.03063368 -0.9995797 0.02154779 -0.01939302 -0.9985436 0.02038705 -0.0499525 -0.9997374 0.02278888 -0.002417147 -0.9995618 0.02484703 0.01609432 -0.9997357 0.02269607 -0.003673613 -0.9996965 0.02411997 0.005006968 -0.9997255 0.02339959 -0.001250684 -0.9997301 0.0227012 -0.004955887 -0.9997289 0.02299922 -0.003639698 -0.9997267 0.02337741 -3.72373e-4 -0.9997147 0.0237866 0.002183139 -0.999725 0.02345204 -2.00654e-5 -0.999711 0.02390205 0.002588748 -0.9997233 0.02352541 -1.14284e-4 -0.9997244 0.02347731 -5.37675e-5 -0.9997239 0.02350026 1.39779e-6 -0.9997087 0.02393805 0.00312823 -0.9997174 0.02233386 -0.008143663 -0.9997233 0.02351963 3.87007e-4 -0.9996953 0.02272319 -0.009649395 -0.9993104 0.02834707 0.02398312 -0.9996012 0.02225297 -0.01738888 -0.9996495 0.01977843 -0.01759946 -0.9997165 0.02299314 -0.006197631 -0.9997081 0.02386319 0.003774821 -0.9997223 0.02356117 5.89885e-4 -0.9997188 0.02365863 0.001621901 -0.9997266 0.02336108 -0.001058042 -0.9997326 0.02288055 -0.003361225 -0.9997191 0.02368772 8.29423e-4 -0.9997235 0.02351522 -3.61381e-5 -0.9997241 0.02349078 8.35214e-6 -0.999715 0.02383953 -0.001277148 -0.9997314 0.02315425 0.001100182 -0.9997301 0.02320146 0.001259446 -0.9997242 0.02348673 3.75548e-6 -0.9997242 0.02348744 2.97168e-5 -0.999719 0.02368646 -9.68314e-4 -0.9997195 0.02365714 -0.001212954 -0.9997277 0.02331364 0.001041889 -0.9997262 0.02338302 9.63261e-4 -0.9997236 0.02350962 -1.29649e-4 -0.9997232 0.02352207 -6.16688e-4 -0.9997245 0.02347469 1.04541e-4 -0.999724 0.02349191 -3.03024e-4 -0.9997246 0.02346706 3.63901e-4 -0.9997243 0.02347594 6.28157e-4 -0.02347266 -0.9997246 0 -0.02347272 -0.9997246 -1.00415e-6 -0.02347099 -0.9997246 -5.92281e-6 -0.02347248 -0.9997246 0 -0.02347099 -0.9997246 1.45218e-6 -0.02347058 -0.9997246 -4.27137e-6 -0.0234701 -0.9997246 -8.41791e-7 -0.02346956 -0.9997246 2.64387e-6 -0.02346891 -0.9997246 1.47343e-5 -0.02347159 -0.9997246 1.04753e-5 -0.02346837 -0.9997246 8.91286e-6 -0.02347612 -0.9997245 -4.32021e-5 -0.02346575 -0.9997247 3.04372e-5 -0.02348226 -0.9997243 -5.20013e-5 -0.02346599 -0.9997248 2.1935e-5 -0.02346581 -0.9997248 1.32991e-5 -0.02346897 -0.9997246 4.52263e-6 -0.023476 -0.9997245 -1.14731e-5 -0.02346551 -0.9997247 2.32067e-6 -0.02346992 -0.9997246 0 0.9997245 -0.02347147 -5.19093e-5 0.9997245 -0.02347266 4.06207e-5 0.9997246 -0.02347052 1.68531e-5 0.9997245 -0.02347522 1.40634e-4 0.9997246 -0.02347022 -5.53126e-6 0.9997248 -0.02346551 -1.00936e-4 0.9997244 -0.02347707 7.11895e-5 0.9997246 -0.02346903 -2.85859e-5 0.9997244 -0.02347707 6.566e-5 0.9997248 -0.02346342 5.06443e-5 0.9997248 -0.02346163 1.26198e-4 0.999717 -0.02365118 -0.00259149 0.9997236 -0.02350872 -2.56127e-4 0.9997179 -0.02283889 0.006537973 0.999724 -0.02349573 7.82389e-5 0.9997286 -0.02305889 0.003333866 0.9997251 -0.02345103 2.72825e-4 0.9997232 -0.02352702 -3.25779e-4 0.9997233 -0.02352505 -4.05605e-4 0.9997249 -0.0234543 1.58708e-4 0.9997242 -0.0234909 -1.5069e-4 0.9997262 -0.0233978 4.00386e-4 0.9997245 -0.02347391 3.33805e-6 0.999723 -0.02353769 -2.73313e-4 0.9997246 -0.02346992 -6.01541e-6 0.999725 -0.02345234 1.5642e-4 0.9997247 -0.02346384 6.95308e-5 0.9997241 -0.02349072 -1.50647e-4 0.9997248 -0.02345871 8.32442e-5 0.9997246 -0.02347296 -1.4827e-5 0.9997239 -0.02349919 -1.79805e-4 0.9997246 -0.02346926 -5.99819e-6 0.9997246 -0.02347195 -2.05229e-6 0.9997245 -0.02347123 4.28645e-6 0.9997242 -0.02348619 -1.04107e-4 0.9997243 -0.0234856 -7.8242e-5 0.9997247 -0.02346563 6.5455e-5 0.9997243 -0.02348089 -6.36765e-5 0.9997254 -0.02343672 2.92537e-4 0.9997245 -0.02347201 -2.20912e-5 0.9997246 -0.02347129 -1.15939e-5 0.9997246 -0.02346932 7.04739e-5 0.9997224 -0.02355921 -4.49866e-4 0.9997223 -0.02355813 -5.91876e-4 0.9997242 -0.02348291 3.25545e-4 0.9997222 -0.02355319 -9.62867e-4 0.9997248 -0.02345508 -5.21834e-4 0.9997247 -0.02346587 1.27218e-4 0.9997246 -0.02346956 1.77333e-4 0.9997244 -0.02348011 -2.08458e-4 0.9997245 -0.02347582 -7.48873e-5 0.9997244 -0.02347892 -5.14689e-5 0.9997255 -0.02343088 2.09163e-4 0.999725 -0.02345371 -1.54289e-4 0.9997246 -0.02347111 5.15499e-6 0.9997246 -0.02346801 -2.37338e-5 0.9997241 -0.02348941 2.07662e-4 0.9997246 -0.02347123 5.02503e-5 0.9997248 -0.02345901 -1.80985e-4 0.9997247 -0.02346485 -1.4748e-4 0.9997245 -0.02347534 1.02549e-4 0.9997246 -0.0234692 -1.54889e-4 0.9997246 -0.02347236 1.68757e-4 -0.023467 -0.9997246 -1.88813e-5 -0.02347487 -0.9997245 0 -0.02347117 -0.9997245 -1.81028e-5 -0.02347028 -0.9997246 7.38259e-6 -0.02347218 -0.9997246 -1.83972e-5 -0.02347052 -0.9997246 -3.52341e-5 -0.02346408 -0.9997247 8.45597e-5 -0.02347403 -0.9997245 -1.91775e-5 -0.02347129 -0.9997245 -8.14996e-6 -0.02346956 -0.9997246 4.92251e-6 -0.0234667 -0.9997247 1.2375e-5 -0.02347975 -0.9997243 -1.65285e-5 -0.02346366 -0.9997248 0 -0.02347064 -0.9997246 1.39749e-6 0.9995374 -0.02298706 -0.01991355 0.999733 -0.02310156 3.9337e-4 0.9997265 -0.02301907 0.004133403 0.9997176 -0.02340561 -0.004126965 0.9997271 -0.02326607 -0.002142608 0.999644 -0.02237564 0.01453924 0.9996615 -0.02401638 -0.01000976 0.999714 -0.02368962 -0.003299415 0.9997274 -0.02319872 0.002649664 0.9997273 -0.0231049 0.003418207 0.9997127 -0.02379441 -0.002943933 0.9997208 -0.02359038 -0.001384615 0.9997246 -0.02346611 4.00446e-5 0.9997256 -0.02342456 -2.41712e-4 0.9997253 -0.02344185 0 -0.02347064 -0.9997246 0 -0.02347064 -0.9997246 0 0 0 -1 0 0 -1 -6.62388e-6 -1.92078e-4 -1 -8.61414e-6 -2.65634e-4 -1 -6.99538e-4 -0.002102553 -0.9999976 1.56828e-4 4.70741e-4 -1 2.52538e-5 1.54088e-4 -1 -5.59786e-4 -0.001478075 -0.9999988 4.86878e-6 1.74973e-4 -1 0.9825397 0.135689 -0.1272962 0.9942649 0.07437604 -0.07684814 0.9566556 0.2025561 -0.2092397 0.9115548 0.295184 -0.2862418 0.8615055 0.3583909 -0.3596727 0.7777401 0.4447673 -0.4441875 0.4903272 0.613901 -0.6186316 0.6395077 0.547369 -0.5398307 0.6715823 0.5220976 -0.5257294 0.1653551 0.6966705 -0.6980744 0.3184648 0.6727281 -0.6678451 0.3127931 0.6708158 -0.6724334 0.1709687 0.6986157 -0.6947703 0.0912525 0.7027667 -0.7055439 1 -1.37287e-5 0 -0.02990877 -0.9164599 0.3990075 -0.02777224 -0.8429035 0.5373475 -0.03045821 -0.9272059 0.3733116 -0.0260635 -0.7996367 0.5999183 -0.03210604 -0.9830808 0.1803373 -0.03210592 -0.9799023 0.1968777 0.5359685 0.8442373 -0.001098632 0.2468991 0.9690409 -8.24014e-4 0.416682 0.9090523 2.13636e-4 0.9928252 0.1195748 0 0.9858272 0.1677633 -6.7142e-4 0.9493373 0.3142585 6.40908e-4 0.9042826 0.4269325 -0.001342833 0.7387162 0.6740156 0.00125128 0.2722009 0.9622405 -1.52596e-4 -0.9445958 -0.2058206 -0.2556888 -0.9543564 -0.1795731 -0.2386577 -0.9635242 -0.1587308 -0.2154661 -0.966124 -0.1510713 -0.2092414 -0.9693014 -0.1520179 -0.1932498 -0.9354277 -0.2219928 -0.2751258 -0.9304532 -0.2234577 -0.2903851 -0.9440512 -0.1959944 -0.2652426 -0.9539655 -0.1529616 -0.2579778 -0.9546599 -0.1398068 -0.2628282 -0.959943 -0.1368774 -0.2444873 -0.9506703 -0.1560747 -0.2680798 -0.9609411 -0.1525981 -0.230881 -0.9443609 -0.1848558 -0.2720497 -0.8143882 -0.4626179 -0.3503664 -0.4943172 -0.7364249 -0.4618754 0.2330479 -0.8291572 -0.5081213 -0.9997751 0.008270621 0.0195322 -0.9971497 -0.03244173 -0.06811857 -0.9981837 -0.01779252 -0.05755871 -0.9986425 -0.008484244 -0.05139398 -0.9988741 -0.002044737 -0.04739534 -1 -3.05185e-4 6.1037e-5 0.9936702 -0.1096245 -0.02453732 0.9824392 -0.1556167 -0.1029407 0.9666646 -0.2335327 -0.104986 0.9909555 -0.1083734 -0.07913601 0.3708713 -0.7762294 -0.509826 0.9959176 -0.08963346 -0.0106815 0.979974 -0.1903182 -0.05856645 0.9926688 -0.1200016 -0.01443558 0.9962199 -0.08679497 -0.003570675 0.9938066 -0.1111215 -7.32468e-4 0.9798939 -0.159399 -0.1199994 0.8974222 -0.1842149 -0.400872 0.9337578 -0.09747749 -0.3443759 0.3832597 -0.2037154 -0.9008952 -0.03054928 -0.1759409 -0.9839266 -0.9462364 -0.07336723 -0.3150459 -0.9847066 -0.01440513 -0.1736245 -0.9635851 -0.1012019 -0.2475113 -0.8940497 -0.2686879 -0.3584439 -0.6744822 -0.4579765 -0.5790781 -0.9974682 -0.02551424 -0.06637984 -0.207376 -0.4109371 -0.8877646 0.9549089 -0.1890957 -0.2288925 0.7386352 -0.5914392 -0.3234466 0.9395347 -0.3188344 -0.1249762 0.9437959 -0.3081185 -0.1196339 0.9752253 -0.2103959 -0.06833136 0.9894072 -0.1431663 -0.0240187 0.9921603 -0.1241497 -0.01431322 -0.9706178 -0.07544231 -0.2284938 0.2780249 -0.7113592 -0.6455 0.9857196 -0.1646782 -0.0351879 0.9934197 -0.1143541 -0.006378412 -0.9971401 -0.01672428 -0.07370281 -0.03955227 -0.8009643 -0.5974043 -0.978545 -0.1418544 -0.1494232 -0.8974272 -0.3561631 -0.2603317 0.9829354 -0.1776834 -0.0476101 -0.995166 -0.05380511 -0.08215731 -0.9998381 -0.01110893 -0.01416087 -0.9998936 -0.009979665 -0.01065111 -0.9993713 -0.02380472 -0.0262767 -0.9870373 -0.1092266 -0.1175887 -0.9687132 -0.1894028 -0.1603789 -0.9397163 -0.269637 -0.2103077 -0.9856728 -0.106786 -0.1305603 0.4832431 -0.7690261 -0.41842 -0.9764693 -0.1585179 -0.1462185 -0.994241 -0.05929797 -0.08926743 -0.9998583 0.008819937 0.01434385 -0.99852 -0.004486262 -0.05420166 -0.9999522 0.002929806 0.009338736 -0.9999088 0.003082334 0.01315343 -0.9998434 -0.008484363 -0.01553428 -0.9993657 0.01406908 0.03271603 -0.9999716 9.46076e-4 0.007477045 -0.9988995 -7.73446e-5 -0.04690372 -0.9989014 -6.92466e-4 -0.04685622 -0.9989009 -5.11307e-5 -0.04687404 -0.8997738 -0.4353902 -0.02902394 -0.8968632 -0.4339808 -0.08542281 -0.8981273 -0.434872 -0.06522011 -0.8884413 -0.430014 -0.1604999 -0.8905217 -0.4313593 -0.1445698 -0.8663457 -0.4194239 -0.2711622 -0.8548363 -0.4142339 -0.3125143 -0.8771502 -0.4247347 -0.2240714 -0.8374457 -0.4056606 -0.3662299 -0.853808 -0.4132924 -0.3165462 -0.721575 -0.3500903 -0.5972992 -0.7973868 -0.3865923 -0.4633798 -0.7564234 -0.3667821 -0.5415667 -0.8005169 -0.3878677 -0.4568715 -0.779197 -0.3777111 -0.5001864 -0.732585 -0.3550309 -0.5807515 -0.6623197 -0.3213938 -0.6767856 -0.6164565 -0.2993929 -0.7282481 -0.6188811 -0.300132 -0.7258837 -0.5771566 -0.2801396 -0.7670803 -0.4920918 -0.2393622 -0.8369895 -0.5373002 -0.2609744 -0.801998 -0.4868766 -0.2364035 -0.8408714 -0.4232144 -0.2059153 -0.8823199 -0.3042102 -0.1483513 -0.9409825 -0.3501153 -0.170785 -0.921006 -0.3594278 -0.1748155 -0.9166523 -0.254195 -0.1247932 -0.9590681 -0.05774235 -0.0287491 -0.9979175 -0.1952621 -0.09543365 -0.9760969 -0.1833316 -0.09104013 -0.9788265 -0.1199387 -0.05935895 -0.9910052 -0.0503264 -0.02536159 -0.9984108 0.0167855 0.006683647 -0.9998368 0.001709043 -3.05194e-4 -0.9999986 -0.8194637 -0.3971123 -0.4132568 -0.7018246 -0.3402611 -0.6258313 0.05704075 -0.05664396 -0.9967637 0.05679666 -0.02716225 -0.9980162 0.05630767 -0.1547622 -0.986346 0.05057013 -0.3767278 -0.9249426 0.05502605 -0.1480485 -0.9874482 0.05328571 -0.2053301 -0.9772411 0.05423271 -0.1126771 -0.9921506 0.008392751 -0.9888208 -0.1488724 0.007873892 -0.9898565 -0.1418527 0.003357112 -0.9981316 -0.06100791 0.01794487 -0.9474478 -0.3194069 0.003326535 -0.9981782 -0.06024408 0.003418087 -0.9980006 -0.06311321 0.003845393 -0.997609 -0.0690037 0.004455745 -0.9969905 -0.07739585 0.04834222 -0.5379903 -0.8415637 0.04037642 -0.6981494 -0.7148127 0.04223889 -0.6798204 -0.7321612 0.03396779 -0.8024405 -0.5957647 0.05353087 -0.3151425 -0.9475334 0.0529505 -0.3644887 -0.9297012 0.05200439 -0.4098094 -0.9106876 0.0546295 -0.1075195 -0.992701 0.04370433 -0.6110674 -0.7903712 0.03097707 -0.8305225 -0.5561232 0.02542221 -0.8871533 -0.4607741 0.02575838 -0.8890006 -0.4571811 0.01690775 -0.953306 -0.3015323 0.04587113 -0.5532004 -0.8317844 0.03848415 -0.7143527 -0.698727 0.0291149 -0.8500102 -0.5259613 0.2213861 -0.6795707 -0.6994082 0.3457536 -0.6771326 -0.6495736 0.2694839 -0.7989605 -0.5376251 0.2669206 -0.5209623 -0.8107723 0.1357489 -0.5976249 -0.7902004 0.1295539 -0.4300761 -0.8934486 0.2005434 -0.2385706 -0.9501928 0.2065528 -0.4032785 -0.8914608 0.2309989 -0.1994727 -0.9522868 0.3857032 -0.8228619 -0.4172906 0.1694736 -0.9558032 -0.2402479 0.2111033 -0.8780458 -0.4295008 0.3221322 -0.91607 -0.2388447 0.4428669 -0.8696197 -0.2182442 0.4869647 -0.8662576 -0.1116393 0.4063933 -0.906328 -0.1158202 0.1374267 -0.9807258 -0.1388916 0.2159503 -0.9687855 -0.121739 0.09735512 -0.9465422 -0.3075385 0.1187183 -0.9904589 -0.06997972 0.1175601 -0.8640608 -0.4894676 0.1341638 -0.7438829 -0.6547048 0.2385691 -0.971123 -0.002227902 0.3180667 -0.9480658 0.002197325 0.1628487 -0.9866446 0.003570675 0.08624762 -0.9962733 -9.461e-4 0.4609307 -0.8874357 9.46094e-4 0.3896693 -0.9209479 -0.003601253 -0.9390565 -0.3437612 0.00112915 -0.9688853 -0.2475087 8.54531e-4 -0.9441484 -0.329518 -0.001281797 -0.9796916 -0.20051 0 -0.9797037 -0.2004514 0 -0.970643 -0.2405244 -5.79871e-4 -0.9252869 -0.3792644 -0.001678526 -0.9207084 -0.3902512 4.57791e-4 -0.8549311 0.5187329 0.003021359 -0.6398241 0.7685213 5.79855e-4 -0.7001739 0.7139687 -0.002288937 -0.9094421 0.4158243 -0.002319455 -0.9353714 0.3536521 0.0032655 -0.9598969 0.2803514 -0.001098692 -0.3763893 0.9264615 -4.57783e-4 -0.3837809 0.9234242 9.15581e-5 -0.09347963 0.9956209 8.24013e-4 -0.1244254 0.9922289 -3.66226e-4 -0.01419138 0.9998977 -0.001770079 0.03683662 0.9993208 0.001098632 -0.4540001 -0.8910017 0 -0.8910133 0.4539775 0 -0.8909934 0.4540164 0 -0.4539516 -0.8910263 0 -0.8910033 0.4539969 0 -0.4539617 -0.8910213 0 -0.4539641 -0.89102 0 0.914603 -0.4043505 -0.001434385 0.9999976 -4.5779e-4 -0.002136349 0.9251893 -0.3795061 -3.6623e-4 0.9970592 -0.07663345 5.79863e-4 0.9703682 0.2416154 0.002777159 0.9380751 0.3464258 -0.002075314 0.9149917 0.4034619 0.002929806 0.8835603 0.4683166 -9.76613e-4 0.7828146 -0.6222537 0.001281797 0.7175257 -0.6965289 -0.00213629 0.6175146 -0.7865575 0.001739561 0.5211799 -0.8534448 -0.001892149 0.4635813 -0.8860539 0.001037597 0.4358978 -0.8999949 -0.001495361 0.402088 -0.9156009 5.18823e-4 -0.9715958 0.2366426 0.001403808 -0.9572581 0.2892283 -0.002014219 -0.9738256 0.2272738 -0.003234982 -0.9496825 0.313214 4.57781e-4 -0.9800021 0.1989852 0.00100708 -0.7832874 0.6216552 -0.00238049 -0.822101 0.5693393 0.001617491 -0.7609156 0.6488475 0.002105832 -0.8349964 0.5502553 -4.57783e-4 -0.7128801 0.7012826 -0.002197384 -0.6233239 0.7819626 0.00137335 -0.6394717 0.7688127 -0.001770079 -0.6944356 0.7195529 0.001739561 -0.5575836 0.830119 -0.001739561 -0.4752749 0.8798369 9.46094e-4 -0.450639 0.8927024 -0.002655088 -0.3989813 0.916958 0.001434385 -0.3390973 0.9407501 -0.001556456 -0.3257611 0.945452 6.71421e-4 -0.2873983 0.9578111 -3.05191e-5 -0.2875551 0.9577642 0 -0.5530439 0.8331519 6.1039e-4 -0.8769128 0.4806494 3.66232e-4 -0.8785617 0.4776284 7.93504e-4 -0.9195941 0.3928692 -7.9349e-4 -0.9209913 0.3895832 -3.35716e-4 1.20241e-7 -1 1.25138e-6 0 -1 0 -2.54832e-7 -1 0 0 -1 1.39365e-6 0 -1 3.76463e-6 -0.7717292 -0.6359511 -7.32451e-4 -0.859629 -0.5109188 0 -0.8592089 -0.511625 0 -0.1019328 -0.9947913 -3.35707e-4 -0.1164924 -0.9931917 2.13636e-4 -0.2564846 -0.9665479 -0.001037657 -0.2212939 -0.975207 6.40901e-4 -0.4393221 -0.8983289 0.00112915 -0.5422568 -0.8402112 -0.001648008 -0.635263 -0.7722954 9.46104e-4 -0.7929359 -0.6093051 3.35705e-4 -0.9001214 -0.4356393 5.32795e-5 -0.9005243 -0.4348045 -0.001027882 -0.9003945 -0.4350736 -9.55156e-4 -0.9000555 -0.4357734 -0.001340031 -0.9001511 -0.4355755 0.001423418 -0.9000406 -0.4358053 -9.77705e-4 -0.9001778 -0.4355222 4.92074e-4 -0.9004156 -0.4350267 0.001903414 -0.9001412 -0.4355984 -1.34349e-4 -0.8998461 -0.436204 -0.001732707 -0.8999447 -0.4360024 -0.001209795 -0.9001908 -0.4354959 3.65126e-5 -0.9002578 -0.4353568 6.56097e-4 -0.9001036 -0.4356762 6.65053e-5 -0.9004392 -0.4349801 0.001351594 -0.899589 -0.4367364 0.001072168 -0.9006473 -0.4345502 -8.55284e-4 -0.900326 -0.4352161 -3.59575e-4 -0.9005118 -0.4348313 -6.95776e-4 -0.8998728 -0.4361522 6.19465e-4 -0.8999529 -0.4359868 5.66309e-4 -0.9001558 -0.4355673 -8.31237e-4 -0.8999156 -0.436064 5.75662e-4 -0.9001434 -0.4355937 2.91277e-4 -0.899384 -0.4371529 0.002387702 -0.9009631 -0.433888 -0.00260508 -0.9004057 -0.43505 0.001112341 -0.9001632 -0.435553 -6.67816e-5 -0.9001299 -0.4356217 -1.16798e-4 -0.9004276 -0.4350025 0.00168389 -0.9003702 -0.4351238 9.98581e-4 -0.8997989 -0.4363025 -0.001485109 -0.9002039 -0.4354688 1.43572e-4 -0.9001047 -0.4356737 -1.35857e-4 -0.9011921 -0.4334018 -0.003940701 -0.8999244 -0.4360448 0.001117646 -0.9002335 -0.4354073 -5.21535e-4 -0.899853 -0.4361912 0.001390099 -0.9006199 -0.4346013 -0.002374708 -0.9000265 -0.4358344 9.95136e-4 -0.900339 -0.4351868 -0.001534223 -0.9000333 -0.4358199 0.00103116 -0.9001007 -0.4356809 9.46853e-4 -0.9001708 -0.4355374 -7.47918e-5 -0.9001981 -0.4354794 -0.001093626 -0.8999447 -0.4360029 0.001087725 -0.8991355 -0.4376547 0.003708899 -0.9001814 -0.4355154 -1.18703e-5 -0.9002829 -0.4353054 2.70005e-4 -0.9001594 -0.4355609 -1.16398e-4 -0.9003342 -0.4351987 7.45e-4 -0.8996931 -0.4365153 -0.002586603 -0.9001783 -0.4355217 2.7805e-5 -0.9001578 -0.435564 4.43796e-6 -0.9001523 -0.4355755 7.97903e-5 -0.9001452 -0.4355902 2.77569e-4 -0.9001453 -0.4355898 1.75394e-4 -0.9000173 -0.4358541 3.53126e-4 -0.8999858 -0.435919 5.44265e-4 -0.90012 -0.435642 1.21703e-4 -0.9000622 -0.4357615 2.9863e-4 -0.9003711 -0.4351229 -4.29624e-4 -0.9000674 -0.4357509 8.45134e-5 -0.900148 -0.4355843 -9.13711e-6 -0.9000914 -0.4357012 9.73126e-5 0.4319376 -0.8931127 -0.1256169 0.4323405 -0.8930032 -0.1250082 0.434499 -0.8977164 -0.07290989 0.435083 -0.8990982 -0.04822045 0.4350836 -0.8991912 -0.04645037 0.4178377 -0.8643634 -0.2797995 0.4255345 -0.8798794 -0.2115007 0.3634562 -0.7521825 -0.5496554 0.38433 -0.7942047 -0.4706692 0.3957405 -0.8186123 -0.4162492 0.3978434 -0.822055 -0.4073652 0.4091633 -0.8453661 -0.3434262 0.3524687 -0.728529 -0.5873767 0.3109568 -0.6440705 -0.6989129 0.3361428 -0.6953585 -0.6352044 0.2415025 -0.4983869 -0.8326388 0.2480892 -0.5138795 -0.8212062 0.1906232 -0.3945527 -0.8988832 0.2769008 -0.5724488 -0.7717697 0.003753721 -0.006744563 -0.9999702 0.04101788 -0.08603382 -0.9954475 -0.03827065 0.0774874 -0.9962586 -0.2758936 0.5677183 -0.775615 -0.2257828 0.4673443 -0.8547582 -0.2031678 0.4176278 -0.8856127 -0.2832164 0.5864533 -0.7588552 -0.25993 0.5380189 -0.8018554 -0.3037838 0.6275269 -0.7168859 -0.3597551 0.743254 -0.5640478 -0.3348833 0.6902752 -0.641384 -0.373006 0.7697865 -0.5179724 -0.4027078 0.8307164 -0.3843654 -0.3920533 0.8101092 -0.4359098 -0.3763665 0.7779421 -0.5031446 -0.4051076 0.8378347 -0.3659518 -0.4147913 0.856684 -0.3066605 -0.4202547 0.8687096 -0.2621632 -0.4262607 0.8790121 -0.2136339 -0.4251315 0.8794699 -0.2140001 -0.4304462 0.8886041 -0.1584264 -0.4331522 0.8934966 -0.1185042 -0.4339183 0.8961277 -0.09311324 -0.4340737 0.8997042 -0.04596179 -0.341821 0.7070506 -0.6190622 -0.3230721 0.6675989 -0.6707729 -0.1841211 0.3805111 -0.906262 -0.1410294 0.2925574 -0.9457911 -0.1225643 0.2512629 -0.9601277 -0.09934037 0.2056697 -0.9735664 -0.05914628 0.122901 -0.9906549 0.07037639 -0.14588 -0.986796 0.1222603 -0.2534629 -0.959588 0.1195736 -0.2462276 -0.9618078 0.1608049 -0.3331462 -0.9290617 0.2013977 -0.416346 -0.88662 0.3005233 -0.6204569 -0.724375 0.3191063 -0.6587824 -0.6813054 0.3692528 -0.7627685 -0.530883 0.416583 -0.8605413 -0.293134 0.4216296 -0.8712152 -0.2514212 0.4291631 -0.887045 -0.1702064 -0.3485926 -0.9369459 -0.02481228 -0.2266974 -0.9738711 -0.01355051 -0.1936445 -0.9807049 -0.02682638 -0.4078612 -0.9122857 -0.03720313 0.3579571 -0.9315001 -0.06460863 0.2725964 -0.9612899 -0.04016309 0.5039312 -0.862622 -0.04400849 -0.07199478 -0.9840307 -0.1627894 -0.1248821 -0.9883141 -0.0874052 0.1302236 -0.9892664 -0.0662868 0.2095736 -0.9649785 -0.1577829 -0.5819711 -0.8123913 -0.03647047 -0.5918377 -0.8033695 -0.06576991 -0.3722183 -0.9230378 -0.09723573 -0.6833836 -0.7289791 -0.03970533 -0.6862483 -0.7201853 -0.1019636 -0.5537347 -0.6801439 -0.4803978 -0.4692021 -0.7783616 -0.4171364 -0.4426829 -0.7741229 -0.4525102 -0.6066251 -0.7016611 -0.373735 -0.7111226 -0.5979582 -0.3697984 -0.5900858 -0.7691106 -0.2454952 -0.5779141 -0.8036045 -0.1422505 -0.3789002 -0.9095131 -0.17094 -0.5870639 -0.6731885 -0.4496367 -0.6615971 -0.7220863 -0.2021902 -0.01159703 -0.9992417 -0.03717166 -0.4958188 -0.8136482 -0.3035463 -0.2905768 -0.9264521 -0.2392734 -0.1931263 -0.9284591 -0.317279 -0.1925129 -0.9025648 -0.3851175 0.1348628 -0.961161 -0.2407938 0.005676627 -0.9704598 -0.2411957 0.4375247 -0.8939105 -0.09744811 0.4808385 0.4386297 -0.759209 0.5321078 0.4838869 -0.6947768 0.488461 0.4434451 -0.7515067 0.2191269 0.1979772 -0.9553996 0.2632896 0.2411021 -0.934103 0.2980203 0.2705224 -0.9154243 0.1333079 0.1226873 -0.9834516 0.1267164 0.1144171 -0.9853181 0.02060025 0.0199899 -0.999588 -0.107702 -0.0955249 -0.9895834 0.02685642 0.02343833 -0.9993645 -0.08557641 -0.07901477 -0.9931936 -0.1749059 -0.1594937 -0.9715811 -0.2597499 -0.2329539 -0.9371567 -0.2528228 -0.2313371 -0.9394487 -0.3154461 -0.2873074 -0.9044049 -0.4033731 -0.3638507 -0.839585 -0.3758108 -0.3425452 -0.8610628 -0.4264464 -0.3889077 -0.816636 -0.5134255 -0.4648998 -0.7212921 -0.4712488 -0.4280029 -0.7711926 -0.5150533 -0.4692429 -0.7173084 -0.556954 -0.5070238 -0.6578216 -0.5831916 -0.5292031 -0.6163049 -0.5957354 -0.5427235 -0.5920732 -0.6270131 -0.5702782 -0.5306951 -0.6316625 -0.5744079 -0.5206325 -0.6629837 -0.6024627 -0.4444002 -0.6586949 -0.59903 -0.4552847 -0.6897462 -0.6280658 -0.360255 -0.6864365 -0.623323 -0.3745309 -0.7108572 -0.6455762 -0.2791301 -0.7070726 -0.6435618 -0.2930469 -0.7177823 -0.6531121 -0.2413157 -0.7258321 -0.6601248 -0.1933985 -0.7277431 -0.6607828 -0.1837288 -0.7336971 -0.6682015 -0.1232696 -0.7366366 -0.6696169 -0.09476143 -0.7368264 -0.6722477 -0.07190334 -0.7385722 -0.6720092 -0.05398899 0.3525926 0.320425 -0.8792078 0.3794129 0.3462082 -0.8580127 0.399959 0.3637933 -0.8412415 0.4460694 0.4052041 -0.7980175 0.5750725 0.5242886 -0.6280233 0.5709641 0.5188363 -0.6362459 0.6079795 0.5528918 -0.5697996 0.645148 0.5876802 -0.4882787 0.6409159 0.5825315 -0.4998839 0.6680977 0.6075779 -0.4295284 0.6920936 0.6300168 -0.3522576 0.6871925 0.6249341 -0.3704375 0.7033863 0.6398445 -0.3095913 0.7235565 0.6588551 -0.2058541 0.7177211 0.6519522 -0.2446117 0.7330715 0.6652273 -0.1417007 0.7336887 0.6685295 -0.1215286 0.7381013 0.6698914 -0.0803259 0.3372623 -0.9414107 -1.52594e-4 0.3646088 -0.9311608 2.13632e-4 0.1837578 -0.9829716 1.52597e-4 0.6737445 -0.7389643 -2.13635e-4 0.908368 -0.4181715 -4.88304e-4 0.7108506 -0.7033429 4.27267e-4 0.9300678 0.3673882 -1.52595e-4 0.8447002 0.5352393 6.40895e-4 0.9692108 0.246232 7.3247e-4 0.8589357 0.5120836 1.22077e-4 0.9995775 -0.02905374 -8.54522e-4 0.9565448 -0.2915841 9.46107e-4 0.1610475 -0.9869467 -1.22075e-4 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 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.35892e-7 1.80597e-7 -1 0 0 -1 1.26731e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.7033009 0.7108923 0 2.41159e-5 0 -1 -2.38725e-5 0 -1 1.92663e-5 0 -1 3.15736e-5 0 -1 2.18925e-5 0 -1 -8.89624e-6 0 -1 -3.58629e-5 0 -1 2.06612e-5 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.02777218 -0.01739573 -0.999463 0.03787374 -0.02371305 -0.9990012 0.03399813 -0.02148532 -0.9991911 0.05835217 -0.0363785 -0.997633 0.05221742 -0.03228873 -0.9981137 0.06415164 -0.03949201 -0.9971585 0.07171964 -0.04419147 -0.9964455 0.08615505 -0.05325555 -0.9948574 0.09921735 -0.06122112 -0.9931808 0.1136217 -0.07022392 -0.9910392 0.1017184 -0.06272834 -0.9928337 0.131963 -0.08121037 -0.9879224 0.1162467 -0.07147538 -0.9906452 0.1449654 -0.08929872 -0.9853989 0.156961 -0.0965327 -0.9828758 0.1647419 -0.1015369 -0.9810965 0.1595022 -0.09804594 -0.9823167 0.1643162 -0.100958 -0.9812277 0.178507 -0.1096861 -0.9778059 0.1819338 -0.1118164 -0.9769326 0.1910156 -0.117588 -0.9745184 0.2029795 -0.1248212 -0.9711947 0.2141519 -0.1319336 -0.9678494 0.2180868 -0.1340382 -0.966681 0.2321295 -0.142769 -0.9621502 0.3123911 -0.1920551 -0.9303369 0.3148669 -0.1938581 -0.9291275 0.2981077 -0.183418 -0.9367442 0.2509154 -0.1544324 -0.9556109 0.264508 -0.1629713 -0.9505135 0.28635 -0.176186 -0.9417867 0.2660927 -0.1636413 -0.9499559 0.2827595 -0.1739588 -0.9432845 0.2473848 -0.1522274 -0.9568843 0.3265218 -0.2007533 -0.9236242 0.3299221 -0.2028518 -0.9219559 0.3597904 -0.2215081 -0.9063581 0.3390384 -0.2086296 -0.9173477 0.3556124 -0.2187022 -0.9086855 0.3687353 -0.2267591 -0.9014514 0.3715662 -0.2285409 -0.8998376 0.3981875 -0.2451629 -0.8839355 0.3831997 -0.2358222 -0.8930543 0.3981553 -0.2450092 -0.8839926 0.4019339 -0.2473239 -0.8816349 0.4096305 -0.2520897 -0.876729 0.4214452 -0.2593251 -0.8689847 0.4346162 -0.267557 -0.8599547 0.4246353 -0.261275 -0.866845 0.4318175 -0.26564 -0.8619565 0.4457916 -0.2742441 -0.8520916 0.4580318 -0.2818751 -0.8430618 0.4741833 -0.2919201 -0.830622 0.4672192 -0.2874609 -0.8361055 0.4695285 -0.2888458 -0.8343328 0.4836117 -0.2975039 -0.8231714 0.4750552 -0.2922173 -0.8300191 0.4860303 -0.2990037 -0.8212012 0.5013409 -0.3085503 -0.8083652 0.4927903 -0.3032673 -0.8155898 0.495962 -0.3053107 -0.8129004 0.5036841 -0.30995 -0.8063706 0.0154426 -0.009491384 -0.9998357 0.004242122 -0.002441525 -0.9999881 -0.001844108 0.001353919 -0.9999974 0.07520008 -0.4722896 -0.8782297 0.02902382 -0.3535662 -0.9349592 0.09876096 -0.3443816 -0.9336208 0.3100128 -0.3455981 -0.8856941 0.3642122 -0.316908 -0.875739 0.2389078 -0.2961627 -0.9247761 0.2457068 -0.2447607 -0.9379342 0.04263514 -0.2400021 -0.9698357 0.1098976 -0.2196732 -0.9693639 0.04840391 -0.1350488 -0.989656 0.1886686 -0.279829 -0.9413288 0.121985 -0.1687709 -0.9780777 0.05783462 -0.2287138 -0.9717743 0.0441302 -0.07513737 -0.9961962 0.326922 -0.4690806 -0.820418 0.4081408 -0.4065842 -0.8173802 0.3952556 -0.4348391 -0.8091279 0.3580861 -0.3650445 -0.85937 0.4231545 -0.3751776 -0.8247315 0.4258341 -0.3858539 -0.8184022 0.4586383 -0.3362575 -0.822546 0.4350206 -0.3415098 -0.8331436 0.3830488 -0.4687168 -0.7959762 0.2217212 -0.4105429 -0.884474 0.4825121 -0.3194163 -0.8155705 0.2737231 -0.583428 -0.7646486 0.3642808 -0.4993602 -0.7860909 0.01236033 -0.4647811 -0.8853394 0.190532 -0.5289606 -0.8269816 0.05041795 -0.5936017 -0.8031781 -0.00814861 -0.5881667 -0.8086987 0.154704 -0.6392035 -0.7533165 0.2589872 -0.6255857 -0.7359132 0.2426598 -0.5947622 -0.7664034 0.2059748 -0.6549137 -0.7270919 0.1086779 -0.7303179 -0.6744072 0.1828713 -0.6625423 -0.726358 0.15986 -0.7195229 -0.6758193 0.0240184 -0.7038597 -0.709933 -0.03061079 -0.7107015 -0.7028275 0.08954334 -0.7753713 -0.6251252 0.1273273 -0.7593253 -0.6381324 0.0590853 -0.7711918 -0.6338551 -0.004394769 -0.7883494 -0.6152122 0.04858702 -0.7758058 -0.6290985 0.01721298 -0.8138954 -0.5807565 -0.04648143 -0.7950369 -0.6047775 -0.03079372 -0.8240766 -0.5656409 -0.06421244 -0.7953618 -0.6027244 -0.05597245 -0.8222217 -0.5664086 0.3432229 -0.5251805 -0.7787064 0.3149884 -0.5912786 -0.7424095 1 -3.29173e-6 0 1 3.17098e-6 0 -0.07530575 -0.9971605 0 -0.07530558 -0.9971605 0 1 1.24088e-6 0 -0.09280878 -0.7997548 -0.5931096 -0.09091526 -0.7934562 -0.6017987 -0.08896362 -0.7456468 -0.660376 -0.09064197 -0.788555 -0.6082476 -0.09747713 -0.8054531 -0.5845883 -0.09308403 -0.8329038 -0.5455335 -0.09662508 -0.8321171 -0.5461179 -0.09662455 -0.8367821 -0.5389429 -0.07208609 -0.6194157 -0.7817467 -0.07593083 -0.6645478 -0.7433779 -0.04156666 -0.3601838 -0.9319549 -0.04086476 -0.3550875 -0.9339396 -0.05838263 -0.5101537 -0.8580995 -0.02172935 -0.1917189 -0.9812093 -0.02600222 -0.2239186 -0.974261 -0.01242107 -0.1041905 -0.9944798 -0.01080358 -0.100498 -0.9948787 -0.00540179 -0.04370278 -0.9990301 -0.05722403 -0.4936225 -0.8677917 -0.1865972 -0.6284 -0.7551788 -0.1911706 -0.6085476 -0.7701453 -0.173014 -0.5910981 -0.7878257 -0.1642555 -0.5019225 -0.8491725 -0.1581811 -0.5171177 -0.8411707 -0.1495735 -0.4587918 -0.8758642 -0.1402645 -0.4821059 -0.864812 -0.1328209 -0.4133257 -0.9008443 -0.115973 -0.368611 -0.9223211 -0.1240008 -0.434018 -0.8923296 -0.1639159 -0.615501 -0.7709022 -0.1325451 -0.5380241 -0.8324434 -0.1849742 -0.6981471 -0.6916466 -0.1939224 -0.6524205 -0.7326264 -0.09967553 -0.3264939 -0.939929 -0.1076706 -0.3900007 -0.914498 -0.1714594 -0.6377997 -0.750875 -0.1720981 -0.6390735 -0.7496448 -0.08435589 -0.2862425 -0.9544367 -0.09146553 -0.3470013 -0.9333939 -0.1252804 -0.5989045 -0.7909604 -0.1521687 -0.6558576 -0.7393886 -0.1739276 -0.6389449 -0.7493321 -0.06735688 -0.2357034 -0.969488 -0.07431405 -0.2993316 -0.9512508 -0.04861688 -0.1842438 -0.9816775 -0.05639904 -0.2502555 -0.9665358 -0.107671 -0.5629231 -0.819466 -0.09870064 -0.5359867 -0.8384369 -0.1145086 -0.6643149 -0.7386296 -0.07822024 -0.4950493 -0.8653368 -0.0904293 -0.6103598 -0.7869458 -0.03259408 -0.1863479 -0.9819431 -0.01864737 -0.1078863 -0.9939884 -0.02929812 -0.1798479 -0.9832581 -0.07159781 -0.6000362 -0.7967624 -0.07873809 -0.5673111 -0.8197308 -0.05670517 -0.4692369 -0.8812499 -0.06622707 -0.4514734 -0.8898234 -0.0446496 -0.3225882 -0.9454857 -0.08542376 -0.7086908 -0.7003285 -0.09000188 -0.6837276 -0.7241659 -0.1061757 -0.7167093 -0.6892421 -0.09421199 -0.7696575 -0.6314677 -0.09686762 -0.7905364 -0.6047056 -0.09879022 -0.8181856 -0.5664033 -0.08673536 -0.80012 -0.593536 -0.1716431 -0.6639572 -0.7278046 -0.1697462 -0.7291274 -0.6629928 -0.1655678 -0.7091186 -0.6853745 -0.1597958 -0.7561613 -0.634575 -0.1543953 -0.7410916 -0.6534107 -0.1421605 -0.7778236 -0.6121935 -0.1366317 -0.7067493 -0.694145 -0.1169487 -0.4962995 -0.8602382 -0.1294296 -0.745327 -0.6540151 -0.1448746 -0.7625524 -0.630496 -0.1352921 -0.7751907 -0.6170701 -0.1015692 -0.4569698 -0.8836642 -0.1175622 -0.7597905 -0.6394509 -0.0858494 -0.4161849 -0.9052183 -0.1113337 -0.7624288 -0.6374224 -0.0300914 -0.1264084 -0.9915218 -0.06964427 -0.3744372 -0.9246332 -0.1049855 -0.7674318 -0.6324766 -0.05276775 -0.3255488 -0.9440518 -0.0974161 -0.7891864 -0.6063786 -0.03762972 -0.1090133 -0.9933279 -0.005554378 -0.01593083 -0.9998578 -0.01171934 -0.0357685 -0.9992914 -0.01586973 -0.04788392 -0.9987269 -0.06305265 -0.1824438 -0.9811925 -0.04513806 -0.1314772 -0.9902911 -0.08432483 -0.2423539 -0.9665164 -0.06488364 -0.1873264 -0.9801526 -0.08365327 -0.2412546 -0.9668498 -0.1032766 -0.2957606 -0.9496629 -0.1031253 -0.2960695 -0.9495831 -0.1221674 -0.349015 -0.9291198 -0.1209777 -0.3464834 -0.9302223 -0.139868 -0.3994005 -0.9060443 -0.1383419 -0.3958293 -0.907844 -0.1561663 -0.4460063 -0.8813005 -0.1554337 -0.4446326 -0.8821238 -0.1718547 -0.4912403 -0.8539023 -0.1715188 -0.4909346 -0.8541455 -0.1849802 -0.5296703 -0.8277873 -0.1846392 -0.5290144 -0.8282826 -0.1861391 -0.5331166 -0.8253115 -0.191813 -0.5500777 -0.8127868 0.9834514 -0.02896273 -0.1788426 0.9717049 -0.02221804 -0.2351514 0.9935576 -0.0240187 -0.1107547 0.85664 -0.02670419 -0.5152231 0.8843078 -0.01959359 -0.4664933 0.9386922 -0.02884006 -0.3435482 0.5486372 -0.01876908 -0.8358499 0.3717569 -0.006286978 -0.9283089 0.5868481 -0.01217699 -0.8096056 0.3281067 -0.01278734 -0.9445542 0.1141701 -0.006103694 -0.9934425 0.1618099 -0.001373291 -0.9868211 -0.05658215 -9.15569e-4 -0.9983977 -0.1724954 0.007446706 -0.9849822 -0.007385671 0.002655148 -0.9999693 -0.3535289 0.01266527 -0.9353379 -0.2197979 0.0032655 -0.9755401 -0.3970247 0.007843434 -0.9177744 -0.5207762 0.01696854 -0.8535247 -0.5611536 0.01263487 -0.8276154 -0.6538436 0.02029526 -0.7563576 -0.7995285 0.01883 -0.600333 -0.7660369 0.02334731 -0.6423724 -0.6897926 0.01638871 -0.7238215 -0.8992137 0.02041721 -0.437033 -0.8587373 0.02633768 -0.5117388 -0.9333338 0.02975606 -0.3577749 -0.9728853 0.02139383 -0.2302965 -0.986494 0.03021371 -0.1609873 -0.9939251 0.02130252 -0.1079776 -0.9979008 0.02896225 -0.0579245 0.7245869 -0.02334713 -0.6887879 0.7556771 -0.01712101 -0.6547207 0.9955057 -0.02783346 -0.0905199 -0.9877297 -0.02047848 -0.1548249 -0.9767067 -0.1412429 -0.1615382 -0.9356462 -0.1594609 -0.3148627 -0.602786 -0.04794573 -0.7964612 -0.7223095 -0.05798739 -0.6891346 -0.6696892 -0.163676 -0.7243801 -0.9343943 -0.05594092 -0.3518208 -0.9975975 -0.0298168 -0.06253296 -0.9872664 -0.1409072 -0.07382601 -0.8735493 -0.1586995 -0.460137 -0.851458 -0.04739642 -0.5222768 -0.7688926 -0.239268 -0.5929208 -0.7991968 -0.4161244 -0.4337338 -0.6654105 -0.5527945 -0.5016444 -0.6317762 -0.697667 -0.3378161 -0.3919348 -0.1866894 -0.900852 -0.2424433 -0.1550978 -0.9576878 -0.2607579 -0.05557584 -0.9638032 -0.1699613 -0.9682825 -0.1831457 -0.09927868 -0.9812507 -0.1651999 -0.2677126 -0.8869126 -0.3764518 -0.4092007 -0.6982475 -0.5873715 -0.3005833 -0.7043519 -0.6430694 -0.5027124 -0.4259871 -0.7522069 -0.009949147 -0.9839329 -0.1782615 -0.05121082 -0.9043991 -0.4236032 -0.05841326 -0.9828023 -0.1751788 0.1015068 -0.07864797 -0.9917212 0.06927829 -0.1723718 -0.9825928 0.2167456 -0.2598078 -0.9410215 0.1801529 -0.5792179 -0.7950168 0.0618323 -0.4384419 -0.89663 0.3828293 -0.2659418 -0.8847128 0.3233486 -0.574062 -0.7522623 0.04980653 -0.9742186 -0.22004 0.08035635 -0.9866473 -0.1416689 0.1628522 -0.8989833 -0.4065812 0.5208413 -0.1998094 -0.8299401 0.4417657 -0.1035822 -0.8911307 0.2801316 -0.9057052 -0.318158 0.4563774 -0.7247288 -0.5162247 0.357926 -0.7236648 -0.5900835 0.03949123 -0.9987877 -0.02938956 0.136023 -0.9899436 -0.0388506 0.120793 -0.9877377 -0.0989111 0.3113595 -0.9471102 -0.07770252 0.5191882 -0.8311223 -0.1991971 0.366814 -0.9095121 -0.1955385 0.02664345 -0.9983835 -0.05020451 0.03192257 -0.9968343 -0.07281774 0.0307936 -0.9975735 -0.06244176 0.6021519 -0.0678451 -0.7954937 0.6608105 -0.2177268 -0.7182789 0.774554 -0.2089669 -0.5969917 0.7502806 -0.08929872 -0.6550611 0.9549253 -0.0919553 -0.2822445 0.8678693 -0.09573811 -0.4874803 0.9204559 -0.2087506 -0.3304302 0.8632643 -0.200999 -0.4630058 0.8453742 -0.4491775 -0.2891058 0.9464812 -0.279339 -0.1616889 0.9877708 -0.1316885 -0.08346885 0.9493256 -0.3027795 -0.0842936 0.9928952 -0.08447575 -0.0838043 0.4740501 -0.4517102 -0.7558006 0.05246204 -0.9981832 -0.02963387 0.05810838 -0.9982495 -0.01101738 0.05829131 -0.9982165 -0.01287901 0.2448822 -0.9691221 -0.02890121 0.06537115 -0.9978413 -0.006286859 0.03811866 -0.9978005 -0.05423289 0.234997 -0.7755817 -0.585875 0.2046894 -0.9084219 -0.3645162 0.06854629 -0.9976447 -0.002594113 0.03994894 -0.7149003 -0.6980844 0.0119636 -0.9974959 -0.06970626 0.283918 -0.09637892 -0.9539925 0.01754868 -0.9058175 -0.4233048 -0.225996 -0.432124 -0.8730376 -0.1854026 -0.7102676 -0.6790773 -0.08212709 -0.56433 -0.8214541 -0.3721829 -0.4298033 -0.8226477 -0.0144658 -0.9962216 -0.08563542 -0.02896225 -0.9965274 -0.07806682 -0.05838364 -0.09131407 -0.9941093 -0.09033656 -0.2512333 -0.9637018 -0.1937682 -0.8982494 -0.3944643 -0.628883 -0.4111575 -0.6598907 -0.5333909 -0.6319998 -0.5622014 -0.4033745 -0.8181023 -0.4098752 -0.5415319 -0.1707241 -0.8231626 -0.4628809 -0.0476095 -0.8851411 -0.6825608 -0.6943106 -0.2281306 -0.8607882 -0.4169505 -0.2918837 -0.3568317 -0.8910415 -0.280564 -0.5241085 -0.7554755 -0.39315 -0.8971395 -0.4165247 -0.1471326 -0.7098763 -0.6957765 -0.1094112 -0.8933715 -0.4420468 -0.08051085 -0.6531276 -0.7545103 -0.06433308 -0.1757302 -0.9798225 -0.0952202 -0.1063886 -0.9930826 -0.04968464 -0.09943091 -0.9936379 -0.0528894 -0.104712 -0.9936501 -0.04117059 -0.09524887 -0.9950013 -0.02999985 -0.2001435 -0.9789268 -0.0405597 -0.09116023 -0.9954386 -0.02813851 -0.1040396 -0.9941602 -0.02865743 -0.4486625 -0.89174 -0.05917668 -0.3568264 -0.933236 -0.04178029 -0.1219249 -0.9923074 -0.0214551 -0.1172552 -0.9930074 -0.01370316 -0.1804586 -0.9833205 -0.02270609 -0.0689432 -0.9975553 0.01141422 0.4751483 -0.8788825 0.04242122 -0.4388938 -0.8857225 -0.1512216 -0.4071877 -0.8908565 -0.2014269 -0.1157291 -0.9929144 -0.02697902 -0.08935916 -0.9946089 -0.05261445 -0.06671392 -0.9950936 -0.07306182 -0.09463882 -0.9933871 -0.065005 -0.08755898 -0.9948889 -0.05029529 -0.05246144 -0.9957298 -0.07596075 -0.09268718 -0.9922747 -0.0824632 -0.08407974 -0.9930259 -0.08264529 -0.09622681 -0.9924823 -0.07562637 -0.135535 -0.8983275 -0.417897 -0.06509751 -0.9949578 -0.07629805 -0.07376396 -0.9942418 -0.07773137 -0.05108946 -0.9956952 -0.07733613 -0.05972605 -0.9949876 -0.08020448 -0.06918704 -0.7733264 -0.6302219 -0.04251366 -0.994753 -0.09305399 -0.03546357 -0.995544 -0.08737713 -0.04858583 -0.9949119 -0.08826029 0.1094727 -0.827073 -0.5513311 -0.02310293 -0.9960218 -0.08606386 -0.02996993 -0.9966087 -0.07663404 -0.007111012 -0.9954512 -0.09500688 -0.01672464 -0.9962149 -0.08530175 0.008117973 -0.9950935 -0.09860599 0.01181089 -0.9958717 -0.09000104 0.001098632 -0.9949212 -0.1006518 0.05218744 -0.9974518 -0.04864722 0.04724407 -0.9981084 -0.03933954 0.01617503 -0.9972673 -0.07208567 0.0124821 -0.9968293 -0.07858538 0.5965251 -0.4559239 -0.6605235 0.3133434 -0.9106093 -0.2694563 0.02560555 -0.9967563 -0.07629793 0.6968235 -0.458618 -0.5514586 0.5345422 -0.7273314 -0.430411 0.02597153 -0.9983643 -0.05093598 0.6023551 -0.7280328 -0.3273172 0.7800123 -0.4589493 -0.425378 0.04864782 -0.9973109 -0.05481272 0.7041342 -0.665192 -0.2484246 0.06540155 -0.9976564 -0.02011179 0.03882002 -0.9987931 -0.03009164 0.7927387 -0.5939666 -0.1370011 0.5505091 -0.8298838 -0.09073418 0.06326544 -0.9976288 -0.02710068 0.8277505 -0.556615 -0.07077473 0.5916823 -0.8039761 -0.05945205 1 -6.69019e-5 0 1 9.5906e-5 0 1 -4.33974e-5 0 1 7.74383e-5 0 1 -6.62921e-5 0 1 -1.10292e-5 0 1 -3.97917e-5 0 1 7.9504e-6 0 1 -1.2714e-5 0 1 4.30157e-5 0 1 -2.24485e-5 0 1 7.24179e-5 0 0.9999998 -5.99251e-4 0 1 4.25487e-4 0 1 -5.10204e-4 0 1 -6.9377e-5 0 1 -3.7743e-5 0 1 3.55999e-4 0 1 -4.27128e-5 0 1 -3.15937e-5 0 1 4.09153e-5 0 1 -1.06545e-5 0 1 6.84856e-6 0 1 5.42288e-6 0 1 -9.50092e-6 0 1 2.18794e-5 0 1 7.33382e-5 0 1 5.67972e-6 0 1 -3.53848e-5 0 1 1.69899e-5 0 1 3.14459e-5 0 1 7.64263e-5 0 1 -1.47143e-5 0 1 6.59597e-5 0 1 9.34039e-5 0 1 -3.34692e-5 0 1 -4.62117e-5 0 1 4.44976e-5 0 1 -6.03522e-6 0 1 2.04633e-5 0 1 -9.22397e-5 0 1 -5.22099e-6 0 1 -2.9947e-5 0 1 5.77491e-5 0 1 -8.16931e-5 0 1 -3.04924e-5 0 1 -9.08196e-5 0 1 8.94827e-5 0 1 1.64382e-4 0 1 1.52531e-4 0 1 -2.98835e-5 0 1 -3.94339e-5 0 1 3.00544e-5 0 1 -9.28589e-5 0 1 4.59909e-5 0 1 -4.57199e-5 0 1 -4.54502e-5 0 1 4.58139e-5 0 1 -1.18177e-5 0 1 5.95623e-6 0 1 -5.09327e-6 0 1 1.28219e-5 0 1 4.99057e-6 0 1 -4.98874e-6 0 1 4.86715e-6 0 1 -1.92318e-5 0 1 4.90055e-6 0 1 2.3878e-5 0 1 -3.82342e-5 0 3.96751e-4 0.9984391 -0.05585032 5.18821e-4 0.9891168 -0.1471315 -2.7467e-4 0.9911609 -0.1326655 4.27272e-4 0.9433256 -0.3318685 -9.15565e-4 0.8668572 -0.4985557 -6.10384e-4 0.9489332 -0.3154768 -5.49341e-4 0.4196967 -0.9076643 -0.001159727 0.5970511 -0.8022025 0 0.4277846 -0.9038807 -4.57781e-4 0.2280968 -0.9736384 5.18817e-4 0.2436915 -0.9698527 3.96743e-4 0.06238013 -0.9980524 3.0519e-4 -0.09668409 -0.9953151 -3.35714e-4 0.04815959 -0.9988396 2.44154e-4 -0.2328004 -0.9725245 -2.44149e-4 -0.1091653 -0.9940236 5.18821e-4 -0.6151695 -0.7883948 -4.57784e-4 -0.5153123 -0.8570023 3.05193e-4 -0.5003336 -0.8658328 -6.7142e-4 -0.6419687 -0.7667306 6.71423e-4 -0.717873 -0.6961738 -5.18819e-4 -0.7413318 -0.6711386 4.57788e-4 -0.8170912 -0.5765082 -3.05193e-4 -0.8269208 -0.5623184 2.74674e-4 -0.8953166 -0.4454304 -1.52595e-4 -0.9000079 -0.4358736 2.44156e-4 -0.9253504 -0.3791129 0 -0.9281629 -0.3721746 -3.0519e-4 -0.3754755 -0.9268323 2.44149e-4 -0.3638435 -0.9314601 -2.44157e-4 -0.2439429 -0.9697896 2.44155e-4 0.569521 -0.8219768 0.001159667 0.6910427 -0.7228131 -0.00149542 0.7488129 -0.6627799 7.32468e-4 0.7925001 -0.6098713 2.44156e-4 0.8706611 -0.4918832 0 0.9989264 -0.04632824 1 -1.02673e-4 0 1 2.57178e-4 0 1 -9.49126e-5 0 1 9.44209e-5 0 1 2.3431e-5 0 1 0 0 0.5067013 -0.8621216 6.40892e-4 0.2473583 -0.9689242 1.52596e-4 0.4813797 -0.8765121 -4.27269e-4 0.8619199 -0.5070441 -6.40901e-4 0.9692965 -0.2458949 -2.44155e-4 0.9687297 -0.2481184 -1.52594e-4 0.8763151 -0.4817383 4.27262e-4 0.2450984 -0.9694982 2.13633e-4 0.08130383 -0.9164081 -0.3919005 0.09238159 -0.8838057 -0.4586427 0.08157706 -0.9466053 -0.3119033 0.09811919 -0.7943233 -0.5995192 0.08933079 -0.8521983 -0.5155368 0.09622657 -0.7829055 -0.614654 0.1000099 -0.6820942 -0.7243933 0.09833157 -0.7228074 -0.684018 0.09900391 -0.6557943 -0.7484198 0.09845495 -0.5906688 -0.8008852 0.09802711 -0.5508378 -0.8288356 0.08807778 -0.4031863 -0.9108695 0.09445506 -0.5014513 -0.8600144 0.09164869 -0.5477865 -0.8315832 0.0885958 -0.389724 -0.9166603 0.08212679 -0.2668892 -0.9602215 0.08429396 -0.2746421 -0.9578446 0.09311342 -0.409168 -0.9076957 0.086277 -0.3420562 -0.9357104 0.08316463 -0.2413148 -0.9668769 0.07675611 -0.1501246 -0.9856831 0.08111983 -0.2636548 -0.9612002 0.07403945 -0.1437757 -0.9868368 0.06936925 0.08636826 -0.9938454 0.06613504 0.05865782 -0.9960851 0.06314337 0.02624613 -0.9976594 0.07571852 0.1629124 -0.9837308 0.08780437 0.5474271 -0.8322345 0.0882017 0.5254869 -0.8462176 0.08545464 0.4343234 -0.8966944 0.09622687 0.7004451 -0.7071897 0.0964713 0.6826238 -0.7243742 0.09445583 0.6179153 -0.7805504 0.09454733 0.7881489 -0.6081793 0.09497487 0.5499512 -0.8297793 0.08835202 0.6808755 -0.7270505 0.09155696 0.6925372 -0.7155485 0.09222894 0.6206992 -0.7786054 0.09329593 0.7944957 -0.6000604 0.08939057 0.7524191 -0.652591 0.0856359 0.7947113 -0.6009165 0.08780282 0.8841323 -0.4589126 0.08670461 0.8681147 -0.4887322 0.0836842 0.857321 -0.5079347 0.08740651 0.8093345 -0.5808079 0.07983773 0.8852655 -0.4581822 0.07904511 0.9266286 -0.3675751 0.07641929 0.9618948 -0.2625236 0.07812857 0.947187 -0.3110189 0.07837295 0.9037916 -0.4207358 0.0722689 0.9474918 -0.3115071 0.07284992 0.9424712 -0.3262529 0.07056075 0.9810143 -0.180644 0.06583064 0.9827597 -0.1727711 0.06595093 0.9932927 -0.09497421 0.05527037 0.9872369 -0.1493612 0.05905526 0.9720161 -0.2273704 0.05877941 0.9976635 -0.03482204 0.05093616 0.9978492 -0.04126167 0.05212569 0.9974993 -0.04773098 0.04867827 0.998787 0.007421195 0.08386576 0.4044358 -0.910713 0.08887302 0.4106105 -0.9074694 0.09573811 0.5362191 -0.8386319 0.07800632 0.2653925 -0.9609797 0.08398741 0.3292661 -0.9404945 0.09256422 0.4508272 -0.8877988 0.08560496 0.2636206 -0.9608206 0.0900619 0.3507866 -0.9321147 0.06799679 0.1306223 -0.9890977 0.07287877 0.2169578 -0.9734567 0.06552451 0.04123133 -0.9969989 0.06680709 -0.05160838 -0.9964304 0.06637972 -0.04327648 -0.9968555 0.0942437 -0.4383491 -0.8938502 0.09723317 -0.5130226 -0.8528503 0.09283959 -0.6808543 -0.7265111 0.09497475 -0.5939279 -0.7988927 0.0948854 -0.7291741 -0.6777181 0.09045964 -0.7944216 -0.6005925 0.09439629 -0.7858424 -0.6111802 0.09207731 -0.8410563 -0.5330535 0.08514893 -0.8848471 -0.4580342 0.07886177 -0.9384065 -0.3364139 0.07779335 -0.9472541 -0.3108988 0.08432507 -0.8981859 -0.4314527 0.06463879 -0.9699484 -0.2345674 0.06006211 -0.9874545 -0.1460352 0.07288008 -0.9833629 -0.1663913 0.07913595 -0.9609543 -0.2651498 0.05789411 -0.9971399 -0.04858583 0.05285888 -0.9985674 0.008318662 0.05441516 -0.9984567 -0.01110887 0.0601226 -0.9956244 -0.07153671 0.05459815 -0.9984849 -0.006866693 0.09582912 -0.6635102 -0.7420047 0.06270027 -5.26195e-4 -0.9980323 0.06260919 -1.87261e-4 -0.9980382 0.04772406 0.9988604 5.40398e-4 0.0461601 0.9989097 0.006973206 -1.64964e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.91062e-7 0 -1 -3.68599e-7 5.6447e-7 -1 3.62233e-7 -5.5472e-7 -1 0 0 -1 3.77649e-7 -2.16922e-7 -1 -3.80298e-7 2.18444e-7 -1 3.81531e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 1.77249e-7 0 -1 3.87732e-7 0 -1 -8.56904e-7 0 -1 -0.06446099 -0.9979202 0 -0.06446105 -0.9979202 0 0.001403868 0.09241217 -0.9957199 -0.001617491 0.1183531 -0.9929704 0.00112915 0.2094497 -0.9778188 2.13632e-4 0.6181302 -0.7860758 -4.2726e-4 0.5776557 -0.8162804 -4.88298e-4 0.6209624 -0.7838403 -3.96749e-4 0.4884287 -0.8726038 2.44155e-4 0.5313425 -0.8471571 4.88309e-4 0.4762841 -0.8792914 -4.27259e-4 0.3828855 -0.9237958 -2.74667e-4 0.4404746 -0.8977651 -0.001098632 0.2275777 -0.9737594 8.85045e-4 0.3136721 -0.949531 -7.01932e-4 -0.01864695 -0.999826 0.001617491 -0.05356144 -0.9985633 -3.35711e-4 -0.1211306 -0.9926365 -9.15574e-5 -0.2105211 -0.9775894 3.05193e-5 -0.2451916 -0.9694746 2.44155e-4 -0.1638892 -0.9864788 -2.44149e-4 -0.297618 -0.954685 1.52593e-4 -0.3234971 -0.9462292 -5.79852e-4 -0.3735469 -0.9276111 4.27273e-4 -0.3829591 -0.9237653 -3.96747e-4 -0.4391384 -0.8984194 4.88299e-4 -0.4410259 -0.8974943 -2.74672e-4 -0.4894655 -0.8720226 3.96744e-4 -0.4883924 -0.8726241 -1.83116e-4 -0.5328983 -0.8461793 -2.13631e-4 -0.5745761 -0.8184512 3.96747e-4 -0.5339298 -0.8455287 4.27263e-4 -0.5776904 -0.8162559 -2.13632e-4 -0.6181302 -0.7860758 -1.83117e-4 -0.6574193 -0.753525 4.88305e-4 -0.6210632 -0.7837604 3.96743e-4 -0.6624086 -0.7491428 2.7467e-4 -0.688934 -0.7248242 0 -0.7236334 -0.6901847 2.13633e-4 -0.7031896 -0.7110024 2.13633e-4 -0.7371567 -0.675722 -9.15564e-5 -0.7608034 -0.6489824 4.88302e-4 -0.7661459 -0.6426665 2.13634e-4 -0.7979518 -0.6027213 2.13631e-4 -0.794525 -0.6072314 -2.74674e-4 -0.8240829 -0.5664693 2.13633e-4 -0.8352758 -0.5498312 1.52598e-4 -0.8567759 -0.5156891 6.71417e-4 -0.865518 -0.5008773 4.27273e-4 -0.8877503 -0.4603251 3.05196e-4 -0.8879074 -0.4600223 1.52597e-4 -0.9056312 -0.4240664 -6.10389e-5 -0.9208632 -0.3898859 4.5778e-4 -0.9113484 -0.4116357 0 -0.9277911 -0.3731002 -3.35711e-4 -0.934437 -0.3561286 -2.4415e-4 -0.9403447 -0.3402234 -7.01932e-4 -0.9464785 -0.3227664 -9.7661e-4 -0.9592444 -0.2825759 -5.79867e-4 -0.9533017 -0.3020192 -6.10374e-4 -0.9700364 -0.2429592 -0.001068174 -0.973083 -0.2304525 -3.96746e-4 -0.986403 -0.1643445 -2.44151e-4 -0.9857599 -0.168159 -1.22077e-4 -0.9944963 -0.1047722 0 -0.9946147 -0.1036425 0 -0.9968663 -0.07910472 -8.24014e-4 0.3213959 -0.9469446 7.01932e-4 0.3983309 -0.9172416 -3.96748e-4 0.5340228 -0.84547 2.44158e-4 0.5746253 -0.8184167 1.83114e-4 0.657469 -0.7534816 -3.96749e-4 0.6623269 -0.749215 -2.44156e-4 0.6888867 -0.7248691 0 0.7235738 -0.6902471 -2.13633e-4 0.7032203 -0.7109721 -2.13634e-4 0.7371275 -0.6757537 9.15564e-5 0.7608034 -0.6489824 -4.88306e-4 0.7660907 -0.6427325 -1.52597e-4 0.7979003 -0.6027895 -2.13633e-4 0.7942878 -0.6075419 2.13635e-4 0.8233485 -0.5675361 -1.83117e-4 0.8352899 -0.5498099 -2.13637e-4 0.8563166 -0.5164512 -6.71417e-4 0.865518 -0.5008773 -3.05188e-4 0.8878824 -0.4600704 -1.22076e-4 0.9056484 -0.4240295 -4.27267e-4 0.8877378 -0.4603492 -4.5778e-4 0.9113484 -0.4116357 0 0.9278271 -0.3730108 6.10389e-5 0.9208632 -0.3898859 3.35714e-4 0.9344128 -0.3561921 2.44155e-4 0.9403313 -0.3402601 5.79856e-4 0.9532841 -0.3020747 7.01945e-4 0.9464971 -0.3227117 6.10374e-4 0.9700364 -0.2429592 9.76618e-4 0.9592528 -0.2825478 0.001068115 0.9730762 -0.2304815 3.96742e-4 0.9863319 -0.1647701 2.44152e-4 0.9857649 -0.1681293 1.22076e-4 0.9944931 -0.1048023 0 0.9945734 -0.1040382 0 0.9968663 -0.07910472 0 0.9968616 -0.07916539 -0.5989376 0.8007954 -7.32716e-4 -0.5996009 0.8002989 6.82764e-4 -0.5991743 0.8006187 5.76482e-6 -0.6007165 0.7994614 0.00116384 -0.5982751 0.8012905 -8.15705e-4 -0.6035553 0.7973169 0.002601683 -0.5971365 0.8021388 -0.001187384 -0.5990762 0.8006921 0 -0.5934426 0.8048697 -0.003274857 -0.5978463 0.8016108 6.75593e-5 -0.6000279 0.7999791 -3.57708e-5 -0.5983911 0.8012042 5.24521e-5 -0.5999798 0.8000153 -5.95115e-5 -0.5986125 0.8010388 4.94278e-5 -0.6003369 0.7997472 -9.71515e-5 -0.5990865 0.8006843 4.46124e-6 -0.599532 0.8003509 -4.97469e-5 -0.5992928 0.80053 -2.56587e-5 -0.5994057 0.8004454 -3.76342e-5 -0.5986858 0.800984 1.01118e-4 -0.5991679 0.8006235 -4.32041e-6 -0.5992309 0.8005763 -2.05876e-5 -0.5992417 0.8005682 -2.69919e-5 -0.5994965 0.8003774 -1.047e-4 -0.5989748 0.8007679 8.99956e-5 -0.5990254 0.8007301 6.0986e-5 -0.5992546 0.8005585 -3.35398e-5 -0.5993549 0.8004836 -7.24648e-5 -0.5990066 0.8007442 7.92321e-5 -0.5995088 0.8003683 -1.68187e-4 -0.598895 0.8008276 1.5971e-4 -0.5994801 0.8003897 -1.88454e-4 -0.5991014 0.8006731 6.90874e-5 -0.5991733 0.8006195 7.60595e-6 -0.5991528 0.8006349 5.17752e-6 -0.5992251 0.8005806 -2.6276e-5 -0.5992137 0.8005892 -3.02948e-5 -0.5991089 0.8006675 7.36691e-5 -0.5991891 0.8006077 -3.94425e-6 -0.5992302 0.8005768 -4.22344e-5 -0.599264 0.8005515 5.92012e-5 -0.5991802 0.8006142 -4.14843e-6 -0.5993626 0.8004778 1.36613e-4 -0.5989629 0.800777 -1.6078e-4 -0.5991397 0.8006445 -3.94481e-5 -0.599271 0.8005462 5.10229e-5 -0.5992394 0.80057 4.51348e-5 -0.5988525 0.8008595 -2.23752e-4 -0.5994169 0.8004371 1.40374e-4 -0.5993412 0.8004937 7.25615e-5 -0.5990878 0.8006835 -5.21116e-5 -0.5989646 0.8007756 -1.01347e-4 -0.59935 0.8004871 6.89234e-5 -0.5992702 0.8005468 2.20889e-5 -0.599437 0.800422 9.14452e-5 -0.5987647 0.8009251 -1.47555e-4 -0.5994533 0.8004098 7.61439e-5 -0.599103 0.800672 -1.70792e-5 -0.5991604 0.8006291 -1.42048e-5 -0.5990477 0.8007134 -3.50162e-5 -0.5996928 0.8002305 1.04532e-4 -0.5992411 0.8005687 0 -0.5984193 0.8011832 -1.48953e-4 -0.6002601 0.799804 -0.001211822 -0.5950387 0.8036804 0.005179166 -0.5977711 0.8016647 0.001878321 -0.6002397 0.7998189 -0.001432716 -0.6000941 0.7999283 -0.001331686 -0.5993456 0.8004904 -3.01377e-4 -0.5991011 0.8006734 1.80712e-4 -0.5988324 0.8008742 6.46096e-4 -0.5996789 0.8002397 -0.001314878 -0.5988129 0.8008885 7.87514e-4 -0.599269 0.8005477 -8.1245e-5 -0.5992348 0.8005735 3.11997e-5 -0.5991347 0.8006476 0.001120865 -0.02347064 -0.9997246 0 -0.02347064 -0.9997246 0 0 -1 7.54954e-7 0 -1 0 0 -1 -2.22093e-7 0 -1 2.68775e-7 0 -1 -6.07052e-6 -3.4261e-4 -0.9999996 -8.47457e-4 0 -1 4.47541e-7 0 -1 3.14333e-6 -1.85477e-7 -1 0 -2.51321e-7 -1 1.6728e-5 -4.33736e-6 -1 8.02501e-6 2.01234e-7 -1 1.45353e-5 -1.20095e-5 -1 0 -1.64688e-6 -1 0 -6.72335e-6 -1 0 -3.47559e-6 -1 0 -4.74866e-6 -1 0 0 -1 2.63019e-4 -3.13757e-5 -1 0 -2.01914e-6 -1 1.45683e-5 -2.56143e-6 -1 8.00769e-5 -8.28943e-7 -1 -1.99665e-5 4.93751e-7 -1 1.39071e-5 -3.25179e-5 -0.9999999 -5.87199e-4 0 -1 -1.48223e-5 4.04979e-6 -1 0 -3.51852e-7 -1 -4.96903e-6 -2.99029e-7 -1 0 0 -1 0 0 -1 1.82648e-6 -2.40498e-7 -1 0 -2.45837e-7 -1 0 0 -1 -3.5987e-6 -2.35223e-7 -1 0 -2.18259e-6 -1 -1.55039e-5 0 -1 7.20695e-7 0 -1 1.91773e-7 0 -1 0 0 -1 1.84586e-7 0 -1 0 0 -1 -1.50907e-6 0 -1 2.54768e-6 0 -1 -8.82447e-7 0 -1 0 0 -1 0 0 -1 5.04906e-7 0 -1 -1.34134e-6 0 -1 1.27439e-6 1.53836e-7 -1 0 2.99165e-7 -1 0 2.96232e-7 -1 7.57097e-6 -0.0570091 0.01635807 -0.9982397 -0.04764068 0.04611468 -0.9977995 -0.0657382 -0.01446604 -0.9977321 -0.09967511 -0.0779761 -0.9919601 -0.1775007 -0.015046 -0.9840057 -0.1591548 -0.02475064 -0.9869434 -0.102423 -0.01699924 -0.9945957 -0.1182304 -0.01690745 -0.9928423 -0.1031854 0.00476098 -0.9946508 -0.09714347 -1.83117e-4 -0.9952704 -0.1019331 0.01077312 -0.994733 -0.2969186 -0.729677 -0.6159634 -0.3698632 -0.7743353 -0.513426 -0.3561266 -0.708011 -0.6098313 -0.3165761 -0.8893917 -0.3297909 -0.3175848 -0.8475236 -0.4252572 -0.2858445 -0.8561601 -0.4304453 -0.1371223 -0.5723246 -0.8084813 -0.1494814 -0.5737546 -0.8052707 -0.1442628 -0.4822902 -0.8640512 -0.1318737 -0.1866558 -0.9735343 -0.1484144 -0.1857088 -0.9713318 -0.1396571 -0.08502727 -0.9865426 -0.1567445 -0.483204 -0.8613623 -0.1624829 -0.3870413 -0.9076335 -0.1497284 -0.3865595 -0.9100292 -0.1277223 -0.6570757 -0.7429258 -0.14045 -0.6586683 -0.7392089 -0.1303483 -0.8666287 -0.4816265 -0.1118831 -0.8657975 -0.4877263 -0.1180776 -0.9152311 -0.38524 -0.09863936 -0.9150694 -0.3910477 -0.104865 -0.9529408 -0.2844417 -0.08420282 -0.9533632 -0.2898422 -0.07867842 -0.9790247 -0.1879371 -0.08923697 -0.9926239 -0.08206504 -0.10233 -0.9774299 -0.1848226 -0.1172863 -0.993073 -0.007080495 -0.1107531 -0.9938479 -4.88302e-4 -0.1162168 -0.9932144 -0.004364192 -0.1135941 -0.9935267 -0.001090824 -0.09671425 -0.9953119 -6.71415e-4 -0.1047099 -0.9944847 -0.006012141 -0.1053819 -0.9943985 -0.00814855 -0.1004505 -0.9949418 -7.88541e-4 -0.09888303 -0.9950869 -0.004913628 -0.09729474 -0.9952267 -0.007599234 -0.08002066 -0.9964436 0.02639883 -0.100432 -0.9949432 -0.001264691 -0.06283891 -0.9883931 0.1383128 -0.03491353 -0.9993696 -0.006439447 -0.05664342 -0.9983102 0.01297056 -0.1002802 -0.9949591 -6.99761e-4 -0.1000522 -0.9949821 -3.93004e-4 -0.05999964 -0.9893229 0.1328171 -0.05221831 -0.9694423 0.2396978 -0.07083529 -0.9935863 0.08813971 -0.03292959 -0.9854176 0.1669371 -0.02270603 -0.9880799 0.1522588 -0.02145469 -0.9549937 0.2958491 -0.04434442 -0.9504611 0.3076646 -0.0534693 -0.986069 0.1575086 -0.03839349 -0.9848337 0.1692001 -0.02520173 -0.9985184 -0.04822725 -0.011532 -0.9996369 0.02435827 -0.07376569 -0.3000071 -0.9510806 -0.08838355 -0.3968409 -0.9136223 -0.08279836 -0.2971952 -0.9512201 -0.08597266 -0.7289521 -0.6791447 -0.07541221 -0.6579573 -0.7492699 -0.07678556 -0.728761 -0.6804495 -0.07687675 -0.1926649 -0.9782486 -0.06500566 -0.1958715 -0.9784726 -0.08496564 -0.4889187 -0.8681817 -0.07022416 -0.4030337 -0.912487 -0.0722689 -0.4959029 -0.8653656 -0.06100815 -0.3034538 -0.9508911 -0.08060055 -0.3980894 -0.9137989 -0.07269734 -0.08759087 -0.9935004 -0.07589977 -0.04767006 -0.9959754 -0.02191233 -0.01913517 -0.9995768 -0.04568684 -0.09305226 -0.9946126 -0.03747707 -0.01858592 -0.9991247 -0.05453813 -0.0179454 -0.9983505 -0.06176978 -0.09134238 -0.993902 -0.0342729 0.06900358 -0.9970276 -0.07053345 2.7069e-4 -0.9975095 -0.04321509 0.06790506 -0.9967554 -0.04941046 0.01797574 -0.9986169 -0.2619787 -0.744796 -0.6137151 -0.2831559 -0.8010644 -0.5273694 -0.1693814 -0.2675616 -0.9485361 -0.1350456 -0.1775583 -0.9748004 -0.167212 -0.2801313 -0.9452866 -0.09381604 -0.04458856 -0.9945906 -0.06265634 -0.006317496 -0.9980152 -0.4456071 -0.009186148 -0.8951816 -0.5601838 0.004211664 -0.8283578 -0.5714372 -0.01162767 -0.8205635 -0.3221298 -0.04907476 -0.9454228 -0.1839092 -0.0117194 -0.9828734 -0.207589 -0.06637841 -0.9759615 -0.3915644 -0.221388 -0.8931208 -0.5162926 -0.1996868 -0.8328068 -0.3583211 -0.1373651 -0.9234375 -0.1052281 -0.01342815 -0.9943575 -0.04352015 -0.8880125 -0.4577551 -0.05102807 -0.9368474 -0.345996 -0.05347001 -0.8919605 -0.4489406 -0.3185603 -0.3314089 -0.8880808 -0.4249472 -0.3069911 -0.8515729 -0.2816872 -0.2394798 -0.9291403 -0.1299806 -0.0701633 -0.989031 -0.4578747 -0.3936325 -0.7971225 -0.3539953 -0.4241291 -0.8335478 -0.16819 -0.1597058 -0.9727313 -0.2444319 -0.1502787 -0.9579507 -0.3105084 -0.5408109 -0.7817342 -0.4154278 -0.6004049 -0.6833257 -0.3867992 -0.5150406 -0.7649311 -0.2437233 -0.3504781 -0.9043031 -0.2788243 -0.4469552 -0.8499931 -0.2066431 -0.2539168 -0.9448942 -0.1320249 -0.1677931 -0.9769417 -0.264324 -0.5604792 -0.7848541 -0.3363226 -0.6291857 -0.7007229 -0.282819 -0.6507859 -0.7046214 -0.3147777 -0.7934756 -0.5208758 -0.3771238 -0.8278291 -0.4153031 -0.378624 -0.8685523 -0.3197825 -0.375783 -0.8981192 -0.2284057 -0.2043885 -0.3701395 -0.9062131 -0.2011831 -0.3906774 -0.8982742 0.03661918 -5.01061e-5 -0.9993293 0.01699894 -0.2849844 -0.9583815 0.01400804 -0.2687476 -0.9631088 0.02942061 -0.1371844 -0.9901085 0.03319615 -1.0599e-5 -0.999449 0.03344893 -0.02816915 -0.9990434 0.02459806 -0.1465508 -0.9888974 0.03851479 -0.02624619 -0.9989134 -0.006348013 -0.5394905 -0.8419678 -0.01788431 -0.5309453 -0.8472174 -0.004669308 -0.4619914 -0.8868721 -0.04815977 -0.8486256 -0.5267974 -0.03671485 -0.8485921 -0.5277721 -0.04294025 -0.9337297 -0.3553941 -0.04522895 -0.9672965 -0.2495836 -0.02964669 -0.9994626 0.01398789 -0.0325573 -0.9993181 0.01742088 -0.03209006 -0.999282 0.02014166 -0.02899414 -0.9994335 0.01709294 0.02353 -0.2790036 -0.9600018 0.02942055 -0.1434406 -0.9892215 0.02981746 -0.2895684 -0.9566928 0.02896255 -0.403401 -0.9145649 0.02365219 -0.399158 -0.9165771 0.0285961 -0.1482604 -0.9885349 0.03390675 -0.02136337 -0.9991968 0.0298478 -0.03088539 -0.9990772 0.0265215 -0.5643683 -0.8250971 0.01800656 -0.551917 -0.8337047 0.02404934 -0.4803764 -0.8767327 0.03025692 -3.51725e-5 -0.9995422 0.02470636 -0.007397592 -0.9996674 0.02350008 -0.6833044 -0.7297554 0.02649086 -0.7451027 -0.6664234 0.01556479 -0.7436926 -0.6683406 0.03482252 -0.6541813 -0.7555359 0.03375399 -0.6824349 -0.7301667 0.03613507 -0.6139305 -0.7885326 0.04477161 -0.5824583 -0.8116267 0.0398885 -0.6142588 -0.7880959 0.04355049 -0.5461973 -0.8365238 0.05096703 -0.5167817 -0.8545988 0.03976583 -0.4764578 -0.8782976 0.04828131 -0.4757022 -0.8782804 -0.2454982 -0.5773665 -0.7787032 -0.236735 -0.5911204 -0.7710598 -0.2550473 -0.6696479 -0.6975117 0.05343919 -0.5075355 -0.8599721 0.05310374 -0.5072022 -0.8601896 0.05835199 -0.4815263 -0.874487 -0.2229747 -0.492339 -0.8413589 -0.2177881 -0.5057408 -0.8347423 -0.2061858 -0.4005609 -0.8927701 -0.1844251 -0.2932246 -0.9380868 0.05050873 -0.2716486 -0.9610702 0.0487079 -0.3771505 -0.9248703 0.04245239 -0.277024 -0.9599248 -0.1480469 -0.01467955 -0.9888715 -0.1650771 -0.08490377 -0.9826195 -0.1450291 -0.08377623 -0.9858744 0.0832262 -0.5072923 -0.8577458 0.05969464 -0.3977204 -0.9155628 0.0626561 -0.3847566 -0.920889 0.05719286 -0.2603282 -0.9638248 0.06149512 -0.2966416 -0.9530069 0.06286835 -0.2582792 -0.9640226 0.06381607 -0.3375449 -0.9391438 -0.181863 -9.15572e-5 -0.9833239 -0.1784783 -0.01510715 -0.9838279 -0.1749952 0 -0.9845694 -0.1684066 -0.01544284 -0.9855967 0.0506252 -0.006870388 -0.9986942 0.04835593 1.34151e-5 -0.9988303 0.04814416 1.16799e-4 -0.9988404 0.04810124 1.15291e-5 -0.9988425 0.04849535 -0.02523952 -0.9985045 0.05096745 -0.1290667 -0.9903253 0.04544246 -0.02572733 -0.9986357 0.04928821 -0.2064306 -0.9772191 0.05380517 -0.1286991 -0.9902231 0.06323617 -0.2608188 -0.9633145 0.06643968 -0.362046 -0.9297896 0.0483604 8.82711e-6 -0.99883 0.06964445 -0.4041638 -0.9120315 0.03231936 -0.7290933 -0.6836509 0.03250271 -0.7330355 -0.6794136 0.03607332 -0.5572445 -0.8295646 0.0124517 -0.6833195 -0.7300135 0.02008152 -0.6328741 -0.7739943 -0.01327586 -0.9995082 -0.02841347 -3.66226e-4 -0.9897871 -0.1425535 -0.008942067 -0.9995025 -0.03024446 0.01168882 -0.7446394 -0.6673647 0.01977604 -0.9253558 -0.3785838 0.01263511 -0.927643 -0.3732545 0.0227676 -0.8912029 -0.453033 0.008728444 -0.7960302 -0.6051941 0.01950192 -0.7972916 -0.6032792 9.15567e-4 -0.9617731 -0.2738462 -0.009613513 -0.9898891 -0.1415174 0.002014219 -0.8858943 -0.4638829 0.01037645 -0.8429659 -0.5378672 0.01217716 -0.8885685 -0.4585825 0.005310297 -0.8440992 -0.5361608 0.02725404 -0.8391683 -0.5431887 0.02185153 -0.846535 -0.5318845 0.01187199 -0.9630678 -0.2689973 0.01712113 -0.9494165 -0.3135525 0.01303154 -0.9753552 -0.2202553 0.006622552 -0.9913702 -0.1309253 0.002349913 -0.9955813 -0.09387552 0.01059019 -0.9901692 -0.1394733 -0.01204741 -0.9999275 -7.68312e-6 0.001525938 -0.9997031 -0.0243234 -0.006506264 -0.9999789 5.98988e-5 -0.0122351 -0.9996953 0.02144223 -0.001712858 -0.9997956 0.02014791 -0.0196138 -0.9997192 0.01330202 -0.03348875 -0.9994296 0.004372835 -0.02562952 -0.9996213 -0.01003134 -0.03204333 -0.9994301 -0.01062005 -0.02354842 -0.9991248 -0.0345717 -0.02416241 -0.9991244 -0.03415673 -0.02131623 -0.9986588 -0.0471853 -0.02871167 -0.999585 0.002324044 -0.02988499 -0.998005 0.05561381 -0.0296629 -0.998017 0.05551707 -0.003656923 -0.9929028 0.1188731 -0.03014546 -0.9934318 0.1103844 -0.003709733 -0.986675 0.162662 -0.03038829 -0.9876607 0.1536333 -0.03064513 -0.9698325 0.2418385 -0.03054767 -0.9796386 0.1984314 -0.02063059 -0.9898126 0.1408742 -0.1003941 -0.9949474 -8.99619e-4 -0.0994305 -0.9950378 -0.003662228 -0.1000111 -0.9949834 -0.002411007 -0.09173959 -0.9956467 -0.01648014 -0.1028807 -0.9946861 -0.003906428 -0.08920693 -0.9958341 -0.01889121 -0.07068127 -0.9973505 -0.01721251 -0.1059918 -0.9943026 -0.01132243 -0.1150859 -0.9933527 -0.00238043 -0.1142625 -0.9934495 -0.001586973 -0.1182293 -0.9929245 -0.01107823 -0.1192061 -0.9927128 -0.01763981 -0.1221371 -0.9925088 -0.002990841 -0.1222893 -0.9923536 -0.01672434 -0.1254173 -0.9921011 -0.00244832 -0.05359095 -0.9984215 -0.01681584 -0.044528 -0.9793419 -0.1972479 -0.02792513 -0.9957839 -0.08737677 -0.04367291 -0.995353 -0.08581995 -0.1144148 -0.9901506 -0.08069157 -0.1320554 -0.9912247 -0.005920648 -0.1317827 -0.9912389 -0.008881092 -0.1407221 -0.9898771 -0.01846385 -0.1349108 -0.9908528 -0.003141999 -0.136856 -0.9905879 -0.002470314 -0.1056584 -0.9942639 -0.01660257 -0.1055678 -0.8047749 -0.5841172 -0.1181406 -0.8063839 -0.5794721 -0.1174705 -0.7344275 -0.6684437 -0.1382339 -0.9903965 -0.002474904 -0.1417942 -0.9898884 -0.003943324 -0.1507927 -0.988408 -0.01763975 -0.144478 -0.9894948 -0.005127191 -0.1430431 -0.9897043 -0.004944086 -0.1470051 -0.9891322 -0.002657353 -0.1512842 -0.9884887 -0.001842916 -0.1571404 -0.9875525 -0.006866633 -0.1583655 -0.9873352 -0.009460985 -0.1701116 -0.9852681 -0.01757878 -0.1774969 -0.9840151 -0.01446586 -0.1670299 -0.9859433 -0.004089474 -0.3540524 -0.9347704 0.02917623 -0.3213635 -0.9467558 0.01947098 -0.3977882 -0.9143576 -0.07559621 -0.6210911 -0.776463 -0.1065416 -0.575587 -0.8161067 0.05166852 -0.5093355 -0.8319847 -0.2199521 -0.1765144 -0.9842913 -0.00363624 -0.1747529 -0.9846103 -0.001983702 -0.1751478 -0.9845391 -0.002471983 -0.1795132 -0.9837517 -0.002746701 -0.1753304 -0.9845055 -0.002868711 -0.190378 -0.9817074 -0.00262463 -0.2027682 -0.9790798 -0.01696854 -0.1931563 -0.9810106 -0.01757907 -0.2033758 -0.9790973 -0.002624571 -0.2807764 -0.9597669 0.0035097 -0.5026202 -0.8481277 -0.1674892 -0.447202 -0.8924202 0.05997073 -0.6032172 -0.7138197 -0.3557959 -0.695504 -0.7174779 0.03872895 -0.7000163 -0.6245427 -0.3463001 -0.7152704 -0.6334493 -0.2951784 -0.7850776 -0.617008 -0.05435478 -0.8025819 -0.5739965 -0.1624512 -0.8074699 -0.5604192 -0.1841817 -0.8472484 -0.5301215 -0.03378492 -0.8642619 -0.4901624 -0.1131026 -0.8755964 -0.476405 -0.07980775 -0.8943038 -0.4468315 -0.0237134 -0.9073359 -0.4113683 -0.08670502 -0.9132789 -0.4071225 -0.01315361 -0.9182964 -0.3957748 -0.009705126 -0.1694731 -0.9854952 -0.008850514 -0.1701127 -0.9853965 -0.007446587 -0.162015 -0.9867814 -0.003688514 -0.4623628 -0.8851121 -0.0528894 -0.5839531 -0.8102524 -0.04989874 -0.2499539 -0.9681366 -0.01532071 -0.2295017 -0.9731545 -0.01730418 -0.2459235 -0.9692893 -1.52596e-4 -0.2826954 -0.9591441 -0.01123088 -0.3563662 -0.9342976 -0.009552299 -0.4678649 -0.8736836 -0.13334 -0.3695524 -0.918281 -0.1420956 -0.3616569 -0.9302669 -0.06171053 -0.2900564 -0.9547386 -0.06589138 -0.3016861 -0.9418038 -0.1482946 -0.2493735 -0.9659676 -0.068699 -0.2604174 -0.9527679 -0.1562564 -0.3112953 -0.9202437 -0.2371642 -0.1017183 1.22074e-4 -0.9948133 -0.119511 1.22075e-4 -0.9928328 -0.1051381 -0.01519846 -0.9943414 -0.2788822 -0.9288748 -0.2437548 -0.4383834 -0.6765583 -0.5916833 -0.5410558 -0.6288004 -0.5584521 -0.5174192 -0.5584673 -0.6483762 -0.5991923 -0.4327991 -0.6735382 -0.6918643 -0.3848743 -0.6108976 -0.5719695 -0.3559206 -0.7390342 -0.7444453 -0.03653097 -0.6666833 -0.7444131 -0.04858583 -0.6659494 -0.7147269 -0.00903362 -0.6993453 -0.2376511 -0.06610405 -0.9690988 -0.4886409 -0.1235717 -0.8636898 -0.4548255 -0.7403923 -0.4949275 -0.1239687 -0.08102828 -0.9889723 -0.1013219 -0.07910436 -0.9917038 -0.2832776 -0.8982359 -0.336045 -0.2348139 -0.469811 -0.8509641 -0.2646675 -0.8084079 -0.5257642 -0.1691664 -0.186318 -0.9678163 -0.1509787 -0.1819862 -0.9716412 -0.1745398 -0.984644 -0.003479182 -0.1754416 -0.984486 -0.002788186 -0.1746966 -0.9846205 -0.001929759 -0.1003164 -0.9949547 -0.001403868 -0.03125482 -0.9590934 0.2813596 -0.005366086 -0.9782382 0.207416 -0.01529008 -0.992667 0.1199098 -0.02148538 -0.967211 0.2530643 -0.007061183 -0.9966744 0.08118075 -0.01225864 -0.9998821 0.009250462 -0.01871997 -0.9994247 -0.02828133 -0.02804821 -0.9991244 -0.03104412 -0.02630192 -0.9982826 -0.0523476 -0.02931946 -0.998627 -0.04341191 -0.02903157 -0.9995784 -5.67532e-4 -0.03352928 -0.9994378 -1.12701e-4 -0.03374832 -0.999412 0.006075441 -0.02481549 -0.999692 5.17674e-4 -0.0248174 -0.999692 2.06314e-4 -0.01887184 -0.9997543 0.01163917 -0.006959199 -0.9998261 0.01730102 -0.004976749 -0.9999088 0.01255536 -0.9077398 -0.419093 -0.0192272 -0.8901479 -0.4540618 -0.03827083 -0.9086261 -0.4175981 -0.003235042 -0.1708756 -0.9852736 -0.006134271 -0.1728593 -0.984938 -0.004089534 -0.20512 -0.9783565 -0.0272842 -0.2161639 -0.9763544 -0.00225836 -0.1808465 -0.9834852 -0.007171213 -0.1873892 -0.9822065 -0.0124824 -0.1089841 -0.9940415 -0.002044737 -0.006846785 -0.9999765 3.09504e-4 -0.007377743 -0.9999728 5.47275e-5 -0.007267057 -0.9999736 -1.68845e-6 -0.01408213 -0.9999007 5.93332e-4 -0.02162057 -0.9997662 4.58231e-4 -0.02401238 -0.9997115 -5.51925e-4 -0.0320971 -0.9994848 -1.81037e-4 -0.03140151 -0.999507 1.2278e-4 -0.03297364 -0.9994562 4.17995e-4 -0.03196728 -0.999489 -2.50295e-4 -0.02845555 -0.9995951 -7.70717e-5 -0.02106213 -0.9997782 -1.36936e-4 -0.01898682 -0.9998197 4.75725e-4 -0.002899289 -0.9982829 -0.05850529 0.00238043 -0.9998256 -0.01852488 -0.006639957 -0.999978 5.3346e-6 0.003275215 -0.9999946 1.40873e-4 -0.9047853 -0.4235211 -0.04465019 -0.9030631 -0.4248273 -0.06323575 -0.882277 -0.4578171 -0.1095026 -0.6975017 -0.7080917 -0.1099889 -0.6992854 -0.7132021 -0.04840332 -0.7866287 -0.6155999 -0.04745709 -0.219828 -0.9753857 -0.01727372 -0.2299913 -0.9731907 -0.002014219 -0.1718207 -0.9851153 -0.005066096 -0.0110194 -0.9999394 1.57561e-5 -0.008109211 -0.9999672 2.03885e-4 -0.01193147 -0.9999288 -3.22081e-4 -0.01612764 -0.9998699 -3.40792e-4 -0.01994919 -0.9998009 -3.57119e-4 -0.02746152 -0.9996229 3.00311e-4 -0.02395755 -0.9993514 -0.02688741 -0.0313428 -0.9870398 -0.1573855 -0.03402876 -0.9975776 -0.06067192 -0.02819216 -0.9996026 8.90103e-5 -0.02445089 -0.9997011 5.3357e-5 -0.01716214 -0.9998527 -1.17711e-4 -0.01168102 -0.9999319 1.61714e-4 -0.902186 -0.4228778 -0.08505773 -0.9001318 -0.4221714 -0.1073969 -0.4704542 -0.8556376 -0.215771 -0.5851725 -0.8016442 -0.1222288 -0.5838391 -0.7871909 -0.1986517 -0.1609056 -0.9869582 -0.004772126 -0.1622563 -0.9867423 -0.003564238 -0.1269895 -0.9918976 -0.003601193 -0.1294322 -0.991571 -0.005859673 -0.0336014 -0.9992839 -0.01739579 -0.02127176 -0.99959 -0.01916593 -0.01169198 -0.9999317 -2.31153e-4 -0.06088501 -0.944893 -0.3216683 -0.07028687 -0.9016742 -0.4266655 -0.06207656 -0.9405791 -0.3338523 -0.0336728 -0.9994329 -4.29594e-7 -8.61867e-5 -1 -1.73268e-4 -0.8967359 -0.4227473 -0.1309564 -0.8851649 -0.409317 -0.2212302 -0.8814582 -0.4035871 -0.245253 -0.8645033 -0.4368752 -0.2485443 -0.8730934 -0.4507992 -0.1857093 -0.8881365 -0.4143274 -0.1988624 -0.6870171 -0.6806386 -0.2544384 -0.6934326 -0.6979494 -0.1789355 -0.7785822 -0.606727 -0.1602882 -0.1601931 -0.9870693 -0.005706965 -0.1590664 -0.9872376 -0.007751882 -0.1513423 -0.9884797 -0.001854956 -0.1510275 -0.988528 -0.001799166 -0.06406015 -0.9943822 -0.08426398 -0.008209705 -0.9630716 -0.2691205 -0.001709461 -0.9999985 2.32881e-4 0.003907144 -0.9999924 5.41008e-5 -0.8940498 -0.4212211 -0.1524721 -0.8915184 -0.4176513 -0.1753922 -0.8444041 -0.5310639 -0.07037717 -0.8778862 -0.397086 -0.2676538 -0.8541085 -0.4160063 -0.3121497 -0.2202537 -0.9727846 -0.07196313 -0.1465204 -0.9892034 -0.002929747 -0.1673359 -0.9830489 -0.07492423 -0.1406925 -0.9870761 -0.07672476 -0.1925149 -0.9785361 -0.07352066 -0.05905467 -0.97982 -0.1909588 -0.127385 -0.9750724 -0.1816778 -0.1282709 -0.9516398 -0.2791562 -0.06817847 -0.9531868 -0.2945958 -0.0115056 -0.9997673 -0.01825022 -0.02530044 -0.9952334 -0.09418243 -0.01290959 -0.9997479 -0.01837253 -0.01995933 -0.9996474 -0.01751786 -0.03308224 -0.9949095 -0.09518778 -0.05075383 -0.9752182 -0.2153452 -0.03988838 -0.9939441 -0.1023914 -0.02670389 -0.9994899 -0.01751774 -0.05289012 -0.9718908 -0.2294144 -0.03265571 -0.9992656 -0.02005118 -0.0418719 -0.9919862 -0.1192068 -0.03430366 -0.9992324 -0.01892197 -0.03744661 -0.9913139 -0.1260734 -0.03482204 -0.999006 -0.02783322 -0.03122073 -0.9990946 -0.02890127 -0.0295118 -0.9901568 -0.1368164 -0.02609354 -0.9991862 -0.03076297 -0.01828062 -0.9996356 -0.01986753 -0.01284861 -0.9959055 -0.08948254 -0.001525938 -0.9995424 -0.03021425 -0.865305 -0.3705311 -0.3375706 -0.8606668 -0.3583543 -0.3617113 -0.8414832 -0.3864377 -0.3775871 -0.7832658 -0.6135201 -0.1004375 -0.6640778 -0.6164976 -0.4230028 -0.6774587 -0.6542338 -0.3361963 -0.7613968 -0.5737333 -0.3018364 -0.4698452 -0.8286611 -0.3042473 -0.2316699 -0.9587855 -0.1644975 -0.2049065 -0.9638906 -0.1700839 -0.1402365 -0.9145742 -0.3793253 -0.1510378 -0.8669797 -0.474904 -0.1528419 -0.9720173 -0.1783868 -0.1787188 -0.9682736 -0.1746597 -0.04376423 -0.9774628 -0.2065221 -0.05075329 -0.9688599 -0.2423523 -0.03753805 -0.9656744 -0.2570289 -0.03439527 -0.9651125 -0.2595669 -0.01748764 -0.9465327 -0.3221336 -0.0252701 -0.9653614 -0.2596902 0.01559513 -0.9641235 -0.2649958 0.01190239 -0.983505 -0.1804893 -0.8742893 -0.3886646 -0.2907888 -0.8373154 -0.5275185 -0.1436217 -0.843977 -0.31685 -0.4327923 -0.8382354 -0.3009175 -0.4547639 -0.8268018 -0.3483488 -0.4416466 -0.771034 -0.5944811 -0.2282521 -0.5797132 -0.7645683 -0.2817232 -0.4649891 -0.7908721 -0.3978776 -0.2545894 -0.9351933 -0.2461661 -0.2285905 -0.9396016 -0.2547457 -0.177226 -0.9468941 -0.2682958 -0.1525037 -0.9495701 -0.2739697 -0.2026467 -0.9435588 -0.2619759 -0.08328652 -0.914168 -0.3966867 -0.09708124 -0.8645756 -0.493036 -0.08581918 -0.8609694 -0.5013649 -0.07278877 -0.9116756 -0.4044126 -0.05734586 -0.9514105 -0.3025384 -0.07873874 -0.7963906 -0.5996353 -0.08279818 -0.7946859 -0.6013476 -0.07806783 -0.8565491 -0.5101267 -0.05734485 -0.939278 -0.3383317 -0.032808 -0.9294888 -0.3673886 -0.02255386 -0.9273328 -0.3735578 0.001037597 -0.9262605 -0.3768827 -0.003753781 -0.9079673 -0.4190243 -0.8692134 -0.3805117 -0.3157197 -0.8306073 -0.5172679 -0.2062174 -0.8105573 -0.3027496 -0.5013376 -0.5718407 -0.7317621 -0.3708404 -0.2608146 -0.9025968 -0.3424832 -0.2360041 -0.9062644 -0.3506948 -0.1868084 -0.9115797 -0.366231 -0.1631275 -0.9133616 -0.3730416 -0.2110701 -0.909256 -0.3587521 -0.1045899 -0.7376235 -0.6670626 -0.09387749 -0.8052529 -0.5854526 -0.1031248 -0.728344 -0.6774072 -0.0558499 -0.9483197 -0.3123629 -0.06973636 -0.9077023 -0.4137794 -0.08838504 -0.7364709 -0.6706704 -0.06567704 -0.899275 -0.4324247 -0.06137424 -0.8953744 -0.4410645 -0.01690775 -0.6813156 -0.7317947 -0.03140395 -0.7372452 -0.6748951 -0.0268262 -0.6760879 -0.7363325 -0.03244131 -0.8871477 -0.4603438 -0.02581882 -0.8458881 -0.5327352 -0.01751774 -0.8445773 -0.5351472 -0.01232981 -0.8756011 -0.4828777 -0.0213328 -0.8883186 -0.4587321 0.001098632 -0.813669 -0.5813273 0.02475082 -0.8992394 -0.436756 -0.8552001 -0.3463588 -0.3855755 -0.8503028 -0.3322044 -0.4081978 -0.8211923 -0.5013464 -0.272571 -0.7486619 -0.5429638 -0.380389 -0.646336 -0.5662841 -0.5114411 -0.5591785 -0.6868416 -0.4642933 -0.2645111 -0.8607065 -0.4349921 -0.241074 -0.8641308 -0.4417706 -0.1944701 -0.8672719 -0.4582804 -0.1724646 -0.8669925 -0.4675253 -0.2177881 -0.8663914 -0.449371 -0.1339797 -0.8084868 -0.5730609 -0.1299227 -0.7365341 -0.6638054 -0.1107842 -0.7308709 -0.6734645 -0.09387522 -0.8010832 -0.5911456 -0.1491158 -0.6687322 -0.7283968 -0.08157789 -0.8572546 -0.5083893 -0.08673548 -0.6664167 -0.7405173 -0.08728456 -0.6563435 -0.7493962 -0.07788473 -0.8527346 -0.5165054 -0.07327622 -0.8519393 -0.5184882 -0.06677621 -0.8496882 -0.52304 -0.05841404 -0.8488348 -0.5254212 -0.03509742 -0.7932938 -0.6078267 -0.02456825 -0.7943649 -0.6069439 0.02572757 -0.8705264 -0.4914488 -0.8320194 -0.2822127 -0.4775978 -0.8096258 -0.4760458 -0.3433463 -0.795697 -0.172342 -0.5806586 -0.7862901 -0.1452091 -0.6005517 -0.767383 -0.1688035 -0.6185698 -0.7326055 -0.5007231 -0.4610486 -0.6244084 -0.5041596 -0.5966047 -0.2431449 -0.8128738 -0.5292606 -0.1715765 -0.8128066 -0.556693 -0.1902561 -0.8147382 -0.5477265 -0.2221481 -0.8144617 -0.536006 -0.1777442 -0.7472034 -0.6403859 -0.1693208 -0.6669982 -0.7255646 -0.1616019 -0.7427586 -0.649765 -0.2095166 -0.813071 -0.5431562 -0.1523524 -0.8106236 -0.5654008 -0.1185989 -0.6438099 -0.7559387 -0.08838278 -0.8295961 -0.5513245 -0.07458847 -0.8296903 -0.5532184 -0.0870403 -0.5754671 -0.8131799 -0.09186393 -0.5770643 -0.8115158 -0.08859753 -0.4882174 -0.8682133 -0.07620638 -0.7929799 -0.6044629 -0.06778359 -0.7920395 -0.6066951 -0.05798542 -0.7917757 -0.6080535 -0.04693877 -0.7921915 -0.6084648 -0.01211595 -0.6199896 -0.7845165 -0.02096682 -0.7402482 -0.6720068 -0.0142523 -0.796116 -0.6049761 -0.00689727 -0.7871462 -0.6167281 0.02938991 -0.7969473 -0.6033336 0.03076308 -0.8067998 -0.5900235 -0.7925743 -0.2481487 -0.5569993 -0.8247579 -0.2630472 -0.5005802 -0.8181331 -0.242568 -0.5213626 -0.7953933 -0.4406067 -0.4161913 -0.7748163 -0.118078 -0.6210616 -0.7353963 -0.06811934 -0.6742048 -0.2425954 -0.7519878 -0.6129127 -0.2234619 -0.7543139 -0.617313 -0.2058838 -0.7530051 -0.6249762 -0.1914445 -0.7507321 -0.6322582 -0.1449075 -0.7391567 -0.6577607 -0.1232987 -0.4964298 -0.8592758 -0.1170412 -0.5712894 -0.8123608 -0.1174691 -0.4857465 -0.8661706 -0.06631833 -0.7294104 -0.6808543 -0.05517858 -0.7309942 -0.6801493 -0.04336804 -0.7335948 -0.678202 -0.01199382 -0.7437413 -0.6683601 0.007995843 -0.6967711 -0.7172491 0.03119069 -0.77104 -0.6360225 -0.8082369 -0.2200426 -0.5462001 -0.8019275 -0.1991084 -0.5632658 -0.7787386 -0.395168 -0.4872457 -0.7133933 -0.4472327 -0.5394932 -0.6460341 -0.2471764 -0.7221799 -0.5440632 -0.2772656 -0.7919085 -0.2393904 -0.6792292 -0.6937867 -0.1928789 -0.6758086 -0.7113935 -0.2232815 -0.6827239 -0.6957252 -0.20726 -0.6810192 -0.702322 -0.1777148 -0.6736561 -0.7173599 -0.1546729 -0.6618158 -0.7335367 -0.1321471 -0.4827489 -0.8657314 -0.1212207 -0.4840892 -0.8665814 -0.1270819 -0.5729981 -0.809644 -0.1215876 -0.4005922 -0.9081534 -0.1133773 -0.6566728 -0.7456046 -0.06308335 -0.6605592 -0.7481191 -0.0508446 -0.6643376 -0.7457013 -0.0385766 -0.6695369 -0.7417765 -0.0195322 -0.6019588 -0.7982883 -0.007293999 -0.686737 -0.7268694 -0.001068115 -0.6845395 -0.7289751 -0.7674273 -0.0906105 -0.6347008 -0.7602033 -0.3412354 -0.5528557 -0.489229 -0.4787303 -0.7290214 -0.09390604 -0.07348901 -0.992865 -0.2266674 -0.6023609 -0.7653648 -0.2150673 -0.5995761 -0.7708792 -0.2021293 -0.5967745 -0.7765333 -0.1890963 -0.5886525 -0.7859585 -0.17457 -0.5827038 -0.7937139 -0.1628182 -0.5769901 -0.8003578 -0.1269586 -0.35289 -0.9270115 -0.1185961 -0.2953305 -0.9480058 -0.1142947 -0.2847144 -0.9517744 -0.1150586 -0.5750488 -0.809988 -0.08163923 -0.6216788 -0.7790061 -0.09155684 -0.5560554 -0.8260871 -0.07074338 -0.5764456 -0.8140676 -0.05658227 -0.5806245 -0.8122029 -0.04333722 -0.586121 -0.8090637 -0.03103804 -0.5933244 -0.8043649 0.01208567 -0.4532744 -0.8912891 0.003021359 -0.478142 -0.8782774 0.01193308 -0.3912892 -0.9201905 0.003601253 -0.5505415 -0.8348001 -0.005218744 -0.6184101 -0.7858383 0.004730522 -0.5791078 -0.8152374 0.0142219 -0.5848083 -0.8110469 0.01928824 -0.4910262 -0.8709313 0.02932852 -0.6292971 -0.7766113 0.03524971 -0.6406297 -0.7670404 -0.7406454 -0.28203 -0.6098391 -0.6690705 -0.3169104 -0.6722444 -0.2063406 -0.5056124 -0.837723 -0.1977046 -0.5014337 -0.8423047 -0.1843365 -0.4924898 -0.8505727 -0.1683447 -0.4860511 -0.8575631 -0.1134402 -0.2013664 -0.972925 -0.09277689 -0.4101411 -0.9072909 -0.09201395 -0.3140072 -0.9449514 -0.08722376 -0.2222101 -0.9710895 -0.05560654 -0.5009779 -0.8636719 -0.04123121 -0.5062502 -0.8614006 -0.02874898 -0.5172377 -0.8553588 0.001586973 -0.03164821 -0.9994979 -0.01318418 0.1724016 -0.9849385 0.03296065 -0.3953143 -0.9179545 -0.7474176 -0.03506666 -0.6634285 -0.7208274 -0.2212319 -0.6568596 -0.06769198 -0.01327592 -0.997618 -0.1214357 -0.01519852 -0.992483 -0.2049677 -0.4068837 -0.8901877 -0.1910216 -0.3958686 -0.8982198 -0.1969088 -0.4003182 -0.8949707 -0.177746 -0.3910474 -0.9030439 -0.1331235 -0.01727366 -0.990949 -0.1180165 -0.1914755 -0.9743764 -0.1235408 -0.3874993 -0.9135547 -0.1366659 -0.3872302 -0.9117978 -0.05176073 -0.4122547 -0.9095972 -0.05795633 -0.4072815 -0.911462 -0.03775167 -0.418473 -0.9074444 -0.02423173 -0.4274438 -0.9037172 -0.0134285 -0.4433849 -0.8962308 0.006683528 -0.382673 -0.9238597 0.0318315 -0.1145081 -0.9929122 0.03173965 -0.4778345 -0.8778763 0.05905413 -0.5305107 -0.8456188 -0.7012076 -0.1581501 -0.6951953 -0.6582157 -0.01193314 -0.7527348 -0.6300988 -0.1612328 -0.7595916 -0.6233793 -0.1780168 -0.7613859 -0.1940385 -0.2978025 -0.9346994 -0.1964859 -0.298025 -0.934117 -0.1923328 -0.2904219 -0.9373704 -0.1832075 -0.2902082 -0.9392626 -0.1728904 -0.2906329 -0.9410853 -0.1603487 -0.2894762 -0.9436588 -0.1467045 -0.2900825 -0.9456902 -0.1315971 -0.2913631 -0.9475176 -0.1007749 -0.1109378 -0.9887049 -0.08685827 -0.1451198 -0.9855943 -0.04983741 -0.3074175 -0.9502688 -0.0394001 -0.3117216 -0.9493563 -0.03299111 -0.3168795 -0.9478919 -0.01922678 -0.3266423 -0.9449525 -0.007660269 -0.3429726 -0.9393141 5.79867e-4 -0.362539 -0.9319685 0.03662288 -0.3980301 -0.9166411 0.04217785 -0.3789292 -0.9244641 0.0661959 -0.5360376 -0.8415949 0.06378442 -0.4737749 -0.8783331 0.06082552 -0.4833386 -0.8733178 -0.7587406 -0.05829185 -0.6487795 -0.6837891 -0.09912729 -0.7229151 -0.6010434 -0.1093805 -0.7916962 -0.5384814 -0.254561 -0.8032662 -0.481076 -0.008606433 -0.8766368 -0.06878888 -0.01419109 -0.9975303 -0.1803696 -0.1904104 -0.9649926 -0.1899207 -0.1913551 -0.9629712 -0.1883045 -0.1878162 -0.9639848 -0.1751782 -0.1847306 -0.9670509 -0.1626374 -0.1854048 -0.96911 -0.05090546 -0.1992881 -0.9786179 -0.03845357 -0.2034073 -0.9783388 -0.0270096 -0.2083249 -0.9776867 -0.01413029 -0.2188214 -0.9756627 -0.001220762 -0.2347865 -0.9720462 0.008179068 -0.251873 -0.9677258 0.02826076 -0.1262273 -0.9915988 0.01898288 -0.30394 -0.9525021 0.034639 -0.2798284 -0.9594249 0.08691805 -0.6270128 -0.7741448 0.100562 -0.6706987 -0.7348814 -0.6627816 -0.03375399 -0.7480518 -0.4585869 -0.04379552 -0.8875697 -0.5774857 -0.03689777 -0.8155666 -0.05583184 -1.45185e-5 -0.9984402 -0.08194416 6.10385e-5 -0.9966369 -0.06387537 -6.71409e-4 -0.9979578 -0.0892992 -0.01425242 -0.9959029 -0.1387401 -0.01434397 -0.9902249 -0.1783828 -0.08484244 -0.9802966 -0.1875718 -0.0849353 -0.9785718 -0.1825666 -0.08563721 -0.9794569 -0.1840628 -0.01577854 -0.9827879 -0.1754521 -0.01815861 -0.9843205 -0.1701159 -0.08356249 -0.9818748 -0.1563804 -0.08359211 -0.9841533 -0.1629089 -0.01745665 -0.9864868 -0.1478652 -0.01760953 -0.9888508 -0.1207322 -0.08764988 -0.988808 -0.1048634 -0.08044815 -0.9912275 -0.03122067 -0.09579831 -0.9949111 -0.01803666 -0.09814882 -0.9950084 -0.006103813 -0.102514 -0.9947129 0.008178949 -0.109989 -0.9938992 0.02087527 -0.1182323 -0.9927665 0.02908438 -0.03814846 -0.9988487 0.02346938 -0.1534209 -0.9878823 0.03518891 -0.144418 -0.9888909 0.04193317 -0.1390449 -0.9893979 0.04544335 -0.1327288 -0.9901102 0.05426317 -0.2284671 -0.9720382 0.1002243 -0.6285991 -0.7712447 0.04822033 -0.03912562 -0.9980701 -0.7075944 0.001190245 -0.7066178 -0.6515627 1.22078e-4 -0.7585948 -0.05877953 -0.01318418 -0.998184 -0.1615043 -0.01504564 -0.9867573 -0.1854318 -0.01641905 -0.9825201 -0.09164929 -0.02105826 -0.9955686 -0.07043802 -1.83114e-4 -0.9975162 -0.01110881 -0.02017289 -0.9997349 -4.27265e-4 -0.02151578 -0.9997685 0.01083403 -0.02346873 -0.9996659 0.02032583 -0.01977646 -0.9995979 0.02728414 -0.02713155 -0.9992595 0.03405934 -0.02249258 -0.9991667 0.03827065 -0.02771115 -0.9988832 0.03378468 -0.03085482 -0.9989528 0.03845357 -0.02871811 -0.9988477 0.04278767 -0.02862679 -0.9986741 0.04836177 8.36242e-6 -0.9988299 -0.296161 -8.24026e-4 -0.9551377 -0.1288215 0.01944071 -0.9914773 -0.1128892 0.02484232 -0.9932971 -0.02078342 0.07379502 -0.9970569 -0.02185142 0.05990839 -0.9979648 0.02903556 4.85639e-4 -0.9995784 0.03057301 -3.45234e-4 -0.9995325 0.03043413 -2.14679e-4 -0.9995368 -0.38296 -0.06451845 -0.9215091 -0.05520665 -2.24685e-4 -0.998475 -0.1862093 -1.13953e-4 -0.9825101 -0.185921 1.07635e-4 -0.9825648 -0.1799177 -2.14938e-5 -0.9836817 -0.1801165 1.75606e-4 -0.9836453 -0.1641595 -0.004791378 -0.9864222 -0.176308 -0.01593089 -0.9842062 -0.1559241 0.003265559 -0.9877637 -0.1434679 0.02044743 -0.9894437 -0.1274468 0.03997969 -0.9910393 -0.06975734 -4.49907e-5 -0.997564 0.0442366 -1.42729e-4 -0.9990211 0.03393566 1.22403e-4 -0.999424 -0.3607374 -0.1218633 -0.9246718 -0.02325522 0.2588294 -0.9656432 0.006164908 0.1930654 -0.9811666 0.01025438 0.1444469 -0.9894595 0.01385557 0.1070606 -0.994156 0.01785385 0.07758045 -0.9968263 0.02118003 0.05374354 -0.9983302 0.02776956 -2.41212e-4 -0.9996144 0.02381807 2.94491e-4 -0.9997164 0.02794092 -3.16309e-4 -0.9996096 0.0346902 -3.61618e-4 -0.9993981 0.03217518 2.80578e-4 -0.9994823 0.04017668 -3.85001e-4 -0.9991926 0.03737264 2.76696e-4 -0.9993014 0.04171371 2.27757e-4 -0.9991296 0.04443734 9.80478e-5 -0.9990122 0.04154056 -4.47806e-4 -0.9991368 0.03833132 5.12771e-4 -0.999265 0.0384112 4.64649e-4 -0.9992619 0.03503882 -1.84153e-4 -0.999386 -0.1962023 -0.04033601 -0.9797335 -0.1806121 -0.0276184 -0.9831666 -0.180198 -0.02993059 -0.983175 -0.1709166 -0.03603261 -0.9846264 -0.1727092 -0.03070247 -0.9844943 -0.03372353 0.1184444 -0.9923879 -0.01791471 0.1459732 -0.9891263 -0.08175957 0.2356654 -0.968389 0.03363311 7.72617e-6 -0.9994344 0.02871203 7.70402e-5 -0.9995878 0.03476339 -5.72787e-4 -0.9993954 0.03269648 -8.90406e-5 -0.9994654 0.03724199 5.13024e-4 -0.9993062 0.03896945 -1.21645e-4 -0.9992405 0.04099822 6.83719e-4 -0.999159 0.04283136 -1.16498e-4 -0.9990824 0.04474455 5.91792e-4 -0.9989984 0.04619812 -2.94895e-4 -0.9989323 -0.1344962 1.22075e-4 -0.9909141 -0.1470718 1.52596e-4 -0.9891259 -0.1577239 9.1558e-5 -0.9874833 -0.1670906 9.15565e-5 -0.9859415 0.02594113 0.431997 -0.901502 0.0223093 0.3288105 -0.9441324 0.02020364 0.2482123 -0.9684951 0.01913547 0.1839691 -0.9827457 0.01883035 0.1319044 -0.9910836 0.01907444 0.08911579 -0.9958387 0.03220224 0.1309401 -0.9908672 0.009693026 0.06942558 -0.9975401 0.0326851 0.08840554 -0.9955481 0.01264572 0.03747737 -0.9992175 0.03335201 0.05320173 -0.9980267 0.03198349 0.01222467 -0.9994137 0.01732337 9.69542e-4 -0.9998496 0.03180837 -0.03198951 -0.998982 0.02254134 -0.03641712 -0.9990825 0.03584206 -0.05817586 -0.9976628 0.03743451 -0.07958012 -0.9961254 0.03703224 -0.07976174 -0.9961259 0.03486371 -0.06432992 -0.9973195 0.02839881 -0.01022207 -0.9995445 0.03133249 -0.008495509 -0.999473 -0.1817227 4.10688e-4 -0.9833498 0.02793431 -0.0635966 -0.9975847 0.03554296 -0.07158285 -0.9968013 0.04522699 -0.06558972 -0.9968212 0.05260843 -0.05128884 -0.9972973 0.05328267 -0.1418886 -0.9884476 0.1007894 -0.05826056 -0.9932006 0.05811011 -0.08239454 -0.9949043 0.03083246 -0.1303874 -0.9909836 0.06329727 -8.7578e-4 -0.9979944 0.03214508 -0.06991708 -0.9970347 0.02812945 -0.008877038 -0.9995649 0.0332486 -9.86531e-4 -0.9994466 -0.1852166 -1.51839e-4 -0.9826977 -0.1869787 2.85033e-4 -0.982364 1 -7.248e-5 0 1 3.99991e-5 0 1 -2.64211e-5 0 1 2.84114e-5 0 1 -6.01628e-5 0 1 -9.06901e-5 0 1 -5.08325e-5 0 1 1.3442e-5 0 1 2.61436e-5 0 1 -8.54292e-5 0 1 5.11295e-5 0 1 -4.6565e-5 0 1 5.17428e-5 0 1 -6.35392e-5 0 1 7.13109e-6 0 1 3.96032e-5 0 1 6.98007e-5 0 1 -1.19076e-4 0 1 -2.98778e-5 0 1 -1.00266e-5 0 1 -1.32046e-4 0 1 1.32818e-4 0 1 1.51386e-5 0 1 1.91248e-5 0 1 -4.03302e-5 0 1 -4.14146e-5 0 1 -1.84906e-4 0 1 1.42342e-4 0 1 -2.89217e-5 0 1 -3.5821e-4 0 1 2.42958e-5 0 1 -8.81652e-5 0 1 2.87997e-5 0 1 1.77012e-5 0 1 -8.39869e-7 0 1 1.96297e-5 0 1 -3.60895e-5 0 1 9.49411e-5 0 1 3.65119e-5 0 1 8.7146e-5 0 1 6.40581e-5 0 1 4.42301e-5 0 1 -1.66205e-5 0 1 -3.25782e-5 0 1 7.77361e-5 0 1 2.90761e-5 0 1 6.98417e-6 0 1 -6.14588e-6 0 -0.02729821 -0.9996274 8.73465e-7 -0.02728968 -0.9996276 -6.09023e-5 -0.02731537 -0.9996269 6.39137e-5 -0.02729827 -0.9996274 -2.86679e-5 -0.0272848 -0.9996277 -5.34825e-5 -0.02729928 -0.9996274 0 -0.02729475 -0.9996275 0 -0.02731478 -0.9996269 1.93112e-4 -0.02730762 -0.9996272 -7.74125e-5 -0.02733713 -0.9996261 6.01777e-4 -0.02730572 -0.9996272 0 -0.02730053 -0.9996274 6.93489e-5 -0.02728855 -0.9996277 -2.18169e-4 -0.02718472 -0.9996303 -5.26075e-4 -0.02729868 -0.9996274 0 -0.02730071 -0.9996273 -3.65575e-5 -0.02722316 -0.9996294 -3.4748e-4 -0.02728211 -0.9996278 -1.67268e-4 -0.02729004 -0.9996276 -1.48292e-5 -0.02732241 -0.9996268 1.45026e-5 -0.02730643 -0.9996271 7.96706e-5 -0.0271824 -0.9996305 -2.25041e-4 -0.02748531 -0.9996222 2.22188e-4 -0.02751052 -0.9996216 2.16955e-4 -0.02556145 -0.9996728 -9.52916e-4 -0.02983915 -0.9995546 5.97343e-4 -0.03272676 -0.9994627 0.001830518 -0.02743303 -0.9996237 1.05668e-4 -0.02640026 -0.9996514 -5.15284e-4 -0.02722305 -0.9996294 4.02622e-5 -0.02770549 -0.9996162 3.8429e-4 -0.02746462 -0.9996227 2.47861e-4 -0.02754527 -0.9996206 2.65257e-4 -0.02695506 -0.9996366 -3.65044e-4 -0.02720957 -0.9996299 -8.46785e-5 -0.02720218 -0.99963 -1.83823e-4 -0.02735841 -0.9996258 1.32788e-4 -0.02743649 -0.9996236 2.52975e-4 -0.02726626 -0.9996283 -4.90834e-5 -0.02739316 -0.9996247 -2.09346e-4 -0.02741652 -0.9996241 2.65787e-4 -0.02727586 -0.999628 3.85659e-5 -0.02736282 -0.9996256 -1.39906e-4 -0.02731758 -0.9996269 1.25522e-4 -0.02730309 -0.9996272 3.50919e-5 -0.02731716 -0.9996268 1.74831e-4 -0.02728354 -0.9996278 -1.00998e-4 -0.02729308 -0.9996275 -2.06808e-4 -0.02730822 -0.9996271 1.66365e-4 -0.02729636 -0.9996275 0 -0.02730143 -0.9996273 3.82168e-5 -0.0273087 -0.9996271 -8.28345e-6 -0.02729862 -0.9996274 1.47282e-4 -0.02721184 -0.9996297 -1.15845e-4 -0.02729922 -0.9996274 1.78636e-6 -0.02734571 -0.9996261 7.10685e-5 -0.02723193 -0.9996292 -8.03302e-5 -0.02729928 -0.9996274 -7.75561e-7 -0.0272929 -0.9996275 2.1107e-4 -0.02728903 -0.9996276 -7.84029e-5 -0.02729767 -0.9996274 -4.23499e-5 -0.02729535 -0.9996274 -4.80082e-5 -0.02730721 -0.9996271 1.67676e-5 -0.02740579 -0.9996243 5.41215e-4 -0.02729845 -0.9996274 0 -0.02717334 -0.9996308 2.15772e-4 -0.02732384 -0.9996267 0 -0.02724081 -0.999629 1.47333e-4 -0.02737611 -0.9996253 -1.50841e-4 -0.02727824 -0.9996279 -6.18161e-5 -0.02728527 -0.9996278 9.16148e-6 -0.02730458 -0.9996272 -3.49491e-6 -0.0272904 -0.9996277 -5.33866e-6 -0.02730441 -0.9996272 -3.05603e-6 -0.02727824 -0.9996279 1.33116e-5 -0.02729701 -0.9996275 2.21971e-6 -0.02730756 -0.9996271 -1.11654e-6 -0.02729952 -0.9996274 -5.57191e-7 -0.02730202 -0.9996273 -2.61689e-6 -0.02729791 -0.9996274 -8.50725e-7 -0.0272879 -0.9996277 -2.7421e-6 -0.02729171 -0.9996275 4.04153e-4 -0.02729886 -0.9996274 0 -0.02729868 -0.9996274 0 -0.0273078 -0.9996269 -5.06096e-4 -0.02729874 -0.9996274 0 -0.02729523 -0.9996274 2.43558e-4 -0.02729833 -0.9996274 0 -0.02729868 -0.9996274 0 -0.02729815 -0.9996274 1.81996e-4 -0.02729958 -0.9996274 -1.42119e-4 -0.02729952 -0.9996274 1.67908e-4 -0.02729922 -0.9996273 -3.05991e-4 -0.02729898 -0.9996274 -3.98469e-5 -0.02729886 -0.9996274 0 -0.02729833 -0.9996274 2.42642e-5 -0.02729797 -0.9996274 -7.93857e-5 -0.02729803 -0.9996274 -3.8405e-5 -0.02729558 -0.9996274 -1.68161e-4 -0.02729934 -0.9996274 1.19431e-4 -0.02729588 -0.9996274 7.53092e-5 -0.02729558 -0.9996274 0 -0.02729612 -0.9996275 -8.9678e-5 -0.02729612 -0.9996274 0 -0.02729767 -0.9996273 3.37564e-4 -0.02729851 -0.9996274 6.80801e-5 0.9996745 -0.02373075 -0.009367406 0.9997213 -0.02355653 -0.001605033 0.9996635 -0.02308857 0.01182812 0.9996058 -0.02380764 -0.01488262 0.999673 -0.02404296 -0.008718371 0.9997242 -0.02348554 -3.05347e-5 0.9997278 -0.0233193 7.95288e-4 0.9997292 -0.0231294 0.002593219 0.9997102 -0.02392923 -0.002658784 0.9997243 -0.0234819 -1.01378e-4 0.9997247 -0.02346187 -5.54647e-4 0.9997241 -0.02348691 3.11828e-4 0.9997246 -0.02346891 -1.98556e-4 0.9997243 -0.02348244 0 -0.02347677 -0.9997244 0 -0.02347046 -0.9997246 1.79242e-4 -0.02347445 -0.9997245 3.28708e-5 -1.34089e-6 0 -1 -1.32219e-7 0 -1 -2.35551e-7 0 -1 0 0 -1 1.47828e-7 0 -1 -5.3738e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.02347201 -0.9997246 -7.15293e-5 -0.02346992 -0.9997246 8.36122e-6 -0.02347093 -0.9997246 0 0.9909554 -0.03889191 0.1284321 0.9357699 -0.04906654 0.3491809 0.9387567 -0.01817673 -0.3441012 0.9996684 -0.02284163 -0.01189422 0.9924557 -0.01918971 -0.121093 0.9997236 -0.02349197 0.001048386 0.9997265 -0.02336853 -9.85682e-4 0.9997275 -0.02331757 -0.001149594 0.9997231 -0.02352488 6.66247e-4 0.9997125 -0.02364391 0.00401926 0.9997228 -0.02329707 -0.003390491 0.9997243 -0.02348297 -2.11589e-4 0.9997248 -0.02345794 4.85777e-4 0.9997255 -0.02342814 3.57466e-5 0.9997242 -0.02348262 -4.73018e-4 0.9997232 -0.02342706 0.002181053 0.9997221 -0.02347588 -0.002143204 1 2.13428e-5 0 1 -5.51509e-5 0 1 3.57351e-5 0 1 -7.53813e-5 0 1 -1.15762e-4 0 1 9.94022e-5 0 1 1.21905e-4 0 1 1.32181e-4 0 1 -1.46784e-4 0 1 -1.60921e-4 0 1 1.53449e-4 0 -0.03281384 -0.9994615 -1.73705e-4 -0.03271895 -0.9994646 0 -0.03275859 -0.9994633 0 -0.03272259 -0.9994645 -5.18055e-5 -0.03271979 -0.9994646 4.08454e-7 -0.03263586 -0.9994673 3.57833e-4 -0.03272479 -0.9994645 3.55619e-5 -0.03272068 -0.9994646 -2.92355e-5 -0.03271907 -0.9994646 4.34153e-5 -0.03271949 -0.9994646 1.54926e-5 -0.03271585 -0.9994648 2.0995e-5 -0.03265726 -0.9994666 1.43026e-4 -0.03271776 -0.9994646 7.8546e-6 -0.03265559 -0.9994667 1.22966e-4 -0.03272104 -0.9994645 2.10379e-5 -0.03273761 -0.999464 -1.41558e-4 -0.0327208 -0.9994646 1.80691e-5 -0.032754 -0.9994635 1.8648e-4 -0.03270816 -0.999465 1.60518e-4 -0.03274303 -0.9994639 1.25909e-4 -0.03270816 -0.999465 5.98231e-5 -0.03271716 -0.9994647 5.69236e-5 -0.03277701 -0.9994627 2.75638e-4 -0.03268206 -0.9994658 2.0181e-4 -0.03276467 -0.9994631 -2.19745e-4 -0.0326839 -0.9994657 2.53004e-4 -0.03278928 -0.9994623 -3.629e-4 -0.03275007 -0.9994636 -1.84213e-5 -0.03274869 -0.9994636 -1.3363e-4 -0.03278809 -0.9994624 -2.19984e-4 -0.03271931 -0.9994646 -8.69441e-5 -0.03297638 -0.9994559 -8.62591e-4 -0.03266143 -0.9994665 2.75169e-4 -0.03288727 -0.9994591 8.25181e-5 -0.03272038 -0.9994646 0 -0.03253656 -0.9994706 -1.15369e-4 -0.03272116 -0.9994645 8.73678e-7 -0.0327332 -0.9994642 -4.81437e-5 -0.0327183 -0.9994646 -6.09887e-6 -0.03264349 -0.9994671 1.68548e-4 -0.03273439 -0.9994642 -2.46021e-5 -0.0327205 -0.9994646 -2.50835e-6 -0.03281259 -0.9994616 -2.0794e-4 -0.03283494 -0.9994608 4.34974e-4 -0.03271937 -0.9994646 0 -0.03266483 -0.9994664 -2.72936e-4 -0.03266966 -0.9994662 -2.41873e-4 -0.0327143 -0.9994648 -8.55634e-5 -0.03271758 -0.9994647 0 -0.03270548 -0.9994651 1.26184e-4 -0.03271245 -0.9994648 0 -0.03272086 -0.9994645 0 -0.03271847 -0.9994646 -2.07604e-5 -0.03272682 -0.9994644 0 -0.03271156 -0.9994649 -1.48617e-4 -0.0327354 -0.9994641 1.10997e-4 -0.03272002 -0.9994646 -2.07645e-5 -0.0327152 -0.9994648 -1.06739e-4 -0.03269433 -0.9994655 1.70363e-4 -0.03278136 -0.9994624 -5.52054e-4 -0.03274381 -0.9994638 -6.68359e-5 -0.03271847 -0.9994646 -3.45206e-6 -0.0327174 -0.9994647 0 -0.03271484 -0.9994648 -8.81449e-7 -0.03271889 -0.9994646 6.57361e-7 -1.55783e-5 0 -1 -2.14961e-5 0 -1 3.53757e-5 0 -1 -1.30239e-5 0 -1 -2.24257e-7 0 -1 0 0 -1 -1.30924e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.03272002 -0.9994646 0 -0.03271728 -0.9994646 7.12985e-6 -0.03271615 -0.9994647 -1.88945e-6 -0.03271883 -0.9994647 1.8802e-6 -0.03271895 -0.9994646 0 6.82784e-7 0 -1 0 -1 -4.11166e-6 1 7.52864e-6 0 1 -6.18871e-6 0 2.21676e-7 0 -1 3.77906e-7 0 -1 3.03328e-6 0 -1 3.95865e-6 0 -1 1.32383e-6 0 -1 -1.20034e-5 0 -1 -1.00664e-6 0 -1 8.15225e-6 0 -1 0 0 -1 1 0 -5.22944e-6 1 2.10722e-7 0 1 -3.02522e-6 0 0 0 -1 0 0 -1 -0.9867561 1.52597e-4 -0.1622111 -0.9840103 -2.74676e-4 -0.1781119 -0.9952557 -1.83114e-4 -0.09729456 -0.9446507 2.7467e-4 -0.3280779 -0.8631939 4.27263e-4 -0.5048726 -0.9362375 -3.9675e-4 -0.3513675 -0.84914 -3.05194e-4 -0.5281679 -0.7476097 3.05197e-4 -0.6641384 -0.6163676 1.83116e-4 -0.7874587 -0.6058096 -4.57791e-4 -0.7956096 0.4390769 -0.001068115 -0.8984489 0.2215392 -8.54539e-4 -0.9751511 0.2672235 8.85048e-4 -0.9636342 0.8113735 0.001159667 -0.5845271 0.7473501 -8.85052e-4 -0.6644299 0.6685547 8.2402e-4 -0.7436626 0.8707683 -0.001403868 -0.4916917 0.9302125 0.001403808 -0.3670189 0.9677741 -0.001312315 -0.2518166 0.9858481 6.40894e-4 -0.1676396 0.9926733 -9.46101e-4 -0.1208262 0.9963186 1.22075e-4 -0.08572745 0.6137777 -8.24027e-4 -0.7894785 0.4958757 9.76614e-4 -0.868393 0.06140351 6.40892e-4 -0.9981129 0.00814861 -6.71426e-4 -0.9999666 -0.1875692 -7.62973e-4 -0.9822511 -0.1047721 6.71421e-4 -0.9944961 -0.2675588 7.32453e-4 -0.9635413 -0.4078847 -8.2401e-4 -0.9130331 -0.4513472 4.57787e-4 -0.8923484 -0.7413471 -1.83116e-4 -0.6711219 -0.9963054 1.22078e-4 -0.08588153 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.01034259 0.9999465 -9.65219e-7 0.01024162 0.9999476 -9.35057e-6 -1.74027e-6 0 -1 -0.5992321 0.8005754 1.44487e-6 -0.5990303 0.8007264 -3.50127e-4 -0.5992057 0.8005951 0 -0.5991906 0.8006064 -2.51639e-5 -0.5992115 0.8005908 2.03032e-6 -0.5989364 0.8007966 7.40249e-7 -0.5989481 0.8007878 -5.62548e-4 -0.5993502 0.8004869 3.11432e-4 -0.59922 0.8005846 1.04396e-4 -0.5991393 0.8006449 -2.29366e-4 -0.5990617 0.8007029 -4.52007e-4 -0.599331 0.8005012 4.77663e-4 -0.5993646 0.8004758 6.77104e-4 -0.5992211 0.8005837 1.22995e-4 -0.5994184 0.8004352 0.001173853 -0.5989481 0.8007872 -0.001167893 -0.5993644 0.8004754 0.001306891 -0.5990203 0.8007331 -0.001091718 -0.5991982 0.8006008 -2.10596e-4 -0.599193 0.8006047 -1.50662e-4 -0.599198 0.8006007 6.79632e-4 -0.599199 0.8006002 -2.47656e-4 -0.5991302 0.8006516 4.92774e-4 -0.5992938 0.8005288 -8.90675e-4 -0.5993092 0.8005176 -4.56093e-4 -0.5991688 0.8006228 6.13458e-5 -0.59917 0.8006218 2.5478e-5 -0.5991049 0.8006705 1.43956e-4 -0.5991861 0.80061 5.91597e-5 -0.5993335 0.8004994 -5.37661e-5 -0.5991238 0.8006564 3.08088e-5 -0.5991562 0.8006322 2.75391e-5 -0.5993261 0.8005051 3.64646e-5 -0.5993446 0.8004912 3.56199e-5 -0.5988669 0.8008486 -1.56193e-4 -0.5990704 0.8006964 -2.49831e-5 -0.5998356 0.8001232 5.57002e-4 -0.5989541 0.8007834 -2.63791e-4 -0.5993098 0.8005173 1.5254e-4 -0.5990784 0.8006905 -1.19551e-4 -0.5990805 0.8006888 -1.67285e-4 -0.5992494 0.8005626 1.12938e-4 -0.5993466 0.8004897 2.53176e-4 -0.5991359 0.8006474 -1.10326e-4 -0.5988402 0.8008683 -6.86733e-4 -0.5994323 0.8004254 5.08835e-4 -0.5990149 0.8007379 -3.62961e-4 -0.599349 0.8004877 4.08378e-4 -0.5992387 0.8005704 1.15952e-4 -0.5990212 0.8007332 -4.41251e-4 -0.599255 0.8005583 1.92433e-4 -0.5991768 0.8006168 -4.44896e-5 -0.5990862 0.8006846 -2.96211e-4 -0.5994538 0.8004088 9.65213e-4 -0.5991895 0.8006073 -2.91247e-5 -0.5990902 0.8006817 2.42988e-4 -0.5991795 0.8006148 2.08725e-5 -0.5991999 0.8005995 -3.00697e-6 -1.0376e-5 -1 -3.0567e-4 -1.37465e-5 -0.9999998 -7.42942e-4 0 -1 4.3802e-4 0 -1 -3.18945e-4 0 -1 1.27698e-4 0 -1 -1.60321e-4 0 -1 2.14846e-4 -0.1335509 8.5453e-4 -0.9910416 -0.1323916 -1.52595e-4 -0.9911975 -0.1361468 0 -0.9906888 -0.1495133 4.27268e-4 -0.9887596 -0.1393787 -6.10373e-5 -0.9902392 -0.1480792 -1.52596e-4 -0.9889755 -0.154548 -2.80643e-4 -0.9879853 -0.1692055 -3.38035e-4 -0.9855808 -0.1684921 0.001191437 -0.9857023 -0.1549556 -0.001245558 -0.9879207 0 -1 0 0 -1 -3.82205e-5 0 -1 5.86992e-5 0 -1 -1.33028e-5 0 -1 6.06355e-6 0 -1 8.65464e-6 0 -1 -1.43143e-5 0 -1 1.7418e-5 0 -1 7.10392e-6 0 -1 1.3224e-5 0 -1 -3.97043e-6 0 -1 2.16213e-6 0 -1 -2.29181e-6 0 -1 -9.75304e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.16179e-7 0 -1 -1.05088e-5 0 -1 1.32542e-5 0 -1 -6.16217e-7 0 -1 -1.8487e-5 0 -1 1.37598e-5 0 -1 2.78979e-6 0 -1 -2.48781e-5 0 -1 2.59363e-5 0 -1 7.01131e-5 0 -1 -1.28337e-4 0 -1 -7.27484e-5 -0.5855373 -5.49342e-4 -0.8106453 -0.5769369 0.00100708 -0.8167881 -0.5088468 -0.001770079 -0.8608554 -0.5190027 0.001953184 -0.8547705 -0.4423095 0.003143429 -0.896857 -0.4186665 -0.001831114 -0.9081382 -0.3942117 0.003418087 -0.9190133 -0.378163 -0.00137335 -0.925738 -0.6450195 -7.32457e-4 -0.7641658 -0.6341573 0.001586973 -0.7732025 -0.6895111 0.00213629 -0.724272 -0.7084774 -0.002044796 -0.7057306 -0.7501562 0.002868771 -0.6612545 -0.7783749 -0.003418207 -0.6277906 -0.8046046 0.001403868 -0.5938094 -0.8148978 -0.003601253 -0.5795935 -0.8248636 8.54528e-4 -0.5653312 -0.9071792 0.005737543 -0.4207053 -0.9077431 -0.001983761 -0.4195218 -0.9080065 0.01797574 -0.4185705 -0.9076976 -0.06048876 -0.4152422 -0.9122603 -0.105323 -0.3958387 -0.9081959 -0.08948284 -0.4088682 -0.9079206 0.02752846 -0.4182373 -0.9085068 0.01165807 -0.4177075 -0.9063573 0.05148577 -0.4193634 -0.9077073 -0.02713167 -0.4187259 -0.9082714 -0.0142523 -0.4181388 -0.9058845 0.06045943 -0.4191874 -0.9080681 0.03616523 -0.4172584 -0.9162862 -0.1560155 -0.3688889 -0.9193682 -0.124733 -0.3731004 -0.9153981 -0.1775312 -0.3612883 -0.9176574 -0.2068605 -0.3392841 -0.9207 -0.2302971 -0.3150792 -0.9213802 -0.1781111 -0.3454489 -0.9236022 -0.207683 -0.3222216 -0.8904184 -0.4513434 -0.05868774 -0.8829087 -0.457141 -0.1072125 -0.8807284 -0.4668856 -0.07959455 -0.9430837 -0.2718984 -0.1914795 -0.9172819 -0.3329328 -0.2185167 -0.9949579 -0.07983833 -0.06070274 -0.9011338 -0.4146003 -0.1267453 -0.9014756 -0.3994045 -0.1667873 -0.9160085 -0.2565153 -0.3084288 -0.9162355 -0.2256255 -0.3310679 -0.906926 -0.3500502 -0.2344146 -0.9045822 -0.3535622 -0.23817 -0.9124589 -0.3075711 -0.2698495 -0.9138088 -0.2693938 -0.3039417 -0.8973352 -0.3979136 -0.1909301 -0.869916 -0.4820489 -0.1042837 -0.8692311 -0.4848356 -0.09680843 -0.8862648 -0.4359605 -0.1564391 -0.8329512 -0.5503161 -0.05783319 -0.8525609 -0.5222184 -0.02069216 -0.8306885 -0.556417 -0.01889103 -0.8919337 -0.4122275 -0.1858029 -0.8787047 -0.4666669 -0.1004992 -0.9042457 -0.4072142 -0.1285153 -0.8990154 -0.4119229 -0.1486303 -0.8567056 -0.5139745 -0.04342883 -0.8513945 -0.5242895 -0.0157479 -0.8596624 -0.5108595 -0.001831114 -0.8805322 -0.4699 -0.06210601 -0.8278709 -0.5607951 -0.0117805 -0.8540143 -0.5187016 -0.040102 -0.898835 -0.4057759 -0.1656551 -0.8855285 -0.4497835 -0.116337 -0.9179329 -0.3509734 -0.1849783 -0.9036775 -0.3897624 -0.1773478 -0.9209972 -0.2608139 -0.2893795 -0.9238435 -0.243054 -0.2956995 -0.9958699 -0.0616486 -0.06665378 -0.954539 -0.2104887 -0.2110685 -0.9248872 -0.2789158 -0.2584373 -0.9235268 -0.1532039 -0.3516061 -0.9257944 -0.1879056 -0.3280184 -0.924952 -0.1314776 -0.3566194 -0.9206632 -0.09741628 -0.3780069 -0.9685241 -0.1417307 -0.2046306 -0.929083 -0.2250454 -0.2935296 -0.9965828 -0.04464995 -0.06949281 -0.9094824 -0.3120012 -0.2747674 -0.9692049 -0.1015381 -0.2243481 -0.930384 -0.1727093 -0.3233531 -0.9340808 -0.1478061 -0.325033 -0.9126141 -0.1326362 -0.3867081 -0.9262251 -0.1153013 -0.358905 -0.929748 -0.1387419 -0.3410561 -0.9124665 -0.05020427 -0.4060595 -0.9157546 -0.07815927 -0.3940619 -0.9274525 -0.0886892 -0.3632718 -0.9261987 -0.1021479 -0.3629351 -0.9221565 -0.05624616 -0.3827059 -0.9264205 -0.07962542 -0.3679741 -0.9130229 -0.02752864 -0.4069783 -0.9213953 -0.02752798 -0.3876507 -0.9212135 -0.03985768 -0.3870103 -0.9180485 -0.01614463 -0.3961394 -0.9158833 -0.01904398 -0.4009927 -0.906472 6.83228e-4 -0.4222655 -0.9215198 -0.05414062 -0.3845388 -0.9120256 -0.004150509 -0.4101124 -0.921226 -0.07339894 -0.382041 -0.9151962 -0.05920636 -0.3986359 -0.9233077 -0.06753975 -0.378076 -0.9964745 -0.0456258 -0.07040721 -0.9271363 -0.1282408 -0.3520975 -0.9190051 -0.2981456 -0.2579513 -0.9657901 -0.1321495 -0.2231281 -0.92591 -0.1159409 -0.3595115 -0.9151304 -0.3126733 -0.254503 -0.9084833 -0.3596639 -0.212838 -0.9653366 -0.1713624 -0.196876 -0.9964703 -0.05740588 -0.06125128 -0.9175526 -0.2811101 -0.2812017 -0.9546492 -0.2310934 -0.1877253 -0.9953505 -0.07672506 -0.05823045 -0.9118516 -0.3307667 -0.2431461 -0.9482743 -0.2775452 -0.1540934 -0.9948238 -0.09054946 -0.04611402 -0.9025581 -0.3796036 -0.2031999 -0.8916418 -0.4246408 -0.15702 -0.8500785 -0.5246841 -0.04553443 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.5858151 -0.8051868 -0.09216785 -0.4730188 -0.8774912 -0.07913655 -0.4393907 -0.8883951 -0.1330044 -0.6031852 -0.7974717 -0.01437461 -0.7166807 -0.6973621 -0.007416129 -0.7280284 -0.6855461 0.001220703 -0.8227618 -0.568386 7.32456e-4 -0.8645572 -0.5025345 6.10391e-5 -0.8627229 -0.5056763 7.62985e-4 -0.4668793 -0.8841958 -0.01489323 -0.3873776 -0.921521 -0.02716189 -0.3825905 -0.922966 -0.04193353 -0.8657777 -0.5004286 -3.66234e-4 -0.8250165 -0.5648737 -0.01629704 -0.7282797 -0.6839353 -0.04290997 -0.6109629 -0.7893168 -0.06085515 -0.7159478 -0.6953778 -0.06219792 -0.3973572 -0.9176448 -0.005951166 -0.8619551 -0.5069553 -0.005462944 -0.8634194 -0.5044828 -0.002044737 -0.8320116 -0.5539826 -0.02932882 -0.8625148 -0.5059236 -0.01046818 -0.864031 -0.5032628 -0.01330637 -0.8732179 -0.4870269 -0.01718235 -0.878799 -0.4770754 -0.01055961 -0.8782879 -0.4779646 -0.01266551 -0.4001326 -0.9142836 -0.06308245 -0.372147 -0.9168173 -0.144751 -0.4079127 -0.9088159 -0.08752757 -0.4000777 -0.9094144 -0.1135929 -0.3648599 -0.9182993 -0.1536348 -0.3809146 -0.9093303 -0.1673998 -0.4716427 -0.8817893 0.001037597 -0.6119393 -0.7909036 0.00137335 -0.3935103 -0.9193199 7.93491e-4 -0.7295005 -0.6736199 -0.1185976 -0.7717354 -0.6133415 -0.1680379 -0.8328423 -0.5366522 -0.1355669 -0.6278814 -0.6996332 -0.3409964 -0.6467326 -0.6161524 -0.449548 -0.7112744 -0.6276525 -0.3164508 -0.7611806 -0.417839 -0.4959988 -0.7855681 -0.4236696 -0.4509844 -0.7522929 -0.4503686 -0.4808571 -0.4514425 -0.5668362 -0.6891273 -0.3898493 -0.5187005 -0.760899 -0.4877361 -0.4707061 -0.7352207 -0.3439485 -0.4197576 -0.8399423 -0.3167616 -0.5231037 -0.7912173 -0.3427333 -0.3094977 -0.8869865 -0.2555073 -0.3429144 -0.90395 -0.2869432 -0.4396622 -0.851094 -0.2268183 -0.4370954 -0.8703454 0.01947087 -0.04528963 -0.9987841 -0.03604257 -0.07174944 -0.9967713 0.04355031 -0.1392574 -0.9892981 -0.1184764 -0.6370014 -0.7617037 -0.1142936 -0.7092308 -0.6956499 -0.04468071 -0.6449715 -0.7628994 -0.1897974 -0.6333292 -0.7502474 -0.17222 -0.695228 -0.6978527 -0.2438209 -0.6386528 -0.7298454 -0.2286818 -0.6800026 -0.6966357 -0.176949 -0.5061572 -0.8440937 -0.2550163 -0.5278862 -0.8101254 -0.1705695 -0.3449844 -0.9229799 -0.2140032 -0.2454383 -0.945496 -0.1467989 -0.1074898 -0.9833088 -0.04156637 0.009643852 -0.9990893 0.08331668 -0.1189933 -0.9893933 -0.1637033 -0.5695133 -0.8055159 -0.2389056 -0.5768771 -0.7811127 -0.04751855 -0.7286789 -0.6832051 -0.1330948 -0.7777242 -0.6143542 -0.1534198 -0.4366987 -0.8864291 -0.1220157 -0.8601832 -0.4951738 -0.01785403 -0.8282751 -0.5600371 -0.07913678 -0.8027519 -0.5910388 0.0139169 -0.7535276 -0.657269 -0.1462478 -0.9364804 -0.3187726 -0.1818938 -0.909988 -0.3726077 -0.204205 -0.9371275 -0.283006 -0.1781429 -0.9496175 -0.2578601 -0.1858334 -0.947021 -0.2619491 -0.1517432 -0.9484565 -0.2782164 -0.1577229 -0.9600407 -0.2311825 -0.1588827 -0.9586676 -0.2360351 -0.1646518 -0.9543394 -0.2492513 -0.1927262 -0.9419016 -0.2750964 -0.2218465 -0.8728282 -0.4346897 -0.1627606 -0.8411183 -0.5157801 -0.408228 -0.3338827 -0.8496307 -0.4150659 -0.4316686 -0.8008636 -0.4573621 -0.3720912 -0.8076931 -0.5970789 -0.5547182 -0.5794693 -0.524348 -0.546688 -0.6528334 -0.5962035 -0.4509294 -0.664232 -0.6621219 -0.5057702 -0.5529839 -0.7598723 -0.5380877 -0.364768 -0.6971423 -0.673246 -0.2464398 -0.6807906 -0.7103941 -0.1785064 -0.6155214 -0.7658309 -0.1861091 -0.5896948 -0.7917023 -0.1595857 -0.517516 -0.8309798 -0.2040826 -0.4457597 -0.8759548 -0.1843954 -0.4215957 -0.8826225 -0.207929 -0.3856151 -0.9017015 -0.195539 -0.3871704 -0.903011 -0.1861994 -0.8694506 -0.4676704 -0.1591861 -0.9008089 -0.4341987 -0.003845393 -0.828382 -0.5209929 -0.2057908 -0.8851409 -0.460897 -0.06402873 -0.6416935 -0.7287337 -0.2391167 -0.385978 -0.8980008 -0.2112243 -0.8579191 -0.4591886 -0.2304793 -0.4600772 -0.8447108 -0.2734827 -0.5517627 -0.7853593 -0.2806577 -0.3974228 -0.8817342 -0.2541651 -0.3680955 -0.8985546 -0.2389675 -0.8541986 -0.4293119 -0.2933189 -0.8416697 -0.4308453 -0.3255221 -0.01489329 -0.9767336 -0.2139389 -0.6637923 -0.3578679 -0.6567423 -0.7101564 -0.3713908 -0.5981196 -0.6858272 -0.4001981 -0.6078507 -0.8880811 -0.3378181 -0.3117547 -0.4920342 -0.7895681 -0.3667215 -0.3863381 -0.8690243 -0.3090949 -0.1552528 -0.9632576 -0.2191607 -0.002044796 -0.9837029 -0.17979 -0.817164 -0.4096654 -0.4054842 -0.5809966 -0.7057292 -0.4054494 -0.4109413 -0.843002 -0.3470951 -0.2018858 -0.9503439 -0.2368306 -0.7052037 -0.5412248 -0.4579994 -0.3895488 -0.8589362 -0.3323861 -0.7387206 -0.3924482 -0.5479748 -0.3840804 -0.856513 -0.3447721 -0.5670452 -0.6741978 -0.4731989 -0.4333119 -0.7973452 -0.4200971 -0.4924536 -0.7293721 -0.4748747 -0.3709276 -0.8594754 -0.3517312 -0.3579302 -0.8645199 -0.3528335 -0.5630139 -0.1222285 -0.817359 -0.5123922 -0.2988471 -0.8050743 -0.5612826 -0.2482755 -0.7895069 -0.6034801 -0.343612 -0.7195433 -0.5447651 -0.6411443 -0.540523 -0.3843575 -0.8335682 -0.3967788 -0.3320182 -0.8771519 -0.3469421 -0.1632146 -0.9704981 -0.1774668 -0.535309 -0.2839823 -0.7954863 -0.4973507 -0.6295015 -0.5969674 -0.4683771 -0.2575204 -0.8451663 -0.4374562 -0.7102637 -0.5515049 -0.3967223 -0.7799855 -0.4839774 -0.187297 -0.9682862 -0.1653536 -0.2624946 -0.9291535 -0.2603278 -0.545623 -0.384695 -0.7445169 -0.3606166 -0.819414 -0.4455519 -0.2570345 -0.9334365 -0.2502592 -0.2842593 -0.9140307 -0.2893866 -0.3965334 -0.2463493 -0.8843491 -0.4327936 -0.6412706 -0.6336103 -0.3086676 -0.2240083 -0.9244159 -0.3497808 -0.1526876 -0.9243052 -0.400532 -0.5971053 -0.6950104 -0.3731286 -0.7421981 -0.556702 -0.3858253 -0.6787193 -0.6248832 -0.349906 -0.7993362 -0.4884951 -0.3508524 -0.8266212 -0.4399999 -0.2555087 -0.9486052 -0.1867179 -0.3409244 -0.8222044 -0.4557968 -0.2762913 -0.163614 -0.9470447 -0.3487483 -0.6108819 -0.7107728 -0.3307951 -0.7469518 -0.5767475 -0.3349173 -0.82475 -0.4556512 -0.04446631 -0.03119051 -0.9985239 -0.326314 -0.6912961 -0.6446929 -0.3293918 -0.830026 -0.4500641 -0.3102635 -0.8178675 -0.4845921 -0.3255486 -0.8344568 -0.4446346 -0.2922554 -0.6139316 -0.7332631 -0.3240537 -0.832749 -0.448908 -0.2887688 -0.7294602 -0.6200809 -0.3207833 -0.8285858 -0.4588504 -0.2179378 -0.1408157 -0.9657506 -0.1441131 -0.2265158 -0.9632872 -0.2710394 -0.6874103 -0.6737988 -0.2762292 -0.7779645 -0.5643303 -0.3162119 -0.8260391 -0.4665507 -0.3104392 -0.8266071 -0.4694127 -0.08597242 -0.1735318 -0.9810686 -0.2299051 -0.7411715 -0.6307206 -0.3051915 -0.8319522 -0.4633723 -0.06509649 -0.2783922 -0.9582589 -0.09341865 -0.3614061 -0.9277169 -0.3020179 -0.8379043 -0.4546444 -0.008759081 -0.1871147 -0.9822991 -0.2981732 -0.8519147 -0.4305047 -0.05597198 -0.416738 -0.9073018 -0.0881083 -0.4924237 -0.8658844 -0.2659463 -0.8395591 -0.4737226 0.02124118 -0.3190756 -0.9474912 0.01437455 -0.24037 -0.970575 -0.2960067 -0.8521602 -0.4315125 -0.07980823 -0.5646091 -0.821491 -0.2400638 -0.8033256 -0.5450114 0.06857675 -0.2375314 -0.9689562 -0.1798798 -0.7595909 -0.625032 -0.2831605 -0.8478638 -0.4482712 -0.01825058 -0.4886762 -0.8722743 0.04345965 -0.4027652 -0.9142711 -0.2732049 -0.8504692 -0.4495124 -0.1975826 -0.8093442 -0.5531032 -0.2678386 -0.8583897 -0.4375267 0.08832252 -0.3369624 -0.9373663 -0.01898258 -0.5607194 -0.8277883 0.0491659 -0.4891263 -0.8708262 -0.2660979 -0.8708075 -0.413384 0.09238022 -0.428178 -0.8989603 -0.2656731 -0.8787201 -0.3965715 0.05334764 -0.5780957 -0.8142232 0.08917582 -0.5256553 -0.8460108 0.03524982 -0.6672142 -0.7440314 -0.2536441 -0.8784919 -0.4048662 -0.240521 -0.8827344 -0.4036456 0.08820009 -0.624298 -0.7761913 -0.2344215 -0.8915097 -0.3876302 0.06726408 -0.6978189 -0.713109 -0.2339611 -0.8997095 -0.3684902 -0.2365861 -0.907707 -0.3465474 0.04828214 -0.7680279 -0.6385939 -0.2335023 -0.909075 -0.3450499 -0.2186108 -0.9117379 -0.347769 2.44156e-4 -0.8539669 -0.5203274 -0.2075279 -0.9170907 -0.340407 -0.06494551 -0.896633 -0.4379856 -0.2025269 -0.9241591 -0.3239028 -0.204205 -0.9317559 -0.3002189 -0.06476253 -0.9195247 -0.3876599 0.05279713 -0.02496415 -0.9982932 0.05142432 -0.03595125 -0.9980297 0.04983735 -0.06796556 -0.9964421 0.05182045 -0.01086455 -0.9985973 0.05096006 0.023795 -0.9984172 0.05085891 0.02265799 -0.9984489 0.05055385 0.02057355 -0.9985094 0.05009657 0.01856815 -0.9985718 0.05031061 0.01941901 -0.9985448 0.0495519 0.01686871 -0.9986292 0.05014687 0.02165675 -0.998507 0.0479685 0.004591822 -0.9988384 0.04727917 5.72148e-4 -0.9988816 0.04977548 0.01743412 -0.9986084 0.05025708 0.01913994 -0.9985529 0.05033832 0.01949059 -0.9985421 0.05061334 0.02090913 -0.9984995 0.05066186 0.02119499 -0.998491 0.05115044 0.01759928 -0.9985359 0.05404603 0.05028045 -0.9972717 0.05717867 0.01116007 -0.9983017 0.05139368 -0.0708037 -0.9961655 0.04715228 -0.06277817 -0.996913 0.04901367 -0.03308272 -0.9982501 0.04574781 -0.07162791 -0.9963818 0.04196375 -0.1084649 -0.9932143 0.03891134 -0.1254318 -0.9913389 0.04416054 -0.08175963 -0.9956732 0.04577845 -0.07367283 -0.9962313 0.0453822 -0.07458919 -0.9961811 0.04486334 -0.07690864 -0.9960283 0.03664016 -0.1916856 -0.9807723 0.03636509 -0.1818845 -0.9826473 0.03479838 -0.1904079 -0.9810882 0.04739576 -0.03808748 -0.9981498 0.003692865 -0.4738782 -0.8805827 0.03105288 -0.2236483 -0.9741752 0.04752826 -0.03689432 -0.9981883 0.05389738 -0.02252334 -0.9982925 0.04852485 -0.02481174 -0.9985138 0.04226833 -0.05713087 -0.9974716 0.0479182 -0.02144843 -0.998621 0.04892188 -0.01611399 -0.9986727 0.04611986 -0.02089232 -0.9987175 0.04645168 -0.0210027 -0.9986997 0.04671275 -0.0175994 -0.9987533 0.05127978 0.02230715 -0.9984352 0.05459904 -0.008697986 -0.9984706 0.04611486 -0.02084475 -0.9987186 0.04660218 -0.01760929 -0.9987584 0.04761034 -0.0152902 -0.998749 0.04631489 -0.02257603 -0.9986718 0.05120635 0.0210132 -0.998467 0.05221438 0.02392119 -0.9983494 0.04375833 -0.03934925 -0.998267 0.05128675 0.02317166 -0.9984151 0.05179011 0.01535087 -0.9985401 0.05163878 0.004455804 -0.9986559 0.05383515 0.003234982 -0.9985446 0.05517905 0.002716183 -0.9984728 0.05131393 0.02178847 -0.9984449 0.051364 0.02164703 -0.9984455 0.05220133 0.02442908 -0.9983378 0.05224668 0.02546578 -0.9983096 0.05212289 0.009219944 -0.9985982 0.05276691 0.01367241 -0.9985133 0.05511695 0.01724308 -0.9983311 0.05560523 0.0134893 -0.9983618 0.05344164 0.02312189 -0.9983033 0.05091083 0.02311229 -0.9984358 0.05229133 0.02365869 -0.9983516 0.05076414 0.02191329 -0.9984703 0.05097275 0.02388936 -0.9984143 0.05133956 0.01220035 -0.9986068 0.05158936 0.02036321 -0.9984608 0.05710089 0.01132249 -0.9983043 0.0524078 0.02375596 -0.9983432 0.05658328 0.01902294 -0.9982167 0.05361735 0.02478551 -0.998254 0.05393821 0.01539522 -0.9984257 0.05512136 0.02503108 -0.9981659 0.5284723 -0.8388841 -0.1303479 0.5325009 -0.843981 -0.06433469 0.5359176 -0.8441313 -0.01532059 0.1087094 -0.1666654 -0.9800025 0.08322626 -0.1226878 -0.9889495 0.1640106 -0.2525776 -0.9535749 0.0939083 -0.1434108 -0.9851978 0.2260837 -0.352035 -0.9082717 0.1678262 -0.2608494 -0.9506798 0.2745192 -0.4306549 -0.8597533 0.2853838 -0.4456089 -0.8485216 0.3456255 -0.5413426 -0.7664799 0.3600988 -0.5665323 -0.741195 0.3912246 -0.6149602 -0.6846659 0.424615 -0.6693187 -0.6096841 0.4254325 -0.6693084 -0.6091253 0.4551637 -0.7169576 -0.5280131 0.473415 -0.7474781 -0.4659988 0.4825348 -0.7613253 -0.4330636 0.5040282 -0.7957328 -0.3358052 0.5117729 -0.810218 -0.2857187 0.5234085 -0.8297932 -0.1936153 0.5165635 -0.8166258 -0.2574578 0.5250471 -0.8328301 -0.17527 0.5338444 -0.8449892 -0.03167903 0.5339881 -0.8454921 4.04291e-5 0.5339949 -0.8454877 2.97585e-5 0 2.75268e-7 -1 0 2.74223e-6 -1 0 2.63452e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 7.66231e-7 2.10457e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -5.65696e-7 -5.21083e-5 -1 1.10704e-6 -2.62956e-7 -1 -1.57764e-6 9.85964e-5 -1 -3.54456e-6 -1.24162e-4 -1 -1.28049e-6 -2.09146e-6 -1 -1.29668e-6 -2.64281e-6 -1 -5.90777e-6 -1.1812e-4 -1 -0.0392667 -0.9992287 -4.75972e-4 -0.03934949 -0.999225 0.001101553 -0.03964251 -0.999214 1.03498e-4 -0.03963559 -0.9992132 -0.001435101 -0.04000204 -0.9991995 5.59078e-4 -0.03989601 -0.999203 -0.001295924 -0.03900092 -0.9992383 0.001389861 -0.04012954 -0.9991938 -0.001255095 -0.03854453 -0.9992552 0.001866638 -0.0393573 -0.9992252 -2.00761e-5 -0.0398702 -0.9992046 -8.08605e-4 -0.0401417 -0.9991939 4.16232e-4 -0.03942465 -0.9992226 6.52027e-5 -0.03817933 -0.9992706 -8.0318e-4 -0.03884321 -0.9992452 -4.84072e-4 -0.04021418 -0.9991909 6.32918e-4 -0.03921312 -0.9992309 -2.36018e-4 -0.04008632 -0.9991961 5.86792e-4 -0.04001742 -0.9991989 5.7403e-4 -0.03908818 -0.9992356 -5.00977e-4 -0.03978979 -0.9992079 5.18237e-4 -0.0398364 -0.999206 7.90893e-4 -0.0389297 -0.9992416 -9.5393e-4 -0.03952467 -0.9992187 8.06021e-5 -0.03963428 -0.9992142 4.75454e-4 -0.0392751 -0.9992283 -6.54423e-4 -0.03949743 -0.9992198 7.93047e-5 -0.03966009 -0.999213 7.56607e-4 -0.03937727 -0.9992244 -3.60194e-4 -0.03922224 -0.99923 -0.001073598 -0.03941136 -0.9992231 -2.5857e-4 -0.04057776 -0.9991604 0.005647957 -0.03802156 -0.9992468 -0.007759451 -0.03945815 -0.9992213 9.58816e-5 -0.03875166 -0.9992409 -0.004005193 -0.039388 -0.999224 4.43675e-5 -0.03977763 -0.9992086 3.58131e-4 -0.0389834 -0.9992394 0.001040279 -0.03942829 -0.9992225 5.22613e-5 -0.03972601 -0.9992105 -5.84096e-4 -0.03925806 -0.999229 4.13778e-4 -0.03956282 -0.9992171 -2.43495e-4 -0.03954577 -0.9992178 -1.24689e-4 -0.04007905 -0.9991958 -0.001237928 -0.03911334 -0.9992346 6.77137e-4 -0.03944599 -0.9992218 0 -0.03945922 -0.9992213 0 -0.03969204 -0.9992104 0.001813113 -0.03953462 -0.999218 6.82601e-4 -0.03918606 -0.9992299 -0.002063035 -0.03950589 -0.9992192 6.1101e-4 -0.03932893 -0.9992258 -0.001098215 -0.03918671 -0.9992277 -0.002931237 -0.03969937 -0.9992087 0.002433955 -0.03937548 -0.9992241 -9.47507e-4 -0.03955125 -0.9992168 0.001253724 -0.03948384 -0.9992201 5.43735e-4 -0.03946089 -0.9992212 1.92541e-4 -0.03939437 -0.9992228 -0.001350164 -0.0394985 -0.9992193 8.38098e-4 -0.03942114 -0.9992218 -0.001373827 -0.03950411 -0.9992184 0.001458644 -0.03947532 -0.9992195 0.001421511 -0.03945004 -0.9992209 -0.001143276 0.672802 -0.7398226 -3.99996e-6 0.6721654 -0.7404009 -5.40087e-4 0.6736047 -0.7390916 5.9988e-4 0.6737142 -0.7389919 4.10551e-4 0.6740754 -0.7386624 6.5104e-4 0.6679033 -0.7442461 -0.001758575 0.6919642 -0.7219105 0.005553841 0.6735451 -0.7391459 6.62634e-4 0.6809238 -0.732347 0.003258466 0.6819337 -0.7314054 0.003567814 0.6668364 -0.7452034 -0.001023054 0.6755234 -0.7373379 0.001064479 0.6695261 -0.742788 -0.00102365 0.6736342 -0.7390649 3.00026e-4 0.6716778 -0.7408433 -4.84472e-4 0.6713156 -0.7411712 -9.42344e-4 0.671791 -0.7407406 -5.22016e-4 0.6728203 -0.739806 0 0.6728721 -0.7397589 4.10726e-5 0.672704 -0.7399117 -9.35129e-5 0.6719051 -0.7406371 -6.46942e-4 0.672916 -0.7397189 1.23058e-4 0.6724372 -0.7401542 -3.10946e-4 0.6734501 -0.7392325 6.33284e-4 0.6727749 -0.7398473 -2.27191e-5 0.6723738 -0.7402118 2.56403e-4 0.6728039 -0.7398208 -7.68551e-6 0.673296 -0.7393731 -2.58727e-4 0.6727262 -0.7398915 3.87914e-5 0.6725991 -0.7400071 1.0072e-4 0.67271 -0.7399064 3.01255e-5 0.6733148 -0.7393559 -1.80714e-4 0.6724585 -0.7401349 1.06993e-4 0.6728496 -0.7397793 -1.57389e-5 0.6727854 -0.7398378 2.39734e-6 0.672837 -0.7397907 -9.48644e-6 0.6727619 -0.7398591 2.79057e-6 0.6728078 -0.7398173 -2.0462e-6 -0.02727252 -0.9996281 7.9473e-5 -0.02729433 -0.9996275 9.70345e-7 -0.02726531 -0.9996283 -9.22433e-5 -0.02727121 -0.9996281 8.13715e-5 -0.02727037 -0.9996282 2.23825e-5 -0.02727556 -0.999628 4.19677e-5 -0.02723687 -0.9996291 -1.98175e-4 -0.02728241 -0.9996278 4.41123e-5 -0.02722519 -0.9996293 -3.01184e-4 -0.02730512 -0.9996272 1.91024e-4 -0.02732133 -0.9996268 1.87694e-4 -0.02727216 -0.9996281 5.39989e-5 -0.02731233 -0.9996269 1.98593e-4 -0.02720481 -0.9996299 -3.18506e-4 -0.027233 -0.9996292 -8.38457e-5 -0.02726167 -0.9996284 -1.58344e-4 -0.02708476 -0.999633 -4.91462e-4 -0.02731031 -0.9996271 1.10542e-4 -0.02744942 -0.9996232 3.90173e-4 -0.02731627 -0.9996269 -1.92551e-5 -0.02730101 -0.9996273 -8.00156e-6 -0.02728974 -0.9996277 1.45332e-6 -0.0272957 -0.9996275 2.10855e-6 -0.02729725 -0.9996274 2.93107e-6 -0.02730989 -0.9996271 -1.0413e-5 -0.02729409 -0.9996275 4.21252e-6 -0.02725654 -0.9996286 -1.21307e-4 -0.02730047 -0.9996274 -6.36371e-6 -0.02728933 -0.9996277 3.23295e-5 -0.02726894 -0.9996283 -8.84744e-5 -0.02735531 -0.9996258 2.34841e-4 -0.02730876 -0.9996271 0 -0.02730011 -0.9996274 0 -0.02721583 -0.9996296 -3.07605e-4 -0.02727895 -0.9996278 3.29837e-4 -0.02728784 -0.9996277 1.40122e-4 -0.02727758 -0.9996279 3.44082e-4 -0.02732664 -0.9996265 -4.00583e-4 -0.02730482 -0.9996272 -6.84017e-5 -0.02729874 -0.9996274 -4.90383e-5 -0.02729409 -0.9996275 1.63971e-4 -0.02730095 -0.9996273 -8.78962e-5 -0.02729505 -0.9996275 8.17825e-5 -0.0273025 -0.9996272 -8.08901e-5 -0.02729725 -0.9996274 8.33146e-5 -0.02730184 -0.9996272 -7.55814e-5 -0.0272991 -0.9996274 2.08003e-5 -0.02730214 -0.9996272 -1.08626e-4 -0.02729976 -0.9996273 -3.55621e-5 -0.02730005 -0.9996273 -1.05468e-4 -0.02730059 -0.9996274 0 -0.02730059 -0.9996274 0 -0.02728754 -0.9996277 0 -0.0273053 -0.9996272 2.11006e-6 -0.02730321 -0.9996273 0 -0.02730387 -0.9996272 3.16435e-6 -0.02729028 -0.9996276 1.24225e-5 -0.02728372 -0.9996278 1.67433e-5 -0.0273084 -0.9996271 -2.44675e-5 -0.02729833 -0.9996274 4.11141e-6 -0.02728933 -0.9996277 3.71321e-5 -0.02730613 -0.9996272 -2.37355e-5 -0.02729898 -0.9996274 -3.53581e-7 -0.02730029 -0.9996274 -7.71767e-6 -0.02728289 -0.9996278 1.58076e-6 -0.02731227 -0.999627 1.92007e-6 -0.027318 -0.9996269 -3.85272e-6 -0.02741932 -0.9996241 -2.14829e-5 -0.02734899 -0.9996261 -1.1574e-5 -0.02719831 -0.9996302 2.6978e-5 -0.02727347 -0.999628 -3.51289e-5 -0.02719771 -0.9996301 5.17983e-5 -0.02735596 -0.9996259 -3.30564e-5 -0.02732902 -0.9996265 -3.39178e-5 -0.02739304 -0.9996248 -6.3036e-5 -0.02716833 -0.9996309 5.09846e-5 -0.02726829 -0.9996282 3.12267e-5 -0.02734047 -0.9996262 -4.83419e-5 -0.02727556 -0.999628 0 4.32131e-6 1.68297e-4 -1 -2.51607e-5 5.04556e-5 -1 0.4558986 -0.8900318 -7.75752e-5 0.4559288 -0.8900164 -1.2873e-4 0.4559941 -0.8899826 -6.59952e-4 0.4557133 -0.8901267 0 0.4559373 -0.890012 -6.48744e-5 0.9235814 0.3833792 -0.004230082 0.9114749 0.411342 -0.0033921 0.9848749 0.1730393 0.008877277 0.8906645 0.4546611 3.32174e-4 0.8543274 0.5197309 0.002129197 0.8945629 0.4469423 2.08089e-5 0.8942581 0.4475519 3.0157e-5 0.892285 0.4514724 3.38849e-4 0.8979946 0.4400058 -7.89344e-4 0.892687 0.4506771 4.96028e-4 0.8944052 0.4472578 2.41075e-5 0.8945735 0.4469209 -3.26848e-6 0.8956571 0.4447452 -4.0621e-4 0.8945855 0.446897 -3.068e-5 0.8943515 0.4473652 5.23602e-6 0.895671 0.4447172 3.679e-4 0.8945996 0.4468689 0 0.8930994 0.4498587 -7.59922e-4 0.8946018 0.4468645 -4.13396e-5 0.8944124 0.4472433 -6.71214e-6 0.8944548 0.4471583 7.08246e-6 0.8939339 0.4481983 -8.62612e-4 0.8952278 0.4456084 7.43193e-4 0.8947808 0.4465047 9.30343e-4 0.8944185 0.4472309 -6.09439e-6 0.8944243 0.4472196 1.7215e-5 0.8943091 0.4474486 -0.001123189 0.04602324 -0.9961836 -0.07416212 0.04217773 -0.985592 -0.1637973 0.04559606 -0.9963689 -0.07190382 -0.1940716 -0.6542708 -0.730935 -0.1608362 -0.5077483 -0.846359 -0.1654123 -0.4533274 -0.8758614 -0.1774375 -0.4904404 -0.8532199 -0.1858636 -0.5742241 -0.7973214 -0.1922388 -0.6688836 -0.7180801 -0.1797282 -0.6835106 -0.7074682 -0.1327282 -0.5176066 -0.8452613 -0.1592774 -0.747466 -0.6449228 -0.1754566 -0.7671688 -0.6169823 -0.08404934 -0.2900221 -0.9533221 -0.107396 -0.3820354 -0.9178862 -0.1260445 -0.4387449 -0.889728 -0.1417014 -0.4643216 -0.8742576 -0.05169916 -0.4755774 -0.8781535 -0.08997082 -0.715891 -0.692391 -0.03671509 -0.6015421 -0.797997 -0.1438363 -0.4168902 -0.8975042 -0.1903485 -0.6122159 -0.7674368 -0.1877825 -0.5599297 -0.8069798 -0.1105701 -0.6187409 -0.7777751 -0.06540352 -0.3373944 -0.9390887 -0.06827169 -0.2605739 -0.9630371 -0.04321455 -0.2055134 -0.9776998 -0.1919073 -0.7660422 -0.6134747 0.001678526 -0.1327292 -0.991151 -0.004425287 -0.04269641 -0.9990784 -0.006042659 -0.08044725 -0.9967406 -0.003967463 -0.008270621 -0.9999579 0.009613394 -0.2111906 -0.9773976 -0.1364216 -0.8136464 -0.5651271 -0.1514052 -0.8433342 -0.5156201 0.01074254 -0.2922776 -0.9562731 0.02243173 -0.3461204 -0.9379219 -0.1668812 -0.8214046 -0.5453853 0.01934939 -0.4471421 -0.8942537 -0.02130234 -0.7172918 -0.6964473 -0.1032471 -0.9331918 -0.3442283 -0.1087092 -0.8719628 -0.4773501 -0.138131 -0.8692245 -0.4747301 0.02710127 -0.5223715 -0.8522872 0.02932876 -0.5950292 -0.8031688 -0.08023554 -0.9551663 -0.2849904 -0.09335863 -0.947595 -0.3055291 -0.006286919 -0.8159016 -0.5781567 0.03936976 -0.6449323 -0.7632249 -0.04330593 -0.8737789 -0.4843917 0.01059007 -0.8939921 -0.4479574 0.03927797 -0.7178381 -0.6951013 -0.0760852 -0.9192485 -0.3862553 -0.06061142 -0.9675856 -0.245162 -0.0445584 -0.9765927 -0.2104318 0.04648071 -0.7740283 -0.6314426 0.04812812 -0.8309358 -0.5542828 -0.04245173 -0.9555769 -0.291669 -0.009186208 -0.9910733 -0.1330017 -0.01013225 -0.9807843 -0.1948323 -0.02505594 -0.9851799 -0.169685 0.02636808 -0.9510228 -0.3079944 0.04168874 -0.9975702 -0.05581897 0.04190212 -0.9974731 -0.05737513 0.03146499 -0.9922011 -0.1206108 0.04190272 -0.9981587 -0.04385596 0.04165887 -0.9980129 -0.04727441 0.06427371 -0.9308397 -0.3597313 0.0575596 -0.906244 -0.4188182 0.04220843 -0.9973765 -0.058811 0.04455804 -0.9970934 -0.06180137 0.04474133 -0.9969151 -0.06448739 0.044954 -0.9967406 -0.06698852 0.04648071 -0.9960245 -0.07599276 0.04947209 -0.9953932 -0.08212792 0.05548292 -0.9933829 -0.100559 0.04699945 -0.9958707 -0.07767122 0.06201547 -0.9830614 -0.1724653 0.0733996 -0.9743987 -0.2125079 0.06714236 -0.9570538 -0.2820286 0.06445538 -0.9865458 -0.1502433 0.06256335 -0.9881659 -0.1400504 0.04596221 -0.9613919 0.2713176 0.0687586 -0.9831601 -0.1693177 0.02960336 -0.8751913 0.4828705 0.04526031 -0.9965509 -0.06955379 0.04443544 -0.9972653 -0.05905401 0.04437518 -0.9974355 -0.05615568 0.04355126 -0.9972239 -0.06039804 0.04266524 -0.9972935 -0.05987787 0.04156637 -0.9976844 -0.05383485 0.04153639 -0.997789 -0.05188232 0.05581915 -0.8654265 -0.497917 0.04156684 -0.9979103 -0.04947125 0.01303148 -0.9955532 -0.09329587 0.03302162 -0.9983099 -0.04782336 0.02285903 -0.9951469 -0.0957089 0.04199409 -0.9982143 -0.04248237 0.04217702 -0.9982717 -0.04092574 0.04297089 -0.9984946 -0.03408986 0.03698867 -0.998512 -0.04007107 0.03720283 -0.998557 -0.03872883 0.03683614 -0.9984527 -0.0416581 0.03662335 -0.9982926 -0.04550451 0.03668403 -0.9982821 -0.04568719 0.03824073 -0.9987147 -0.03326606 0.04510736 -0.9988633 -0.01541215 0.04513788 -0.9988625 -0.01538163 0.04065084 -0.9989063 -0.02310258 0.04736566 -0.9988001 -0.01245176 0.0371415 -0.998152 -0.04809778 0.03897291 -0.9980673 -0.04840332 0.006348013 -0.9695693 -0.2447347 -0.01849478 -0.9300504 -0.3669661 -0.06735557 -0.8017361 -0.5938707 -0.1899209 -0.6990727 -0.6893675 0.0486468 -0.7522866 -0.6570376 0.05255454 -0.7978715 -0.6005324 0.05447655 -0.8191322 -0.571012 0.01800632 -0.2993629 -0.9539694 0.02169907 -0.3484976 -0.9370585 0.02743661 -0.4497289 -0.8927436 0.04251259 -0.5796123 -0.8137828 0.03769123 -0.5903638 -0.8062568 0.0663495 -0.7408013 -0.6684394 0.05725353 -0.638792 -0.7672463 0.05609428 -0.6553088 -0.7532755 0.04608434 -0.5375999 -0.8419398 0.04498541 -0.5518194 -0.8327495 0.04376393 -0.565819 -0.8233674 0.03338778 -0.44512 -0.8948484 0.05151581 -0.7030022 -0.7093195 0.06109946 -0.7914857 -0.6081262 0.05307328 -0.6874201 -0.7243182 0.03329581 -0.431198 -0.9016429 0.05466032 -0.6715198 -0.7389678 0.06488454 -0.7582274 -0.6487538 0.08121138 -0.872237 -0.482294 0.07712334 -0.8057819 -0.5871691 0.07641983 -0.8132734 -0.5768418 0.08017474 -0.8948016 -0.4392063 0.0778234 -0.9097101 -0.4078863 0.08267682 -0.9231485 -0.3754487 0.07400882 -0.8266708 -0.5577976 0.05649054 -0.8470537 -0.5284968 0.06070184 -0.8998463 -0.4319629 0.08624649 -0.9120278 -0.4009577 0.08301162 -0.8827008 -0.4625458 0.08465963 -0.9036366 -0.4198496 0.05987799 -0.8973771 -0.437183 0.06421232 -0.9558303 -0.2868193 0.06485223 -0.9416548 -0.3302735 0.06732505 -0.9731919 -0.2199203 0.06558549 -0.9758781 -0.2082316 0.06863808 -0.983884 -0.1651098 0.04681676 -0.7147951 -0.6977652 0.04101806 -0.6258614 -0.7788552 0.04590106 -0.6935824 -0.7189134 0.03634804 -0.5363094 -0.8432384 0.02835232 -0.4420095 -0.8965622 0.03811812 -0.3922292 -0.9190775 0.04577904 -0.4782389 -0.8770358 0.03903442 -0.395655 -0.9175693 0.01382529 -0.2586219 -0.9658797 0.008148491 -0.1481385 -0.9889331 0.008820116 -0.1893426 -0.9818715 0.00540179 -0.07458776 -0.9971998 0.003112852 -0.07437378 -0.9972256 0.06308251 -0.7751187 -0.6286586 0.003295958 -0.1045873 -0.9945104 0.0360127 -0.4110335 -0.9109086 0.03378456 -0.4203086 -0.9067521 -0.002288937 -0.06540268 -0.9978564 0.06027507 -0.6259458 -0.7775339 0.0463584 -0.5239205 -0.8505048 0.006164789 -0.06711119 -0.9977265 0.01178038 -0.1387705 -0.9902545 0.01495414 -0.1304675 -0.9913399 0.02227878 -0.2195224 -0.9753531 0.02624601 -0.262735 -0.964511 0.02893167 -0.3019517 -0.9528842 0.01501548 -0.1458519 -0.9891926 0.006286799 -0.06302112 -0.9979925 0.00213629 -0.02291959 -0.9997351 0.009186267 -0.06235092 -0.9980121 0.005737543 -0.07074266 -0.9974782 0.005523979 -0.07391774 -0.9972491 0.05911499 -0.8073152 -0.5871522 0.06503605 -0.8893557 -0.452567 0.06933999 -0.9477794 -0.3112977 0.0708965 -0.9690206 -0.2365862 0.005462884 -0.06888169 -0.9976099 0.005218744 -0.06802707 -0.9976698 0.02221775 -0.2898994 -0.9567993 0.06747829 -0.874899 -0.4795815 0.07223874 -0.9362049 -0.3439506 0.07391685 -0.9594846 -0.2718931 0.00564599 -0.06933933 -0.9975772 0.005859673 -0.06924813 -0.9975823 0.02420163 -0.2772355 -0.9604972 0.06988811 -0.8596242 -0.5061244 0.07709038 -0.9486453 -0.3068051 0.07510852 -0.9235207 -0.3761225 0.005615472 -0.06433421 -0.9979127 0.07104843 -0.7432007 -0.6652855 0.06906408 -0.7275078 -0.6826146 0.07214689 -0.8435451 -0.5321903 0.08002138 -0.9365434 -0.3412964 0.06497615 -0.6851036 -0.725542 0.005829036 -0.0650047 -0.997868 0.05075424 -0.5126698 -0.8570845 0.05929827 -0.6242953 -0.7789347 0.05227923 -0.5527932 -0.8316771 0.2871271 -0.6973088 -0.6567485 0.2378662 -0.7817481 -0.5764458 0.2433306 -0.7871852 -0.566683 0.1866241 -0.8531302 -0.487176 0.1331868 -0.915095 -0.380608 0.1887324 -0.8569258 -0.479644 0.2320085 -0.7762 -0.5862472 0.2799558 -0.6908098 -0.6666383 0.1817754 -0.8482038 -0.4975019 0.2727196 -0.684729 -0.6758479 0.2278542 -0.7722811 -0.5930131 0.1309891 -0.9101487 -0.3930284 0.1772546 -0.8422648 -0.5090883 0.2206817 -0.767671 -0.6016485 0.2591711 -0.6739916 -0.6917844 0.212842 -0.7602984 -0.6137139 0.1290657 -0.9063898 -0.4022431 0.1711539 -0.8377938 -0.5184671 0.2494993 -0.6655451 -0.7034201 0.2083577 -0.754568 -0.6222653 0.1689842 -0.8328356 -0.5270953 0.1269592 -0.9024177 -0.4117325 0.2403398 -0.6583634 -0.7132983 0.1989837 -0.7475011 -0.6337569 0.1622726 -0.8274166 -0.5376331 0.1246087 -0.8983852 -0.421161 0.1219859 -0.8938209 -0.4315134 0.1586107 -0.8222305 -0.5466074 0.1933077 -0.7410638 -0.643006 0.2247133 -0.6503961 -0.7255955 0.2643616 -0.6798262 -0.6840684 0.2155302 -0.6436608 -0.7343348 0.1837273 -0.7360386 -0.6515302 0.1520761 -0.8154677 -0.5584672 0.1176809 -0.8872765 -0.4459729 0.2070763 -0.6369467 -0.7425755 0.1757593 -0.7295281 -0.6609821 0.1472268 -0.8113957 -0.5656514 0.1177426 -0.881025 -0.4581831 0.190836 -0.6260384 -0.7560803 0.1640435 -0.7219135 -0.6722579 0.1393485 -0.8081055 -0.5723178 0.1362057 -0.8038672 -0.5790041 0.1155147 -0.877149 -0.466118 0.181131 -0.6188364 -0.7643516 0.1572976 -0.7160488 -0.6800968 0.1614792 -0.6084388 -0.7769985 0.1441723 -0.7094474 -0.6898541 0.127631 -0.7992352 -0.5873103 0.1111829 -0.8748142 -0.471528 0.1232684 -0.7968044 -0.5915299 0.1075205 -0.8718224 -0.4778756 0.1348007 -0.7036373 -0.6976556 0.1486907 -0.6010804 -0.7852347 0.1366634 -0.5947514 -0.7922084 0.1239708 -0.6988693 -0.7044239 0.1152408 -0.7933791 -0.59772 0.1068779 -0.7893155 -0.604614 0.10105 -0.8689202 -0.4845272 0.1143248 -0.6948302 -0.7100288 0.1246099 -0.588868 -0.7985655 0.1025126 -0.6919524 -0.7146279 0.1048943 -0.580627 -0.8073844 0.09619599 -0.7862927 -0.6103198 0.09329724 -0.8670509 -0.4894061 0.09689784 -0.6891803 -0.7180818 0.08322572 -0.5721732 -0.8158991 0.08545398 -0.6870502 -0.7215675 0.08493518 -0.7845899 -0.6141701 0.07745867 -0.6851949 -0.7242295 0.04318445 -0.6782556 -0.7335562 0.06866776 -0.5662196 -0.8213892 0.2038666 -0.8452529 -0.4939492 0.09500581 -0.7743294 -0.6256101 -0.9954559 -0.09381419 0.01632744 -0.8195525 -0.1084639 -0.562645 -0.04504638 -0.08105915 -0.9956908 0.257645 -0.1177134 -0.9590426 -0.7165071 -0.2178179 -0.6627012 -0.6894294 -0.2215391 -0.689643 -0.4820595 -0.3449953 -0.8053551 0.1190249 -0.26863 -0.9558615 0.05145484 -0.4414867 -0.8957913 -0.6742267 -0.3231051 -0.6640944 -0.1456065 -0.4057819 -0.902297 -0.6574888 -0.4236763 -0.6230624 0.01019334 -0.5682041 -0.8228246 -0.02224832 -0.5658225 -0.8242269 -0.6244622 -0.5266162 -0.576821 -0.007629811 -0.707071 -0.7071015 -0.5743824 -0.6302946 -0.5223156 -0.09409099 -0.8148656 -0.5719624 -0.5413092 -0.7160285 -0.4407808 -0.5041723 -0.7887306 -0.3517304 -0.8232006 -0.5340595 -0.1926692 0.1348049 -0.9197068 -0.3687372 0.1928815 -0.8618021 -0.4691416 0.2480887 -0.793127 -0.5562388 0.2948469 -0.7038969 -0.6462155 0.1367253 -0.92314 -0.3593312 0.1969432 -0.8688943 -0.4541323 0.3036367 -0.7109781 -0.6342831 0.255265 -0.7987256 -0.5448645 0.1413937 -0.9293291 -0.341109 0.2006337 -0.8744076 -0.4417664 0.2594152 -0.8044006 -0.5344563 0.3116947 -0.7187931 -0.6214362 0.204236 -0.8774945 -0.4339252 0.3172808 -0.7247774 -0.6115806 0.2675291 -0.8140013 -0.5155871 0.2060932 -0.8811377 -0.4255841 0.1417304 -0.9328146 -0.3313148 0.143319 -0.9358465 -0.321949 0.2114047 -0.8865448 -0.4115174 0.2735098 -0.8200107 -0.5027673 0.3338221 -0.7382052 -0.5861877 0.2795222 -0.8255046 -0.4903159 0.2114964 -0.8907569 -0.4022704 0.1441733 -0.938897 -0.3125485 0.1467345 -0.9416586 -0.3028994 0.216017 -0.8944348 -0.3915651 0.2832153 -0.8317008 -0.4775596 0.3476125 -0.7502205 -0.5624365 0.1475008 -0.9440909 -0.2948491 0.218092 -0.8995913 -0.3783801 0.2896564 -0.837809 -0.4627909 0.1517717 -0.9490239 -0.2762594 0.2229742 -0.906119 -0.3594872 0.2948129 -0.842994 -0.4499406 0.3589376 -0.7609381 -0.5404971 0.2986891 -0.8468403 -0.4400529 0.3664489 -0.7665 -0.52744 0.1523492 -0.951267 -0.2681065 0.2244373 -0.9108114 -0.3464831 0.3015645 -0.8509181 -0.4301132 0.3723315 -0.7743274 -0.5116506 0.227767 -0.9151272 -0.3326625 0.1522901 -0.9546972 -0.2556582 0.3061659 -0.8558425 -0.4168887 0.1554329 -0.9582638 -0.2399398 0.2321629 -0.9201979 -0.3151764 0.3110537 -0.860586 -0.4032833 0.3128485 -0.8649645 -0.3923805 0.1550052 -0.9605499 -0.2309055 0.2334097 -0.9233847 -0.3047633 0.1549161 -0.9634647 -0.2184878 0.2360679 -0.9277607 -0.2890192 0.3186501 -0.8700694 -0.376087 0.3210338 -0.8737099 -0.36547 0.238236 -0.9311227 -0.2761414 0.1567173 -0.9677714 -0.197125 0.2408896 -0.9333442 -0.2661597 0.3263451 -0.8798773 -0.3454198 0.3302186 -0.8840522 -0.330768 0.2439676 -0.9405907 -0.2361547 0.33507 -0.8882299 -0.3142864 0.2448849 -0.9440458 -0.2209274 0.1555861 -0.9770367 -0.1455758 0.3377882 -0.8923249 -0.2994254 0.1558905 -0.9811823 -0.113927 0.1574155 -0.9794677 -0.1259507 0.07886165 -0.9913258 -0.1051387 0.1568392 -0.9713412 -0.1785995 0.2426585 -0.9371545 -0.2507156 0.1555868 -0.9741116 -0.1640101 0.2472345 -0.9473713 -0.2033787 0.2483933 -0.9496262 -0.1910788 0.1513453 -0.9846143 -0.08734625 0.07687807 -0.9929757 -0.0899403 0.2485503 -0.9535799 -0.1700237 0.1558932 -0.9844649 -0.08078485 0.104039 -0.9935135 -0.04590046 0.255936 -0.9522981 -0.1662088 0.3527724 -0.9043168 -0.2403393 0.3506704 -0.9027704 -0.2490706 0.3491764 -0.909122 -0.2270973 0.2614878 -0.9517997 -0.1603169 0.1590337 -0.984477 -0.0742523 0.1074872 -0.993479 -0.03802639 0.2651494 -0.9521634 -0.1519237 0.2610331 -0.9541917 -0.1462188 0.3531041 -0.9281418 -0.1177725 0.2582519 -0.9565576 -0.1352908 0.3310159 -0.9360066 -0.1196674 0.1136233 -0.9465258 -0.301958 0.108649 -0.993467 -0.03491413 0.1598267 -0.9847794 -0.06830096 0.2902705 -0.95062 -0.1098395 0.1622709 -0.9843986 -0.06802737 0.2688162 -0.9626784 -0.03143513 0.1088599 -0.9934725 -0.03408926 0.1579989 -0.9857154 -0.05832254 -0.05450677 -0.9329637 -0.3558202 0.2385988 -0.9707839 -0.02548348 0.106573 -0.9936437 -0.03625679 0.1982506 -0.9799003 -0.02218723 0.1111519 -0.9931034 -0.03729474 0.2184865 -0.9667547 0.1328498 0.117162 -0.9927795 -0.02572739 0.1547005 -0.9869214 0.04532057 0.1036715 -0.9944163 -0.01971495 0.1324545 -0.9905403 0.03586035 0.08682543 -0.9961883 -0.008392572 0.09744632 -0.9951243 0.0152288 0.07230019 -0.9973399 -0.00927782 0.01049864 -0.07495576 -0.9971316 0.05310279 -0.9025951 -0.4272029 0.03930878 -0.2927711 -0.9553743 0.03924739 -0.07495462 -0.9964144 0.05319488 -0.4351421 -0.8987891 0.08423244 -0.9000054 -0.4276627 0.03067171 -0.1543657 -0.9875376 0.08691966 -0.9002965 -0.4265108 0.0515778 -0.08307385 -0.9952078 0.04403948 -0.1619971 -0.9858081 0.05157715 -0.2992696 -0.9527736 0.06479251 -0.4408822 -0.8952234 0.06521874 -0.08987796 -0.9938152 0.06189233 -0.305128 -0.950298 0.0875591 -0.9005556 -0.425832 0.05496549 -0.1678265 -0.9842831 0.077977 -0.4448506 -0.8922038 0.07663357 -0.09668463 -0.9923605 0.07464885 -0.3127257 -0.9469056 0.06726467 -0.173289 -0.9825713 0.08856576 -0.1041304 -0.9906125 0.08893233 -0.9002191 -0.4262589 0.07745778 -0.1786595 -0.9808574 0.08768033 -0.4488086 -0.889316 0.08707106 -0.3204509 -0.9432549 0.09592097 -0.5766859 -0.8113154 0.09033834 -0.9001178 -0.4261772 0.1025441 -0.1126459 -0.9883298 0.09817969 -0.4543673 -0.8853875 0.09381669 -0.1896782 -0.977354 0.09802788 -0.3254879 -0.940451 0.1151491 -0.118964 -0.9861989 0.1100208 -0.4601646 -0.8809903 0.09274804 -0.9008985 -0.4240043 0.1232653 -0.1232653 -0.9846885 0.1097475 -0.2006036 -0.9735059 0.1121872 -0.3313735 -0.9368062 0.1166446 -0.5851761 -0.8024731 0.1336721 -0.1327565 -0.9820935 0.1214057 -0.4658158 -0.8765138 0.09280914 -0.9017232 -0.4222344 0.1264397 -0.2074368 -0.9700428 0.1275386 -0.3403168 -0.9316214 0.1471028 -0.1381607 -0.9794245 0.1321498 -0.4717717 -0.8717613 0.1559509 -0.1423395 -0.9774553 0.137185 -0.2154675 -0.9668267 0.1374891 -0.347431 -0.9275713 0.09445649 -0.901625 -0.4220788 0.1646826 -0.1529021 -0.9744232 0.1468582 -0.4800664 -0.864852 0.1565942 -0.2278566 -0.9610201 0.1525342 -0.35219 -0.9234152 0.09662371 -0.9026047 -0.4194861 0.1806427 -0.1586995 -0.970661 0.1878758 -0.1665124 -0.9679754 0.1679483 -0.2356709 -0.957211 0.1629425 -0.3582355 -0.9193025 0.1591262 -0.4883046 -0.8580428 0.09650105 -0.9034537 -0.4176829 0.1759117 -0.3660148 -0.9138317 0.1858011 -0.2448559 -0.95159 0.1714279 -0.49408 -0.8523483 0.2086602 -0.1784461 -0.9615706 0.09900498 -0.9044733 -0.4148809 0.1888193 -0.3751361 -0.9075352 0.2169923 -0.1836957 -0.9587337 0.2023696 -0.2557773 -0.9453172 0.177899 -0.4975007 -0.8490259 0.1731343 -0.6140731 -0.7700253 0.09869849 -0.9053468 -0.4130445 0.1891909 -0.5029628 -0.8433477 0.2028902 -0.384997 -0.9003405 0.2299894 -0.1959915 -0.9532536 0.2182754 -0.2643904 -0.9393901 0.1020552 -0.9071745 -0.4081904 0.2018545 -0.5101298 -0.8360757 0.2441827 -0.2059118 -0.9476155 0.2170829 -0.3943994 -0.8929302 0.2368572 -0.2748228 -0.9318644 0.2581659 -0.2128747 -0.9423559 0.2169888 -0.5196133 -0.8263885 0.2325905 -0.4023715 -0.8854371 0.09131371 -0.9097495 -0.404991 0.2680824 -0.2169318 -0.9386546 0.08624631 -0.9129109 -0.3989427 0.2010923 -0.6319958 -0.7484273 0.2510186 -0.283857 -0.9254269 0.2791919 -0.226027 -0.9332543 0.2433582 -0.4081912 -0.8798618 0.2280973 -0.5275477 -0.8183307 0.2640239 -0.2917355 -0.9193377 0.0843867 -0.9159849 -0.392238 0.291396 -0.2342643 -0.9274743 0.2549915 -0.4160436 -0.8728615 0.2392123 -0.5336344 -0.8111793 0.2784894 -0.3015926 -0.9118583 0.3058953 -0.240004 -0.9213176 0.2655206 -0.4236122 -0.8660551 0.09158831 -0.9200645 -0.380911 0.1210373 -0.8911169 -0.4373337 0.312698 -0.2476314 -0.9170053 0.2885907 -0.3085808 -0.9063627 0.2500432 -0.5403716 -0.8034158 0.2766237 -0.4315683 -0.8586199 0.08859801 -0.9229702 -0.3745351 0.3046154 -0.3161823 -0.8984644 0.3314383 -0.2591689 -0.9071826 0.2617639 -0.5498356 -0.7931964 0.2891378 -0.4387118 -0.8508416 0.2329545 -0.6543968 -0.7193726 0.3332073 -0.2628608 -0.9054706 0.09302198 -0.9254285 -0.367327 0.3204239 -0.3277791 -0.8887573 0.345998 -0.2698827 -0.8985816 0.2957638 -0.4430506 -0.8463038 0.2731143 -0.5592906 -0.7826895 0.09469962 -0.9292651 -0.3570693 0.3080612 -0.4503419 -0.8380278 0.3542388 -0.2745526 -0.893944 0.3381586 -0.3404476 -0.8773508 0.2845593 -0.5668602 -0.7731077 0.09601294 -0.932937 -0.3470016 0.3672385 -0.2815404 -0.8864937 0.3204506 -0.4590684 -0.8285938 0.2962846 -0.5734944 -0.7637537 0.3703838 -0.288073 -0.8830798 0.3501456 -0.3482535 -0.8695502 0.09717369 -0.9360602 -0.3381548 0.3331809 -0.4682905 -0.8183487 0.3020246 -0.5780463 -0.7580525 0.365525 -0.3569797 -0.8596261 0.3881106 -0.2975302 -0.8722648 0.09964501 -0.9391661 -0.3286914 0.3994723 -0.3024502 -0.8654166 0.313557 -0.5861265 -0.7470862 0.3489261 -0.478938 -0.8055241 0.381157 -0.3667518 -0.8486534 0.099186 -0.940711 -0.3243841 0.4153673 -0.3128225 -0.8541734 0.3240228 -0.5950031 -0.7355138 0.3613744 -0.4860442 -0.7957196 0.3968174 -0.3757588 -0.8374612 0.1027572 -0.9427604 -0.3172443 0.3698043 -0.4939269 -0.7869442 0.425504 -0.3230498 -0.8453314 0.3322886 -0.6013728 -0.7265914 0.4127163 -0.3859811 -0.8250358 0.1032162 -0.9451523 -0.309893 0.4425932 -0.3303121 -0.8336697 0.3456605 -0.6102314 -0.712837 0.3850613 -0.5041475 -0.7730221 0.4485741 -0.3347368 -0.8286933 0.1048339 -0.9474422 -0.3022635 0.1372434 -0.9256378 -0.3526457 0.4278522 -0.3961731 -0.8123974 0.396717 -0.5115601 -0.7621824 0.3565886 -0.6203371 -0.6985889 0.458338 -0.3448064 -0.8191671 0.106083 -0.9498949 -0.2940173 0.4431413 -0.4078609 -0.7982952 0.4718554 -0.3513051 -0.8086639 0.4080693 -0.5190973 -0.751011 0.3674234 -0.6290971 -0.6850087 0.4790881 -0.3518847 -0.8041466 0.106939 -0.952227 -0.2860557 0.4820174 -0.3557296 -0.800697 0.4579069 -0.4187205 -0.7842159 0.4196656 -0.526665 -0.7392597 0.3274971 -0.7300704 -0.5997857 0.1076716 -0.9542428 -0.2789757 0.3781949 -0.6378836 -0.6708749 0.4892265 -0.3638831 -0.7926201 0.4297785 -0.5344917 -0.7277425 0.4713118 -0.4269365 -0.7717452 0.5023112 -0.3686382 -0.7821698 0.3882684 -0.644235 -0.6589454 0.1089241 -0.9562371 -0.2715625 0.4394169 -0.5421144 -0.7162575 0.5166056 -0.37179 -0.7712918 0.4838907 -0.4357916 -0.7589042 0.3962023 -0.6504896 -0.647987 0.1106027 -0.9594115 -0.2594159 0.5661048 -0.3852466 -0.7287733 0.3422761 -0.745103 -0.5724236 0.4494644 -0.5506985 -0.7033583 0.4964045 -0.4502281 -0.7422111 0.5650064 -0.4013918 -0.7208693 0.4088324 -0.6606447 -0.6296068 0.4584949 -0.5465132 -0.7007894 0.5338743 -0.4027023 -0.7435114 0.1097458 -0.9619241 -0.2503157 -0.05896329 -0.3607992 -0.9307779 0.147619 -0.9465072 -0.2869369 0.3553965 -0.7578842 -0.5470878 0.5245996 -0.4299281 -0.7348178 0.4712428 -0.560175 -0.6812741 0.4191839 -0.6705111 -0.6121274 0.6072052 -0.4964824 -0.6203284 0.1099295 -0.9651026 -0.237682 0.5845754 -0.5014396 -0.6378324 0.4726296 -0.5655014 -0.6758915 0.4798826 -0.5701887 -0.6667817 0.5763841 -0.5232504 -0.6276867 0.4858751 -0.5845761 -0.6497663 0.1079779 -0.9678035 -0.2273702 0.4284862 -0.6781618 -0.597073 0.5513651 -0.5366243 -0.638773 0.1064508 -0.9688614 -0.2235528 0.08286076 -0.5277758 -0.8453325 0.5238341 -0.5428477 -0.6564407 0.4365158 -0.6819511 -0.5868533 0.108771 -0.9718287 -0.2090883 0.4420374 -0.6883258 -0.5751613 0.3798368 -0.7821965 -0.493855 0.5223079 -0.5718104 -0.6326354 0.5670509 -0.6243665 -0.5372335 0.451838 -0.6848222 -0.5717177 0.1041005 -0.9746569 -0.1980077 0.4543002 -0.69143 -0.5617259 0.3863703 -0.7873592 -0.4803993 0.5672847 -0.641293 -0.516654 0.4583084 -0.7005097 -0.5470281 0.5590865 -0.6536664 -0.5100417 0.1046208 -0.9778441 -0.1813162 0.3928759 -0.792344 -0.4667328 0.1568984 -0.965043 -0.2099405 0.4638366 -0.7113503 -0.5280497 0.5543888 -0.6653886 -0.4999113 0.5321838 -0.6690599 -0.5187862 0.3985542 -0.7974441 -0.4530315 0.469414 -0.7212269 -0.509394 0.09756869 -0.9794713 -0.1763988 0.5271241 -0.6830762 -0.5055167 0.4021847 -0.8025992 -0.4405475 0.09961307 -0.9812684 -0.1648926 0.5127867 -0.7101556 -0.4824199 0.06793564 -0.650516 -0.7564481 0.09506589 -0.9837109 -0.1525632 0.408104 -0.8062282 -0.4283077 0.5317701 -0.7489461 -0.3953484 0.4141219 -0.8048352 -0.4251395 0.09125071 -0.9846837 -0.1485646 0.4169899 -0.8110291 -0.4103062 0.5296987 -0.7621058 -0.372309 0.0924738 -0.986418 -0.1357503 0.4200379 -0.8172779 -0.3944932 0.51755 -0.771686 -0.3696524 0.08710002 -0.9891992 -0.1178933 0.1571728 -0.9782561 -0.1353212 0.4215619 -0.8230727 -0.3805746 0.5096626 -0.7821948 -0.3583508 0.4235083 -0.8307195 -0.3613111 0.3417888 -0.8956581 -0.2845646 0.4989591 -0.7926458 -0.3503609 0.4253436 -0.838907 -0.3395852 0.3426394 -0.9009582 -0.2662193 0.4828141 -0.8051277 -0.3444705 0.09039729 -0.9937599 -0.06534117 0.2601465 -0.8412036 -0.4740258 0.3452968 -0.9014523 -0.2610632 0.4620411 -0.82651 -0.3215579 0.4709778 -0.8504275 -0.2344207 0.1048929 -0.9935991 -0.04193276 0.3542383 -0.9001079 -0.253616 0.4540084 -0.8603757 -0.2315821 0.1056861 -0.9935355 -0.04144436 0.106571 -0.9934725 -0.0406813 0.4381651 -0.8725152 -0.2161679 0.1072123 -0.9934455 -0.03964382 0.4164637 -0.8827652 -0.2174486 0.01977652 -0.8288751 -0.559084 0.3812772 -0.901997 -0.2025564 0.1075505 -0.9934999 -0.03729474 0.3712317 -0.9213958 -0.1149646 0.1080996 -0.9934664 -0.03659272 0.1084645 -0.9934545 -0.0358293 0.109258 -0.9934546 -0.03332674 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.55145e-6 9.11844e-6 -1 -1.09005e-5 -4.10502e-5 -1 2.21887e-6 -4.90192e-5 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1.20266e-5 -6.07319e-5 -1 5.75656e-7 3.64301e-6 -1 2.09519e-5 -3.24376e-4 -1 -2.55767e-4 0.001698553 -0.9999986 2.86304e-4 -0.003547668 -0.9999937 4.70767e-5 -6.14048e-4 -0.9999998 1.09559e-5 -3.0173e-5 -1 -3.3354e-5 4.4354e-4 -1 -2.05766e-5 2.6916e-4 -1 1.77638e-5 -1.71422e-4 -1 -9.16259e-6 1.3438e-4 -1 1.64196e-5 -1.53134e-4 -1 1.1496e-5 -1.46301e-4 -1 -1.29069e-5 1.29067e-4 -1 3.12516e-7 9.84998e-6 -1 -4.54818e-6 7.2799e-5 -1 0 3.11034e-5 -1 -3.52878e-6 6.1857e-5 -1 9.71908e-6 -4.52638e-5 -1 3.21247e-6 4.09676e-6 -1 -8.65156e-6 6.05445e-5 -1 5.17597e-6 -1.738e-5 -1 4.86633e-6 -6.45534e-6 -1 -3.00207e-6 3.12419e-5 -1 1.93431e-5 -6.85487e-5 -1 1.22991e-5 -3.94698e-5 -1 5.16213e-6 -8.10924e-5 -1 0 0 -1 0 0 -1 0 5.77538e-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 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 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 -2.35775e-6 0 1 3.8748e-5 0 1 7.76033e-6 0 1 -1.90422e-5 0 1 7.43453e-6 0 1 2.17782e-5 0 1 2.17068e-5 0 1 1.77851e-5 0 1 7.69769e-6 0 1 7.57869e-6 0 1 -8.97135e-6 0 1 -4.32199e-6 0 1 8.45564e-6 0 1 8.84244e-6 0 1 -4.847e-6 0 1 4.52547e-6 0 1 8.08912e-6 0 1 -1.91549e-5 0 1 7.61698e-6 0 1 1.89771e-5 0 1 -3.49832e-5 0 1 6.10905e-5 0 1 -1.01866e-4 0 1 -9.42547e-5 0 1 7.33174e-6 0 1 2.91733e-5 0 1 -2.94218e-5 0 1 2.13933e-5 0 1 1.65438e-5 0 1 -4.30039e-6 0 1 2.2704e-6 0 1 -9.27098e-6 0 1 -4.13023e-5 0 1 -4.67713e-6 0 1 7.92659e-6 0 1 -8.95487e-6 0 1 -3.55921e-5 0 1 -7.09047e-6 0 1 -7.27359e-5 0 1 1.08539e-5 0 1 7.48272e-6 0 1 -4.079e-6 0 1 6.98415e-5 0 1 1.92138e-5 0 1 6.31459e-6 0 1 1.31284e-5 0 1 -1.65034e-4 0 1 -7.76438e-5 0 1 8.29222e-5 0 1 8.92324e-5 0 1 -8.67665e-5 0 1 -1.75424e-4 0 1 -7.55187e-5 0 1 2.03074e-5 0 1 3.78497e-5 0 1 9.71958e-6 0 1 -1.02457e-4 0 1 8.02871e-5 0 1 2.14542e-5 0 1 3.41798e-6 0 1 9.46718e-6 0 1 -9.03152e-6 0 1 -8.97696e-6 0 1 -3.55496e-5 0 1 -1.3394e-5 0 1 -8.97278e-6 0 1 3.6049e-5 0 1 -9.11135e-6 0 1 6.17089e-5 0 1 7.98577e-6 0 1 1.69297e-4 0 1 2.11408e-5 0 1 -8.99311e-5 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.262256 -0.9649971 -0.001583755 0.009442865 -0.9999445 -0.004680812 0.0120114 -0.9999229 -0.003139793 -0.06527215 -0.9978676 0 -0.05273658 -0.9986079 0.00112915 -0.05777198 -0.9983296 7.01931e-4 -0.07324659 -0.9973139 -4.27272e-4 0.02213871 -0.9997509 -0.002857267 0.002520203 -0.9999965 8.03555e-4 0.001173734 -0.9999993 -3.93309e-4 0.005118489 -0.9999869 0 0.006981134 -0.9999651 -0.004592835 -2.81955e-4 -0.9999989 -0.001507937 7.19478e-4 -0.9999988 -0.001472055 -0.009530961 -0.9999541 0.001043915 -0.007361829 -0.9999724 0.001080691 -0.02337765 -0.9997174 0.004333674 -0.01486259 -0.9998866 0.002441465 -0.0119329 -0.9999267 0.002105772 -0.02047902 -0.999785 0.003245294 -0.03184193 -0.9994788 0.005303263 -0.03278088 -0.9994465 0.005680203 -0.04534596 -0.9989681 0.002572596 -0.03738611 -0.9992941 0.003723323 -0.07104748 -0.997473 3.66224e-4 -0.07013219 -0.9975377 3.66226e-4 -0.08589774 -0.9963038 -5.91154e-4 -0.08433616 -0.9964372 -5.75112e-4 -0.08514922 -0.9963681 -5.1883e-4 -0.1023316 -0.9947503 -3.96753e-4 -0.1065123 -0.9943091 -0.002194106 -0.1377331 -0.9904694 3.05192e-5 -0.1194507 -0.9928387 -0.001739561 -0.1312526 -0.9913476 -0.001676261 -0.1670016 -0.9859564 6.71424e-4 -0.1472553 -0.9890981 -9.46096e-4 -0.1616103 -0.9868546 -5.01824e-4 -0.1910778 -0.9815741 0.001281738 -0.1750892 -0.9845526 0 -0.1993195 -0.9799344 6.1038e-4 -0.2144866 -0.9767259 0.001434385 -0.2212002 -0.9752283 6.71414e-4 -0.2361536 -0.9717152 0.00112915 -0.2466266 -0.9691105 -3.96751e-4 -0.2459521 -0.9692816 9.76606e-4 -0.3678098 -0.929901 2.1363e-4 -0.3628085 -0.9318636 -3.96745e-4 -0.3261901 -0.9453042 2.13635e-4 -0.4046257 -0.9144822 -5.79868e-4 -0.4132027 -0.9106391 3.66233e-4 -0.4539151 -0.8910446 -7.01946e-4 -0.5055229 -0.8628131 -6.40907e-4 -0.4647423 -0.8854458 4.57784e-4 -0.5216005 -0.8531896 6.71418e-4 -0.5497391 -0.8353362 -6.71419e-4 -0.6605266 -0.7508023 7.62979e-4 -0.7361637 -0.6768029 9.15588e-4 -0.7157361 -0.6983708 -5.79865e-4 -0.7601714 -0.6497226 -3.05192e-5 -0.7485128 -0.6631202 -6.71421e-4 -0.8087356 -0.5881713 0.001220762 -0.8081827 -0.5889317 -4.88309e-4 -0.7924595 -0.6099246 -9.15574e-5 -0.7766169 -0.6299731 4.27266e-4 -0.8717811 -0.4898943 0.001190245 -0.8374983 -0.54644 4.27264e-4 -0.8230987 -0.5678985 -1.22076e-4 -0.8517642 -0.5239254 9.1558e-5 -0.918495 -0.3954326 -2.7467e-4 -0.9097111 -0.4152418 9.15571e-5 -0.9211982 -0.389092 0.001159727 -0.9590451 -0.2832516 -0.001037657 -0.9547969 -0.2972581 -8.24022e-4 -0.9593142 -0.2823343 0.001922667 -0.9470379 -0.3211219 9.15573e-5 -0.9398799 -0.3415026 0.001342773 -0.9703789 -0.2415876 6.10378e-4 -0.9674085 -0.2532207 -9.15586e-5 -0.9617468 -0.273939 -8.24014e-4 -0.9808542 -0.1947425 5.18825e-4 -0.9756991 -0.2190974 0.002746701 -0.9830858 -0.1831459 -1.52596e-4 -0.9743024 -0.2252334 0.002166867 -0.9888005 -0.1492409 -8.72637e-4 -0.9841485 -0.1773463 -3.96748e-4 -0.9849461 -0.1728608 -5.49346e-4 -0.9862909 -0.1650143 -7.34703e-4 -0.9789401 -0.2041442 0.001220762 -0.9774299 -0.211252 0.001831114 -0.9717885 -0.2358514 0.001159667 -0.9357004 -0.3527951 6.71409e-4 -0.9281839 -0.372122 -9.15579e-5 -0.8995791 -0.4367579 4.57785e-4 -0.8888602 -0.4581788 -1.52594e-4 -0.8647567 -0.5021907 -7.01938e-4 -0.8770508 -0.4803972 -7.62971e-4 -0.6626344 -0.748943 -4.88308e-4 -0.6189841 -0.7854035 -5.4934e-4 -0.587431 -0.809274 8.85053e-4 -0.5851115 -0.8109526 -7.93496e-4 -0.3206921 -0.9471833 -6.40896e-4 -0.2815101 -0.9595577 -0.001037597 -0.2910584 -0.9567052 5.49339e-4 -0.2548673 -0.9669756 8.54542e-4 -0.2450457 -0.969511 0.001067161 0.9999997 -8.83923e-4 0 0.9999997 8.37949e-4 0 8.21633e-7 0 -1 -5.93453e-7 0 -1 -6.42412e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 1.59125e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 7.63022e-7 0 -1 2.2089e-7 0 -1 -8.53266e-7 0 -1 -1.21546e-7 0 -1 -1.81565e-7 0 -1 1.9278e-7 0 -1 5.43686e-7 0 -1 -3.75086e-7 0 -1 1.87388e-6 0 -1 -1.03767e-6 0 -1 1.68406e-6 0 -1 0.9993264 -0.03669631 -1.73899e-4 0.9992993 -0.03742885 0 0.9993445 -0.03619605 6.04253e-4 0.9993402 -0.0363205 -3.43451e-4 0.9993324 -0.03653126 -4.18131e-4 0.9993416 -0.03628337 7.73849e-5 0.999341 -0.03630059 1.34387e-4 0.9993542 -0.03593212 5.34569e-4 0.9993135 -0.03704524 -4.89062e-4 0.999376 -0.03532034 3.74714e-4 0.9993177 -0.03693735 -9.05833e-5 0.9993424 -0.03626149 9.42429e-5 0.9993508 -0.03602868 0 -0.0363332 -0.9993398 0 -0.03632813 -0.9993399 -7.62914e-6 -0.03632241 -0.9993402 0 0.9993125 -0.03707605 1.68326e-4 0.9993358 -0.03644257 0 0.9993637 -0.03566849 -4.41228e-5 0.9993382 -0.0363785 -1.70732e-5 0.9993349 -0.03646671 3.60594e-5 0.9993551 -0.03590756 2.83016e-4 0.9993447 -0.03619724 9.2959e-5 0.9993363 -0.03643107 2.98303e-5 0.9993273 -0.03667461 -8.60301e-5 0.9993171 -0.03695231 -2.63166e-5 0.9993591 -0.03579783 1.16162e-4 0.9993323 -0.03653967 0 0.9997246 -0.02347296 2.98747e-6 0.9997248 -0.02345925 -7.0834e-5 0.9997249 -0.02345699 -6.67732e-5 0.9997249 -0.02345669 -8.24447e-5 0.9997254 -0.02343446 -3.1554e-4 0.9997245 -0.02347224 4.8668e-5 0.9997245 -0.02347385 5.88376e-5 0.9997241 -0.02348989 1.11166e-4 0.9997265 -0.02338814 -2.93506e-4 0.9997234 -0.02351713 3.06235e-4 0.9997248 -0.02346283 -8.11131e-5 0.9997252 -0.02344518 2.37344e-4 0.9997229 -0.02351993 0.001055955 0.9997257 -0.02341395 -5.18151e-4 0.9997241 -0.02348917 2.80779e-4 0.9997265 -0.0233832 -5.77216e-4 0.9997227 -0.02355092 4.13573e-4 0.9997239 -0.02350026 2.03253e-4 0.9997246 -0.02347069 -2.3576e-6 0.9997245 -0.02347248 3.68538e-6 0.9997246 -0.02346956 1.21653e-5 0.9997251 -0.02344781 1.83269e-4 0.9997248 -0.02346354 8.16468e-5 0.9997243 -0.02348393 -1.23459e-4 0.9997246 -0.02347344 -2.95087e-5 0.9997245 -0.02347218 -1.05048e-5 0.9997246 -0.02346646 1.56755e-4 0.9997244 -0.02347648 -9.21471e-5 0.9997246 -0.02347087 1.57764e-4 0.9997245 -0.02347415 -1.63178e-4 -0.02346897 -0.9997246 0 -0.02346509 -0.9997248 1.8081e-6 -0.02347302 -0.9997246 -1.16269e-5 -0.02346849 -0.9997247 0 -0.02347266 -0.9997246 -6.13816e-6 -0.02347028 -0.9997246 -3.54563e-6 -0.02347439 -0.9997245 -1.27942e-5 -0.02347368 -0.9997246 -1.03871e-5 -0.02347642 -0.9997245 -3.70555e-5 -0.02345949 -0.9997249 4.69699e-5 -0.02346378 -0.9997247 4.73877e-5 -0.02347797 -0.9997245 -3.87342e-5 -0.02347946 -0.9997244 -7.53027e-5 -0.02346479 -0.9997248 3.70382e-5 -0.02346807 -0.9997247 2.85779e-5 -0.02346718 -0.9997246 2.34846e-5 -0.02347016 -0.9997246 -1.35032e-5 -0.02346807 -0.9997247 2.22333e-5 -0.02347129 -0.9997246 -2.79781e-5 -0.02347069 -0.9997246 1.04872e-5 -0.02347266 -0.9997245 0 -0.02347052 -0.9997246 -3.90945e-6 -0.023476 -0.9997245 1.16872e-5 -0.02347481 -0.9997245 6.95166e-6 -0.02345949 -0.9997248 -1.05804e-5 -0.02347737 -0.9997244 0 -0.9997248 0.02345639 -4.86295e-4 -0.9997244 0.023476 3.93805e-4 -0.9997236 0.02350234 6.48113e-4 -0.9997252 0.02344363 -2.81205e-4 -0.9997264 0.02337986 -7.39669e-4 -0.9997251 0.02345305 -8.02727e-6 -0.9997262 0.02339714 -4.78738e-4 -0.9997242 0.02348983 2.0763e-4 -0.9997254 0.02343636 -1.74521e-4 -0.999723 0.02353572 4.56342e-4 -0.9997305 0.02318674 -0.001209199 -0.9997189 0.02368742 0.001096069 -0.999718 0.02372765 9.70911e-4 -0.9997256 0.02342689 -1.23287e-4 -0.9997144 0.02379155 -0.002249479 -0.9997328 0.02308511 -0.001260995 -0.9997259 0.02338516 0.001192808 -0.9997266 0.02338296 4.85842e-5 -0.9997246 0.0228551 0.005340158 -0.9997051 0.0234791 -0.006214141 -0.9997243 0.02339768 0.001980602 -0.9997164 0.02374386 -0.001909077 -0.9995599 0.02510499 -0.01581156 -0.9997284 0.02288973 0.004405498 -0.9997263 0.02339828 -8.27517e-5 -0.9997242 0.02343297 -0.00158298 -0.9997211 0.02357441 -0.001399457 -0.999712 0.02377146 -0.003318428 -0.9997249 0.02345162 -3.47649e-4 -0.9997268 0.0233727 5.53362e-4 -0.9997334 0.02276211 0.003890514 -0.9997289 0.02324402 0.001451551 -0.9997257 0.02342063 4.07401e-4 -0.9997243 0.02348089 7.50772e-6 -0.9997246 0.0234695 -1.41726e-6 -0.9997249 0.02345871 -6.7383e-5 -0.9997245 0.02346837 -4.87402e-4 -0.999713 0.02383762 -0.00241822 -0.9997251 0.02345228 9.95677e-5 -0.9987576 0.0270521 -0.04185223 -0.977326 -0.01380109 0.2112902 -0.999729 0.02320307 0.0018965 -0.9997221 0.02356117 -8.29338e-4 -0.9997268 0.02334493 0.001132667 -0.9997268 0.02337503 3.95137e-4 -0.9997298 0.02320814 0.001380741 -0.9997247 0.0234645 -5.77111e-5 -0.9997188 0.02369314 -0.001072525 -0.9997269 0.02336454 -5.17411e-4 -0.9997194 0.02368122 6.41404e-4 -0.9997289 0.02326649 -9.56113e-4 -0.9997233 0.02352654 2.10547e-4 -0.9997273 0.02333664 -8.44853e-4 -0.9997181 0.02371585 0.001146435 -0.9997246 0.02346819 -2.19312e-4 -0.9997187 0.0236876 0.001238763 -0.999726 0.02338951 -9.70755e-4 -0.9997237 0.02351015 1.07435e-4 -0.9997243 0.02348589 -1.40263e-4 -0.9997223 0.02355343 7.75978e-4 -0.9997246 0.02346831 -1.72768e-4 -0.9997249 0.023436 -0.001013934 -0.9997241 0.0234816 6.70223e-4 -0.02346676 -0.9997247 -2.90469e-6 -0.02347058 -0.9997246 -2.52065e-5 -0.02346473 -0.9997247 0 -0.02347481 -0.9997245 1.17043e-5 -0.02347385 -0.9997245 1.21794e-5 -0.0234642 -0.9997247 -4.17511e-5 -0.0234695 -0.9997246 -1.23072e-5 -0.0234782 -0.9997244 1.81898e-5 -0.02347183 -0.9997245 -7.85823e-6 -0.02346616 -0.9997246 -1.55651e-5 -0.02348124 -0.9997243 7.94794e-7 -0.02347332 -0.9997245 -7.91227e-6 -0.0234822 -0.9997243 0 -0.02347135 -0.9997246 -9.50222e-6 2.08325e-5 1.01753e-5 -1 -1.34037e-4 0 -1 -9.53721e-5 0 -1 1.67084e-4 0 -1 5.93945e-5 2.97107e-6 -1 0 3.36598e-6 -1 -7.21813e-5 1.03953e-5 -1 -4.30339e-5 0 -1 7.74796e-5 -7.5909e-6 -1 -6.74166e-6 -1.53944e-6 -1 0 -1.23691e-6 -1 0 0 -1 0 -8.25983e-6 -1 0 5.95811e-6 -1 0 -1.01449e-6 -1 0 -9.57415e-7 -1 0 -9.13207e-7 -1 0 -8.73015e-7 -1 0 -8.34258e-7 -1 5.93266e-6 -7.89146e-7 -1 0 -7.46431e-7 -1 9.26072e-6 -7.04382e-7 -1 -9.85134e-6 -6.67381e-7 -1 0 -6.39877e-7 -1 0 -6.15915e-7 -1 9.51277e-7 -5.94412e-7 -1 0 -5.7394e-7 -1 -1.33864e-5 -5.50508e-7 -1 9.36722e-6 -1.13782e-5 -1 -0.8007143 -0.5990462 4.73478e-4 -0.8007172 -0.5990427 -2.12084e-6 -0.8004674 -0.5993762 -5.76287e-4 -0.8010143 -0.5986452 2.46771e-4 -0.800623 -0.5991686 -1.10816e-4 -0.8008414 -0.5988765 0 -0.8003336 -0.5995551 -1.17679e-4 -0.8006358 -0.5991513 -3.15167e-4 -2.32722e-6 0 -1 2.34788e-6 0 -1 -0.5991179 0.8006609 1.86767e-4 -0.5991887 0.8006076 6.81522e-4 -0.5991829 0.8006122 3.64161e-5 -0.5994159 0.8004378 -1.39833e-4 -0.5991571 0.8006315 2.61337e-5 -0.5992444 0.8005662 4.30765e-5 -0.5991144 0.8006634 -9.39484e-5 -0.5993385 0.8004958 -1.14177e-4 -0.5991536 0.8006342 -1.15765e-5 -0.5988321 0.8008743 -7.8231e-4 -0.5990273 0.8007287 -2.4499e-4 -0.5991979 0.8006008 -3.93708e-4 -0.5990675 0.8006986 -3.39265e-4 -0.5992639 0.8005516 4.49424e-4 -0.598896 0.8008261 -0.001116871 -0.5993556 0.8004828 5.71697e-4 -0.5992582 0.8005557 5.54079e-4 -0.5991771 0.8006166 -3.03135e-6 -0.5992035 0.8005968 3.78927e-5 -0.5994857 0.8003852 6.22743e-4 -0.5991322 0.8006502 -1.14501e-4 -0.5993696 0.8004724 3.61216e-4 -0.5991733 0.8006195 1.7935e-5 -0.5990518 0.8007093 -0.001235485 -0.5991498 0.800637 -1.75879e-5 -0.5994464 0.8004147 6.63777e-4 -0.5992608 0.8005528 0.001328289 -0.5992483 0.8005628 -8.34214e-4 -0.599167 0.8006239 6.14682e-4 -0.5992122 0.8005902 -5.61791e-4 -0.5991232 0.8006569 1.38709e-4 -0.5991967 0.8006018 6.54761e-6 -0.5989786 0.800765 -3.31979e-4 -0.5993686 0.8004731 2.62411e-4 -0.5992018 0.8005981 0 -0.5991926 0.800605 3.39623e-5 -0.5994113 0.8004412 -3.38698e-4 -0.5989259 0.8008045 -3.84322e-4 -0.5991758 0.8006175 -8.73555e-5 -0.5992413 0.8005685 -9.1337e-5 -0.5992147 0.8005884 -2.69394e-5 -0.5992785 0.8005406 5.93137e-5 -0.598934 0.8007984 -1.40342e-4 -0.5993559 0.8004828 0 -0.5994537 0.8004095 2.27401e-4 -0.5989642 0.800776 -1.6592e-4 -0.5994954 0.8003783 3.29684e-4 -0.5990752 0.8006927 -1.02639e-4 -0.5991906 0.8006065 5.78153e-6 -0.598996 0.8007521 2.36665e-4 -0.5992118 0.8005903 -6.93247e-4 -0.5993078 0.8005186 -4.30093e-4 -0.598954 0.8007832 5.45139e-4 -0.5989258 0.8008034 0.001362442 -0.5989622 0.8007774 2.25615e-4 -0.5988806 0.8008384 3.14655e-4 -0.5990344 0.8007233 7.49484e-5 -0.5992863 0.8005343 -9.30692e-4 -0.5991466 0.8006393 5.67627e-4 -0.5991223 0.8006575 4.71865e-4 -0.5991278 0.8006533 5.07553e-4 -0.5990909 0.8006808 6.34859e-4 -0.5993362 0.8004968 -9.94171e-4 -0.599375 0.8004681 -8.1796e-4 -0.5993122 0.8005151 -7.35316e-4 -0.5992068 0.8005943 -1.51269e-4 -0.5990155 0.8007372 6.55539e-4 -0.5991209 0.8006587 3.09098e-4 -0.5989991 0.8007494 7.96767e-4 -0.5992032 0.800597 0 -0.5991641 0.8006263 -3.71969e-5 -0.5992035 0.8005968 3.88179e-6 -0.5987626 0.8009265 -3.86559e-4 -0.5992724 0.8005452 6.97193e-5 -0.5992597 0.8005548 9.26604e-5 -0.5992871 0.8005342 1.06441e-4 -0.599011 0.8007408 -1.96861e-4 -0.5993863 0.8004599 2.441e-4 -0.5989876 0.8007584 -2.74975e-4 -0.5991936 0.8006042 1.02483e-5 -0.5991662 0.8006247 -1.3658e-5 -0.5993427 0.8004926 7.18222e-5 -0.5990833 0.8006868 -5.92865e-5 -0.5995348 0.8003487 1.99324e-4 -0.5991019 0.8006728 -5.64354e-5 -0.5992217 0.8005833 -3.23394e-5 -0.5991934 0.8006044 -3.61766e-6 -0.5988725 0.8008444 3.11128e-4 -0.5992615 0.8005535 -4.97485e-5 -0.5991849 0.8006108 2.08796e-6 -0.5991668 0.8006243 1.08521e-5 -0.5988233 0.8008812 2.13184e-4 -0.5991114 0.8006657 5.79892e-5 -0.5991813 0.8006135 -4.75976e-6 -0.5996289 0.8002783 -1.999e-4 -0.599173 0.8006197 5.17905e-6 -0.5991891 0.8006075 -3.24744e-5 -0.5992764 0.8005422 -1.95717e-4 -0.5991786 0.8006155 2.12934e-5 -0.5989589 0.8007797 4.15853e-4 -0.5991973 0.8006013 4.23018e-4 -0.599103 0.8006718 6.99061e-4 -0.5992059 0.8005949 -5.06604e-4 -0.5991832 0.800612 2.17321e-5 -0.5991818 0.8006131 2.89863e-5 -0.599294 0.8005291 -2.49248e-4 -0.5989573 0.800781 3.92116e-4 -0.5997282 0.8002036 -7.90981e-4 -0.5997047 0.8002213 -5.16801e-4 -0.5985142 0.8011121 5.23675e-4 -0.5996066 0.800295 -2.64753e-4 -0.5993732 0.8004698 -1.4255e-4 -0.5983809 0.8012117 4.91338e-4 -0.5994976 0.8003767 -1.66913e-4 -0.5992218 0.8005832 -1.1568e-5 -0.5993639 0.8004766 -6.11141e-5 -0.5992466 0.8005645 1.24362e-4 -0.5992639 0.8005517 2.61604e-4 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 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 -1.94779e-5 0 -1 1.2629e-5 0 -1 1.35634e-5 0 -1 -7.4732e-6 0 -1 -7.69951e-6 0 -1 9.52221e-6 0 -1 1.47404e-5 0 -1 8.63821e-5 0 -1 -5.12671e-5 0 -1 9.8491e-5 0 -1 -1.35541e-4 0 -1 1.11794e-4 0 -1 -4.20086e-5 0 -1 2.75634e-5 0 -1 1.9123e-6 0 -1 1.60798e-6 0 0 -1 5.19564e-7 0 -1 9.9987e-7 0 -1 -2.46239e-7 0 0 -1 -6.82236e-7 0 -1 9.70105e-7 0 -1 0 0 -1 -4.30293e-7 0 -1 4.85045e-7 0 -1 1.2439e-5 0 -1 -6.22665e-6 0 -1 4.38446e-7 0 -1 0 0 -1 -7.05423e-7 0 -1 1.19888e-7 0 -1 2.56186e-7 1.32783e-5 -1 0 0 -1 2.09169e-7 0 -1 1.49114e-7 -1.20044e-7 -1 0 0 -1 -1.23756e-6 -2.02131e-7 -1 -6.00166e-7 -4.471e-7 -1 -7.06895e-7 -4.64087e-7 -1 -4.84134e-7 0 -1 9.22784e-7 -1.5774e-7 -1 5.65497e-7 1.39324e-5 -1 0 -2.85843e-7 -1 0 -5.16989e-7 -1 0 -3.35579e-7 -1 6.5398e-7 0 -1 3.65876e-7 0 -1 2.53382e-7 0 -1 -3.75353e-7 0 -1 4.21187e-6 0 -1 -1.06172e-6 0 -1 -2.12129e-7 0 -1 0 -8.02664e-5 -1 5.86634e-7 0 -1 0 8.2273e-5 -1 3.98068e-7 0 -1 -3.84518e-7 0 -1 0 -6.11654e-7 -1 -1.54238e-6 -6.61873e-7 -1 -8.78596e-7 0 -1 1.21038e-6 0 -1 0 -8.2757e-7 -1 1.97872e-6 1.91351e-5 -1 -4.56156e-6 -6.35079e-7 -1 0 -3.9825e-7 -1 0 -4.94319e-7 -1 1.21179e-6 -3.75746e-7 -1 5.79444e-7 -3.56739e-7 -1 0 -3.37059e-7 -1 0 -2.42673e-7 -1 1.79406e-6 -2.84564e-7 -1 0 -5.00911e-7 -1 0 -3.09346e-7 -1 0 -2.09953e-7 -1 0 -4.89513e-7 -1 0 -1.81188e-7 -1 0 -3.91403e-7 -1 0 0 -1 0 -1.33913e-5 -1 2.54949e-7 0 -1 0 -3.05788e-7 -1 2.32818e-7 0 -1 -1.73299e-7 0 -1 2.79497e-6 -2.50564e-7 -1 2.05329e-7 0 -1 0 0 -1 2.01544e-7 0 -1 2.00872e-7 0 -1 -2.71787e-7 0 -1 0 1.21623e-6 -1 0 2.62276e-7 -1 2.40496e-7 3.57725e-7 -1 3.78423e-7 3.37671e-7 -1 0 0 -1 -1.29573e-6 3.0746e-7 -1 -2.50226e-7 3.83846e-7 -1 0 6.98139e-7 -1 -1.92526e-6 2.23089e-7 -1 0 6.39126e-7 -1 1.36726e-6 1.8656e-7 -1 0 5.84517e-7 -1 0 7.57885e-7 -1 0 8.09277e-7 -1 -1.36096e-6 5.403e-7 -1 0 1.12031e-6 -1 0 1.07172e-6 -1 1.05019e-6 4.69158e-7 -1 0 1.00659e-6 -1 -2.80475e-6 5.95102e-7 -1 -2.04976e-6 3.82973e-7 -1 0 1.17233e-6 -1 1.93643e-6 9.24878e-7 -1 -5.71653e-7 8.70332e-7 -1 0 3.10406e-7 -1 0 7.76209e-7 -1 0 1.26314e-6 -1 -3.10893e-7 1.30435e-6 -1 1.23382e-6 1.59068e-7 -1 1.17004e-5 1.0367e-6 -1 -2.52873e-7 1.3484e-6 -1 -8.95815e-7 4.91613e-7 -1 -1.81702e-6 1.39389e-6 -1 -1.69687e-7 4.54731e-7 -1 4.88374e-6 1.42648e-6 -1 -4.54843e-6 1.44877e-6 -1 3.17025e-5 1.41174e-6 -1 0 4.13575e-7 -1 0 1.4735e-6 -1 0 2.30038e-7 -1 0 1.84716e-7 -1 0 1.49426e-6 -1 4.44501e-7 0 -1 2.52664e-7 1.41295e-7 -1 0 1.50556e-6 -1 0 1.62029e-6 -1 -2.90518e-7 3.09558e-5 -1 0 1.50673e-6 -1 -1.88006e-7 0 -1 0 1.51146e-6 -1 1.33116e-7 0 -1 0 1.12924e-5 -1 3.79612e-6 0 -1 0 1.20938e-5 -1 0 1.24434e-5 -1 2.93769e-6 1.25782e-5 -1 -2.25082e-6 1.25389e-5 -1 5.27111e-7 1.18715e-5 -1 0 1.16009e-5 -1 8.06109e-7 0 -1 -3.20529e-6 0 -1 0 1.15598e-5 -1 -1.53828e-6 0 -1 1.66353e-5 0 -1 0 0 -1 -1.61676e-7 0 -1 0 1.13423e-5 -1 -5.62213e-6 0 -1 1.79278e-7 0 -1 4.50989e-7 0 -1 1.38515e-5 0 -1 7.87129e-6 0 -1 2.61682e-5 0 -1 4.45487e-7 0 -1 -1.27622e-5 0 -1 -1.47635e-7 0 -1 -6.14113e-7 3.10978e-6 -1 0 1.05091e-6 -1 2.32637e-6 0 -1 0 0 -1 0 1.22483e-7 -1 -1.49648e-5 -3.22128e-6 -1 -3.00779e-7 1.11814e-6 -1 0 1.88858e-7 -1 -2.52458e-6 -5.54223e-6 -1 7.5726e-6 2.23905e-7 -1 0 -2.86623e-6 -1 -1.25412e-6 1.20479e-6 -1 9.79518e-6 3.0468e-7 -1 0 -1.44723e-6 -1 0 -6.54983e-7 -1 0 3.6867e-7 -1 5.81999e-6 4.59108e-7 -1 -5.83327e-7 1.26266e-6 -1 4.98349e-6 -3.266e-7 -1 -5.19123e-7 -1.73412e-6 -1 0 6.90767e-7 -1 -2.84e-7 0 -1 0 1.27273e-6 -1 0 0 -1 0 9.99201e-7 -1 -1.13959e-6 0 -1 2.71078e-7 1.2761e-6 -1 0 0 -1 0 1.27545e-6 -1 -1.19661e-6 0 -1 0 1.35157e-7 -1 0 1.27401e-6 -1 0 1.70384e-7 -1 0 -1.0698e-6 -1 -2.13227e-7 1.29258e-7 -1 -4.53457e-7 1.56928e-7 -1 -3.68753e-7 1.86297e-7 -1 0 1.27443e-6 -1 -5.37977e-7 2.23643e-7 -1 -3.02806e-7 2.70389e-7 -1 4.53658e-6 9.48603e-7 -1 -6.92118e-7 3.2743e-7 -1 -6.19544e-7 4.0945e-7 -1 0 5.31163e-7 -1 0 7.33201e-7 -1 0 6.21784e-7 -1 0 1.15911e-6 -1 -3.32857e-7 0 -1 3.34899e-7 0 -1 -6.35367e-7 0 -1 6.25154e-7 0 -1 -1.36226e-6 0 -1 2.43081e-7 0 -1 5.45198e-7 0 -1 -2.16448e-6 0 -1 8.23819e-7 0 -1 0 -3.63699e-6 -1 0 1.01984e-5 -1 4.26996e-6 3.04539e-6 -1 1.82875e-6 5.37061e-6 -1 4.8542e-7 1.64386e-5 -1 6.57054e-6 1.98752e-5 -1 0 1.66454e-5 -1 2.25907e-5 4.01032e-5 -1 0 4.05847e-5 -1 0 3.8776e-5 -1 5.96912e-5 1.67382e-4 -1 0 1.1111e-5 -1 0 1.29517e-6 -1 0 1.6144e-7 -1 -2.93766e-5 0 -1 -3.40598e-6 -4.68738e-7 -1 2.01883e-7 0 -1 0 -2.82578e-5 -1 8.42994e-6 0 -1 -1.01181e-6 0 -1 -1.93242e-6 0 -1 2.92357e-6 -5.5379e-7 -1 0 -7.80784e-7 -1 0 -1.74196e-6 -1 -3.93664e-6 -9.31179e-7 -1 -3.80291e-5 -1.26065e-6 -1 0 -1.93341e-6 -1 0 -2.41785e-6 -1 6.31207e-5 -4.28215e-6 -1 0 -3.65323e-6 -1 -7.1437e-7 -2.60493e-6 -1 -2.30643e-6 -1.14308e-6 -1 -5.21005e-6 -3.94792e-7 -1 -5.88471e-7 0 -1 0 -2.64901e-7 -1 -1.15456e-6 0 -1 -8.39421e-7 0 -1 -1.85171e-6 0 -1 -1.74908e-7 0 -1 -1.95473e-7 0 -1 2.16352e-7 0 -1 8.95379e-7 1.44135e-6 -1 2.63661e-7 0 -1 0 1.36326e-7 -1 7.80461e-7 2.74708e-7 -1 -5.12583e-7 -1.69205e-5 -1 0 -1.72231e-7 -1 -1.37317e-6 -5.13276e-7 -1 0 -5.27405e-7 -1 -2.40158e-6 -4.03803e-7 -1 -1.57081e-5 -6.7652e-7 -1 2.35492e-6 -5.45333e-7 -1 -2.94112e-6 -5.61227e-7 -1 3.06806e-6 -5.76575e-7 -1 -4.92394e-6 0 -1 0 -8.9273e-7 -1 -4.15388e-6 -8.44557e-6 -1 0 -6.38237e-7 -1 0 -4.78495e-7 -1 0 -1.48431e-7 -1 -1.69966e-6 -1.22568e-7 -1 2.86397e-7 -4.27319e-7 -1 -5.9518e-6 0 -1 0 -4.60508e-7 -1 5.45971e-6 0 -1 0 -4.24342e-7 -1 -4.44158e-6 0 -1 4.71773e-6 0 -1 0 -4.17787e-7 -1 0 -4.12598e-7 -1 -4.75114e-7 0 -1 4.51607e-7 0 -1 0.06213736 0.01040709 -0.9980134 0.06628775 0.03137373 -0.9973072 0.06479185 0.01483219 -0.9977886 0.06314444 0.1125857 -0.9916337 0.05725365 0.01864707 -0.9981855 0.05694854 0.01605302 -0.9982481 0.06354135 0.007172048 -0.9979535 0.09436547 -0.7755857 -0.6241492 0.09949308 -0.7862091 -0.6098988 0.09915703 -0.7582204 -0.6444141 0.09076547 -0.8376122 -0.5386721 0.08560681 -0.8705953 -0.4844948 0.08966511 -0.8560306 -0.5090894 0.08365267 -0.9514311 -0.2962788 0.08865952 -0.9254777 -0.3682805 0.08594161 -0.9225906 -0.3760861 0.06656169 -0.9911619 -0.114751 0.08960437 -0.9672759 -0.2373784 0.09149682 -0.9422527 -0.3221617 0.096897 -0.9243516 -0.3690326 0.06061011 -0.9979925 -0.01837223 0.07492536 -0.9902966 -0.1170423 0.08877974 -0.9608908 -0.2623109 0.08908492 -0.9539626 -0.2863902 0.1135907 -0.9595084 -0.2577611 0.1016285 -0.9738942 -0.2029823 0.09634894 -0.9814346 -0.165841 0.0965622 -0.9888169 -0.1136529 0.09506648 -0.9855787 -0.1399903 0.05846643 -0.9982719 -0.005924999 0.08881074 -0.9918118 -0.09177112 0.05748629 -0.998342 0.002939403 0.05644631 -0.9980987 0.0247575 0.05481243 -0.9984861 0.004606723 0.05454766 -0.9984622 0.009890854 0.09177094 -0.8876481 -0.451286 0.08972668 -0.9023635 -0.4215323 0.09448713 -0.870527 -0.4829649 0.06543338 -0.9920607 -0.1073974 0.07367253 -0.9693705 -0.2342932 0.0616492 -0.9939261 -0.09116148 0.05655139 -0.9983321 -0.01162767 0.05789506 -0.9981941 -0.01602262 0.07751762 -0.9617989 -0.2625529 0.07266557 -0.9750497 -0.2097567 0.08005201 -0.9413363 -0.327838 0.09332609 -0.7454491 -0.6599968 0.08847475 -0.7406979 -0.6659872 0.0843845 -0.8953609 -0.4372735 0.08273798 -0.9273312 -0.3649812 0.08099812 -0.9314786 -0.3546644 0.0880478 -0.8884739 -0.4504018 0.08652108 -0.882668 -0.4619648 0.09109872 -0.8214757 -0.56292 0.08664429 -0.565645 -0.8200845 0.08484375 -0.5162042 -0.8522529 0.08542382 -0.5947015 -0.7993953 0.09488427 -0.8032662 -0.5880141 0.09231936 -0.8231533 -0.5602643 0.09543269 -0.7337365 -0.6726986 0.08444589 -0.4381908 -0.8949066 0.08484268 -0.5890158 -0.8036555 0.08786475 -0.5703429 -0.8166939 0.0873754 -0.665799 -0.7409974 0.08859592 -0.8202829 -0.5650547 0.08435493 -0.878433 -0.4703613 0.0751065 -0.284007 -0.9558761 0.07712239 -0.3995898 -0.9134442 0.07995933 -0.4017804 -0.9122384 0.07858604 -0.4028795 -0.911873 0.07227039 -0.2735472 -0.9591397 0.09323519 -0.6265225 -0.7738067 0.0583226 -0.06396871 -0.9962462 0.05679571 -0.02160739 -0.9981521 0.06409013 -0.1258304 -0.9899795 0.0798071 -0.9416023 -0.327133 0.09552443 -0.6334215 -0.7678882 0.09531152 -0.7331024 -0.6734068 0.09311336 -0.5242244 -0.8464743 0.09726583 -0.577766 -0.8103862 0.06329625 -0.1216484 -0.9905531 0.05557531 -0.0243237 -0.9981582 0.08060032 -0.3723913 -0.9245693 0.08331799 -0.4840684 -0.8710545 0.05505251 -1.16438e-4 -0.9984835 0.0941506 -0.47057 -0.8773252 0.08865827 -0.4102088 -0.907672 0.06515735 -0.1227156 -0.9903007 0.09030783 -0.7437961 -0.6622779 0.05486375 -2.79538e-4 -0.9984939 0.05488651 -2.52683e-4 -0.9984926 0.05179685 -0.0185253 -0.9984858 0.08356189 -0.3235965 -0.9424982 0.08676612 -0.4524475 -0.8875601 0.08218777 -0.3354653 -0.9384606 0.07586979 -0.2483012 -0.9657072 0.07678592 -0.2291676 -0.9703536 0.06814908 -0.1031545 -0.9923281 0.06094682 -0.01965433 -0.9979476 0.06344884 -0.02139377 -0.9977558 0.0510444 2.90829e-4 -0.9986964 0.08676666 0.7437886 -0.6627596 0.084966 0.7988762 -0.5954644 0.07925766 0.713014 -0.6966558 0.05538988 -4.69146e-4 -0.9984648 0.05624997 0.01896858 -0.9982366 0.0555393 -1.31677e-4 -0.9984565 0.05389022 0.01486283 -0.9984363 0.05372089 0.01619017 -0.9984247 0.05548059 -1.30482e-4 -0.9984598 0.05462139 -0.008774399 -0.9984686 0.06650078 0.157142 -0.9853346 0.07654279 0.2676252 -0.960478 0.06552439 0.1163387 -0.9910458 0.05481642 -1.43133e-4 -0.9984965 0.08877992 0.4906854 -0.8668022 0.08392876 0.3924816 -0.9159227 0.08759039 0.4660908 -0.8803905 0.07443594 0.251416 -0.9650126 0.07233041 0.2581311 -0.9633986 0.080509 0.3872858 -0.9184379 0.07751971 0.3644038 -0.928009 0.0725134 0.2637157 -0.961871 0.0709269 0.245406 -0.9668223 0.08524012 0.5205049 -0.8495934 0.08212709 0.4698426 -0.8789216 0.08621621 0.528437 -0.8445835 0.08685743 0.5071059 -0.857496 0.08163845 0.3759949 -0.9230186 0.09290021 0.7364267 -0.6701086 0.08707195 0.7238906 -0.6843984 0.07642018 0.6927567 -0.717111 0.08923828 0.5831925 -0.8074175 0.09677594 0.7266589 -0.6801479 0.09045803 0.6866754 -0.7213143 0.08639949 0.4846429 -0.8704347 0.08261585 0.85149 -0.5178219 0.07748776 0.7581229 -0.6474915 0.07550406 0.9027527 -0.423482 0.08987873 0.8525513 -0.5148574 0.08585041 0.9124925 -0.3999842 0.0769695 0.7841922 -0.6157259 0.08401858 0.9228926 -0.3757796 0.07257413 0.8375633 -0.5414986 0.07886099 0.9670242 -0.242168 0.07239127 0.9786863 -0.1921787 0.09112977 0.8638104 -0.4955068 0.09177196 0.7422329 -0.6638284 0.0914666 0.7358225 -0.6709688 0.09201478 0.8107678 -0.5780909 0.08053952 0.657348 -0.7492711 0.08179211 0.6124032 -0.786303 0.08551329 0.5711569 -0.8163745 0.09140503 0.6592153 -0.7463782 0.07635891 0.7182381 -0.6915948 0.08090573 0.3980283 -0.9137986 0.09299212 0.6792671 -0.7279758 0.09430289 0.7077905 -0.7000998 0.09979712 0.7282748 -0.6779795 0.08667409 0.6021715 -0.793648 0.0966838 0.6256982 -0.7740504 0.09912699 0.6184757 -0.7795265 0.09561669 0.6897038 -0.7177509 0.09238165 0.6109032 -0.7862971 0.06257599 0.05384314 -0.9965869 0.08450889 0.5910739 -0.8021783 0.06616461 0.1508846 -0.9863348 0.06018257 0.1061741 -0.9925246 0.05652141 0.04342865 -0.9974564 0.0545684 0.01809787 -0.9983461 0.05699032 0.009080708 -0.9983335 0.0576204 0.03192317 -0.9978281 0.0596646 -0.02221781 -0.9979712 0.06613504 0.0897569 -0.9937655 0.06579965 0.08145606 -0.9945026 0.06280821 0.05444598 -0.9965394 0.06518852 0.06967478 -0.9954376 0.0643332 0.05572694 -0.9963714 0.06335651 0.04211556 -0.997102 0.06238019 0.03021347 -0.9975951 0.06143522 0.01962387 -0.9979181 0.05929797 -0.001678526 -0.998239 0.06189161 -0.002868711 -0.9980788 0.06488639 0.00313729 -0.9978877 0.06142944 -0.9980713 -0.008958101 0.06305271 -0.9980102 -3.79399e-4 0.05814379 -0.9983081 5.3007e-4 0.06851553 -0.9962375 -0.05307281 0.05590546 -0.9984316 0.002985417 0.06201142 -0.9980753 7.17462e-4 0.06616461 -0.9972 -0.03485238 0.08853507 -0.9146795 -0.3943642 0.05551534 -0.9984453 0.004990458 0.05358654 -0.9985227 0.008997499 0.06442558 -0.9977579 -0.01812827 0.05816829 -0.9976811 -0.03534042 0.08948355 -0.8689246 -0.4867882 0.09195452 -0.7144562 -0.6936115 0.09467023 -0.6239936 -0.7756736 0.06784492 -0.9877648 -0.1404204 0.09573918 -0.550905 -0.8290584 0.09677648 -0.597872 -0.7957282 0.09375596 -0.7377791 -0.6684997 0.08746826 -0.7532769 -0.6518613 0.09073424 -0.6522918 -0.7525176 0.09448879 -0.6374943 -0.7646391 0.08923882 -0.8583289 -0.50528 0.08108997 -0.5006092 -0.8618671 0.08847475 -0.3467881 -0.9337614 0.08362239 -0.2962796 -0.9514336 0.09613549 -0.6631827 -0.7422579 0.07657188 -0.1961448 -0.9775807 0.08121186 -0.2299325 -0.9698123 0.09134477 -0.5436739 -0.834311 0.08203554 -0.465204 -0.8813941 0.0676915 -0.1817721 -0.9810081 0.0546227 -0.001517772 -0.998506 0.06924754 -0.08096683 -0.9943085 0.07306224 -0.1096239 -0.9912844 0.0574668 -0.02414035 -0.9980555 0.06579881 -0.02142429 -0.9976029 0.05504328 -1.30027e-4 -0.998484 0.05340647 -4.26809e-5 -0.998573 0.05377238 5.72465e-4 -0.9985531 0.05649721 5.13465e-5 -0.9984028 0.06295442 -6.39935e-4 -0.9980163 0.05182516 -0.01934647 -0.9984688 0.0548681 -2.66892e-4 -0.9984936 0.05532526 -8.26055e-5 -0.9984684 0.05877083 -4.40177e-4 -0.9982715 0.05482673 -1.14795e-4 -0.9984959 0.06610184 0.001054942 -0.9978124 0.05861526 0.0125789 -0.9982014 0.05627709 -0.004862368 -0.9984034 0.05801898 2.34163e-4 -0.9983155 0.05485159 1.33336e-4 -0.9984946 0.04647243 2.96767e-4 -0.9989196 0.05951845 2.9685e-4 -0.9982272 0.06102252 -1.41724e-4 -0.9981365 0.06266587 -1.79674e-4 -0.9980345 0.06190675 2.06746e-4 -0.998082 0.06395179 0 -0.997953 0.05616784 -3.45501e-4 -0.9984213 0.06347465 6.45786e-5 -0.9979835 0.05572396 -0.00848639 -0.9984102 0.05903929 0.01435559 -0.9981524 0.06095099 -3.51523e-5 -0.9981408 0.05554437 -1.25394e-4 -0.9984563 0.05549484 -1.59988e-4 -0.9984591 0.05421888 0.00116837 -0.9985285 0.06287932 0.04481238 -0.9970146 0.05348044 -2.14926e-4 -0.9985689 0.06178426 0.009265244 -0.9980465 0.0645104 0.03907114 -0.997152 0.07770073 0.3215456 -0.9437008 0.05113172 -0.005607724 -0.9986763 0.06439453 0.03720235 -0.997231 0.07095432 0.06102401 -0.9956113 0.09412008 0.63467 -0.7670302 0.08191341 0.6848805 -0.7240366 0.07974642 0.7335879 -0.6748996 0.08194279 0.7074854 -0.7019615 0.08923763 0.9048891 -0.416188 0.08639955 0.9392865 -0.3320784 1 2.26164e-5 0 1 -7.12638e-5 0 1 -7.74654e-6 0 1 -5.40827e-6 0 1 0 -3.51922e-6 0.2084134 0.9780409 5.69483e-5 0.2040596 0.9789586 1.13453e-4 0.2125052 0.97716 8.27164e-6 0.2132579 0.976996 5.46761e-6 0.2153432 0.9765384 -1.01644e-4 0.2135187 0.976939 4.50774e-5 0.2147765 0.9766632 -6.12047e-5 0.215654 0.9764697 5.11224e-4 0.2155934 0.9764832 4.94546e-4 0.2152583 0.9765571 4.36088e-4 0.2146369 0.9766939 3.23372e-4 0.2138532 0.9768658 1.95787e-4 0.2122292 0.9772199 -2.74571e-5 0.2097105 0.9777635 -3.04421e-4 0.2078812 0.9781541 -4.49849e-4 0.2068033 0.9783825 -4.96997e-4 0.2067888 0.9783856 -4.96888e-4 0.20051 0.9796914 7.62976e-4 0.2056382 0.9786281 -2.74673e-4 0.1917182 0.9814499 7.01929e-4 0.2105011 0.9775934 -6.96651e-4 0.1744468 0.9846664 7.32457e-4 0.1854048 0.982661 0.001556456 0.1608346 0.9869814 -2.7467e-4 0.1586999 0.9873269 -1.52596e-4 0.1713631 0.985208 -3.05188e-5 0.2145411 0.976715 -5.52508e-5 0.2133259 0.9769811 -4.0014e-6 0.2142233 0.9767847 -2.86572e-5 0.2150321 0.976607 -4.65856e-5 0.2132762 0.976992 -6.83448e-6 0.2401798 0.9707283 -4.28119e-4 0.2096378 0.9777792 5.58729e-5 0.2068465 0.9783734 3.64022e-4 0.1996256 0.9798723 -2.2627e-4 0.1987372 0.9800528 3.365e-4 0.1869165 0.9823758 -2.87263e-4 0.0769999 0.9970312 -9.15575e-5 0.07654243 0.9970664 1.52597e-4 0.09747892 0.9952377 -6.10388e-5 0.05420225 0.99853 -1.52596e-4 0.05249315 0.9986214 6.10386e-5 0.02734518 0.9996261 -1.83115e-4 -6.40908e-4 0.9999998 -3.05194e-4 -0.002563595 0.9999967 4.88309e-4 -0.1172219 0.9931058 -3.05186e-4 -0.09326505 0.9956414 2.74668e-4 -0.09241223 0.9957209 -9.15577e-5 -0.124031 0.9922782 4.57791e-4 -0.145667 0.9893336 -4.27266e-4 -0.1561678 0.9877305 4.88311e-4 -0.1728311 0.9849514 -4.27271e-4 -0.1898909 0.981805 5.49347e-4 -0.2047244 0.9788195 -6.40908e-4 -0.2307553 0.9730115 7.3246e-4 -0.2481542 0.9687203 -7.32469e-4 -0.2792487 0.9602187 6.40898e-4 -0.2927387 0.9561924 -4.88305e-4 -0.3375986 0.9412903 -2.4415e-4 -0.3297277 0.944076 3.96748e-4 -0.385978 0.922508 3.05193e-4 -0.3842101 0.9232457 -3.66234e-4 -0.4383779 0.8987905 -6.71423e-4 -0.4508234 0.8926132 1.83113e-4 -0.5193434 0.8545651 -0.001037597 -0.5249282 0.8511466 -4.27267e-4 -0.6302245 0.7764122 -0.001129209 -0.5994628 0.8004027 -9.15583e-5 -0.675737 0.7371426 4.88315e-4 -0.6899968 0.7238116 -0.001098632 -0.7145746 0.6995592 2.44153e-4 -0.06961381 0.9975741 -9.1557e-5 -0.06616449 0.9978088 3.05187e-4 -0.03708046 0.9993122 5.7986e-4 -0.04757964 0.9988674 -3.05193e-4 -0.0250867 0.9996853 -3.35711e-4 0.02853536 0.9995928 1.52596e-4 0.04150086 0.9991385 -4.33036e-5 0.06578499 0.9978339 -1.46971e-4 0.0893777 0.9959978 1.63784e-4 0.1068527 0.9942749 -1.40333e-4 0.1090114 0.9940405 2.33368e-4 0.1252466 0.9921257 -3.51968e-4 0.1296558 0.9915591 3.33697e-4 0.140621 0.9900634 -3.06367e-4 0.1447268 0.9894717 3.15897e-4 0.1584764 0.9873628 -4.64284e-4 0.1617738 0.9868277 4.92564e-4 0.1764482 0.9843099 -4.0031e-4 0.1773797 0.9841425 -3.15686e-5 0.1855942 0.9826264 2.32106e-4 0.1931354 0.9811722 -6.817e-5 0.1939371 0.981014 3.99685e-4 0.1976279 0.9802772 -2.89703e-4 -0.008556485 -0.9999635 1.08026e-4 -0.01967954 -0.9998064 2.07848e-4 -0.02113789 -0.9997767 -1.21632e-4 -0.02132719 -0.9997726 1.46598e-4 -0.02034628 -0.999793 -8.23665e-5 -0.02141004 -0.9997708 1.16445e-4 -0.02467793 -0.9996955 -1.00894e-4 -0.02508974 -0.9996851 -4.01293e-4 -0.02655416 -0.9996474 2.99006e-4 -0.02903765 -0.9995784 8.87355e-5 -0.0299226 -0.9995521 -4.02133e-4 -0.03138834 -0.9995074 1.50717e-4 -0.03519195 -0.9993807 -2.88496e-4 -0.03547787 -0.9993705 -8.86779e-5 -0.03982168 -0.9992067 4.6677e-4 -0.0437898 -0.9990405 -8.44129e-4 -0.04442793 -0.9990125 -4.39106e-4 -0.05030733 -0.9987334 9.10038e-4 -0.05698406 -0.9983745 -0.001115977 -0.05905681 -0.9982547 1.38564e-5 -0.06695425 -0.997756 5.40535e-4 -0.07315087 -0.9973206 -8.3473e-4 -0.07248759 -0.9973692 -5.12073e-4 -0.08158147 -0.9966666 4.6546e-4 -0.08735871 -0.9961769 -4.83857e-4 -0.08984839 -0.9959555 1.0382e-4 -0.09951603 -0.995036 1.57691e-5 -0.1017335 -0.9948115 -5.40874e-4 -0.1100432 -0.9939267 6.94191e-4 -0.1239657 -0.9922863 -6.14682e-4 -0.1234095 -0.9923558 -4.53031e-4 -0.1364676 -0.9906445 4.80586e-4 -0.1496273 -0.9887417 -0.0012573 -0.1514435 -0.9884657 -7.4125e-4 -0.1599094 -0.9871317 2.90067e-4 -0.1710561 -0.985261 7.53366e-4 -0.1816194 -0.9833689 5.99298e-5 -0.1923569 -0.981325 -3.34718e-4 -0.1881903 -0.9821321 -9.97513e-4 -0.2053737 -0.9786836 4.63593e-4 -0.2238239 -0.9746297 -6.72558e-5 -0.210398 -0.9776154 -9.46089e-4 -0.2375919 -0.9713651 1.83115e-4 -0.2679586 -0.9634301 -8.54538e-4 -0.2669811 -0.9637017 5.49344e-4 -0.2953959 -0.9553749 -4.2727e-4 -0.3343345 -0.9424542 -8.85048e-4 -0.3203632 -0.9472948 -2.13637e-4 -0.3461452 -0.938181 6.10378e-5 -0.3645558 -0.9311814 -3.96754e-4 -0.4124685 -0.910971 -0.001281797 -0.3771873 -0.926137 3.05192e-5 -0.3892068 -0.9211502 6.40896e-4 -0.4107517 -0.9117472 5.49337e-4 -0.4521143 -0.8919598 -5.79868e-4 -0.5009953 -0.86545 0 -0.5792236 -0.8151674 -0.001556456 -0.5477646 -0.836632 9.76625e-4 -0.6001608 -0.7998788 9.15577e-4 -0.654218 -0.7563061 -1.52598e-4 -0.7823814 -0.6227983 -0.001342773 -0.7068931 -0.7073203 -4.88312e-4 -0.7571825 -0.6532034 1.22077e-4 -0.7991862 -0.6010836 2.13637e-4 -0.8448682 -0.5349743 -6.10388e-4 -0.8913545 -0.4533072 1.52598e-4 -0.9290874 -0.3698588 -0.001037597 -0.9310615 -0.3648619 6.71431e-4 -0.9611789 -0.2759262 0 -0.9812763 -0.1926051 -3.0519e-4 -0.9962417 -0.08661377 -7.32463e-4 -0.9915444 -0.1297684 6.10388e-5 -0.9974967 -0.07071346 1.52597e-4 -0.9953064 -0.09677475 2.4415e-4 -0.930595 -0.3660487 0.001220762 -0.997134 0.07565557 3.05186e-5 -0.9934081 0.114631 3.96753e-4 -0.9742278 0.225566 -5.79861e-4 -0.9696831 0.2443664 1.22076e-4 -0.8726038 0.4884287 3.05192e-4 -0.7997214 0.6003709 7.32457e-4 -0.8572208 0.514949 -4.88306e-4 -0.5898146 -0.8075387 -1.22077e-4 -0.779085 0.6269181 -3.66226e-4 -0.02336502 -0.999727 1.56481e-4 -0.02260196 -0.9997446 -1.17814e-5 -0.02202391 -0.9997574 -3.19364e-4 -0.02197092 -0.9997586 -2.61685e-4 -0.02097219 -0.9997801 1.98259e-4 -0.02068299 -0.9997861 1.4076e-4 -0.02044665 -0.999791 3.34827e-6 -0.02034521 -0.9997931 -8.92729e-5 -0.02031576 -0.9997937 -1.24524e-4 -0.02040547 -0.9997919 1.55297e-5 -0.02046072 -0.9997907 1.17625e-4 -0.02050995 -0.9997897 7.15328e-5 -0.0206229 -0.9997874 -4.06685e-6 -0.02073502 -0.999785 -5.25816e-5 -0.02085906 -0.9997825 -7.20108e-5 -0.02102786 -0.999779 -4.282e-5 -0.02122187 -0.9997748 5.87047e-5 -0.02143812 -0.9997702 7.2035e-5 -0.0216434 -0.9997658 5.55226e-6 -0.02171975 -0.9997641 9.42469e-7 -0.02169024 -0.9997648 -2.90214e-6 -0.02153414 -0.9997681 -4.81695e-5 -0.02132099 -0.9997727 -1.52338e-4 -0.0212599 -0.999774 -1.9275e-4 -0.02074068 -0.999785 2.76249e-5 -0.01841026 -0.9998306 2.3228e-4 -0.01611739 -0.9998701 -4.99273e-6 -0.01482456 -0.9998902 -3.25029e-4 -0.01239514 -0.9999232 4.08877e-5 -0.004682838 -0.999989 -1.70809e-4 -0.00444591 -0.9999902 -2.07334e-4 6.2621e-5 -1 1.25961e-4 0.004477083 -0.9999901 1.31504e-4 0.007831096 -0.9999694 -8.03268e-5 0.006792902 -0.999977 1.11403e-4 0.002750575 -0.9999963 -8.69256e-5 0.002646744 -0.9999965 -7.7135e-5 0.002935945 -0.9999957 -1.18952e-4 0.007461786 -0.9999722 1.98696e-4 -3.96753e-4 -1 0 -0.02276712 -0.9997408 3.0519e-5 -0.02041697 -0.9997915 -2.44149e-4 -0.04382526 -0.9990392 -1.83114e-4 -0.04866218 -0.9988152 1.84664e-4 -0.04855543 -0.9988205 1.52594e-4 -0.04446625 -0.999011 9.15572e-5 -0.03540194 -0.9993732 3.05189e-4 0.06353169 0.9979639 0.005648612 0.0675829 0.9977138 4.11037e-5 0.09192454 0.7913081 -0.604468 0.09164917 0.8122385 -0.5760808 0.09366315 0.7979531 -0.5953976 0.08533114 0.937666 -0.3368993 0.08456903 0.9262619 -0.3672697 0.08331674 0.9358334 -0.3424533 0.06758433 0.9977136 1.06309e-4 0.06757771 0.9977141 2.68296e-4 0.06718951 0.9977399 8.32449e-4 0.06758314 0.9977136 1.16261e-4 0.0671752 0.9977413 1.46141e-4 0.06705981 0.9977487 7.29646e-4 0.06748956 0.9977193 0.001233518 0.0672096 0.9977385 9.28685e-4 0.06680178 0.9977663 4.02168e-4 0.06708055 0.9977473 7.68736e-4 0.06691306 0.9977587 5.31202e-4 0.06714117 0.9977432 8.47214e-4 0.06731587 0.9977312 0.001063823 0.06722664 0.9977374 9.53189e-4 0.06719779 0.9977393 9.36378e-4 0.06729632 0.9977325 0.001096129 0.06727826 0.9977338 0.001040935 0.06734883 0.9977288 0.001185894 0.06729567 0.9977325 0.001085221 0.06725996 0.997735 0.001036942 0.06728106 0.9977335 0.001036524 0.06728976 0.9977329 0.001106083 0.06753802 0.9977155 0.001579582 0.06702864 0.997751 5.16104e-4 0.06713515 0.9977439 2.17906e-4 0.06708711 0.9977471 3.56232e-4 0.0670495 0.9977496 4.50498e-4 0.06705361 0.9977493 4.18439e-4 0.06722569 0.9977378 3.35472e-6 0.06696885 0.9977549 6.10387e-4 0.06702762 0.9977511 4.67204e-4 0.06705075 0.9977496 4.18755e-4 0.06716567 0.9977418 1.92682e-4 0.06700158 0.9977528 5.04084e-4 0.06716549 0.9977419 2.05861e-4 0.06685215 0.9977627 7.64402e-4 0.06712174 0.9977449 2.96622e-4 0.06680816 0.9977659 2.25924e-4 0.06679892 0.9977665 7.58234e-5 0.06680113 0.9977664 7.78532e-5 0.06680148 0.9977663 2.21645e-4 0.06679385 0.9977669 -4.72734e-5 0.06679844 0.9977665 6.63833e-6 -0.09515917 0.5025917 -0.8592708 -0.116186 0.4223224 -0.8989688 -0.1130113 0.4604379 -0.8804689 0.06717675 0.9977412 9.68587e-5 0.06728279 0.997734 -1.06605e-4 0.0668419 0.9977442 0.006232023 0.06918752 0.9970701 -0.03262525 0.0701332 0.9950498 -0.07040792 0.07635873 0.9829282 -0.1673972 0.0814259 0.9534277 -0.2904231 0.08090513 0.9603939 -0.2666421 0.06286674 0.9980216 -9.01942e-4 0.06457775 0.9976899 -0.02108848 0.06714212 0.997061 -0.03689765 0.06622701 0.9970681 -0.03833234 0.06979751 0.9950497 -0.07074362 0.06790459 0.9961985 -0.05456781 0.07605344 0.981828 -0.1738669 0.07144618 0.9922503 -0.1016604 0.07120048 0.9937555 -0.08591061 0.07269638 0.9868342 -0.1444773 0.0719034 0.9901368 -0.1202459 0.07376396 0.9829806 -0.1682502 0.07498431 0.9788554 -0.1903143 0.07635861 0.9745037 -0.2109782 0.07788473 0.9698971 -0.2307244 0.07947069 0.9652764 -0.2488496 0.08224993 0.9451878 -0.3159985 0.07782417 0.9818668 -0.1728613 0.06891107 0.9961593 -0.05401796 0.08594089 0.91712 -0.3892366 0.08749967 0.906188 -0.4137237 0.09284043 0.8745072 -0.4760439 0.09009307 0.8614692 -0.4997541 0.08844393 0.8861789 -0.454824 0.0900917 0.8617922 -0.4991973 0.09045767 0.857578 -0.5063372 0.09082597 0.8536605 -0.5128495 0.09470081 0.8920131 -0.441978 0.1021476 0.7505276 -0.6528968 0.09933894 0.8266648 -0.5538566 0.1031548 0.8005186 -0.5903634 0.09140479 0.8294489 -0.5510534 0.09174001 0.8277049 -0.553614 0.09167939 0.8223679 -0.5615211 0.08856755 0.8485943 -0.521578 0.0900321 0.8358034 -0.5415967 0.06372392 0.4238496 -0.9034882 0.06650155 0.3939127 -0.916739 0.06033629 0.3830152 -0.9217694 0.09726387 0.7168598 -0.6903998 0.09326761 0.7552357 -0.6487837 0.09347993 0.7645947 -0.6376963 0.08518016 0.6014803 -0.7943337 0.08792597 0.6493585 -0.7553825 0.0902149 0.6079131 -0.7888618 0.07004076 -0.3604277 -0.9301539 0.07937914 -0.4915038 -0.8672503 0.07675623 -0.487883 -0.8695279 0.07385599 0.5284062 -0.8457733 0.07611495 0.5466302 -0.8339077 0.07617521 0.4999306 -0.8627091 0.08774232 0.4996584 -0.8617673 -0.01098662 -0.9999397 -1.52593e-4 -0.01052892 -0.9999446 -1.83112e-4 -0.02111935 -0.9997228 -0.01040709 0.08334922 -0.3624823 -0.9282562 0.06936937 -0.2100309 -0.9752307 0.07516783 -0.2087487 -0.9750764 0.07889157 0.6976944 -0.7120384 0.08182305 0.6782374 -0.7302734 0.07873958 0.7605088 -0.6445358 0.08148497 0.4975163 -0.863619 0.07733666 0.3771613 -0.922913 0.1014755 -0.4880594 -0.8668914 0.1039172 -0.625365 -0.7733822 0.09808874 -0.4939534 -0.8639378 0.05569779 0.33907 -0.9391109 0.05792528 0.3906449 -0.9187173 0.0705288 0.3807823 -0.9219711 0.06912517 0.459461 -0.885504 0.1066649 -0.6692271 -0.7353623 0.1027584 -0.7468376 -0.6570193 0.1044676 -0.6232958 -0.7749767 0.05408036 0.2679604 -0.9619109 0.05438429 0.3285031 -0.9429359 0.09253531 0.1743888 -0.9803193 0.08978623 0.1604678 -0.9829489 0.09201639 0.1358119 -0.9864523 0.1058716 -0.5813328 -0.8067487 0.05139321 0.3233441 -0.944885 0.04947173 0.2702788 -0.9615103 0.07052922 0.1012923 -0.9923536 0.0712617 0.2442736 -0.9670844 0.07794475 0.2481476 -0.9655814 0.1032164 -0.7599014 -0.6417915 -0.01840281 -0.9998249 -0.003418087 -0.01849472 -0.9998144 -0.005401909 0.04919689 0.3043679 -0.9512833 0.09732687 -0.845331 -0.5253028 0.1028192 -0.7454317 -0.6586045 0.04965442 -0.01568675 -0.9986433 0.0501731 0.004089534 -0.9987323 0.05533069 -0.01440489 -0.9983643 -0.6086423 -0.01443552 -0.7933133 -0.3982139 -0.02829122 -0.9168563 -0.3964428 -0.09018385 -0.9136192 0.04635852 0.2332882 -0.971302 0.09973692 -0.8254851 -0.5555421 0.08713167 0.113317 -0.989731 0.08865684 0.1433464 -0.9856935 0.08566761 0.1377945 -0.9867491 0.08707094 -0.9437721 -0.3189244 0.08850651 -0.9284337 -0.3608015 0.08932977 -0.9171948 -0.3882963 0.07767122 0.4565972 -0.8862766 0.07507681 0.5066158 -0.858897 0.07748889 0.4230303 -0.9027962 0.06314408 0.09796643 -0.9931846 0.06219714 0.008972465 -0.9980236 0.0405597 0.1257992 -0.9912263 0.04467999 0.2201346 -0.9744458 0.07464832 -0.06732386 -0.9949347 0.08661371 -0.1874494 -0.9784482 0.08310335 -0.1981602 -0.9766404 0.05868744 0.256052 -0.9648799 0.03827059 0.1328485 -0.9903973 0.01630687 -0.999867 -6.01293e-4 0.06187796 -0.008434295 -0.9980481 0.04260498 0.2139406 -0.9759172 -0.01852518 -0.9998109 -0.005920708 0.05713093 0.004364132 -0.9983572 0.05609399 0.09918689 -0.9934866 0.03344923 0.1186898 -0.9923679 0.0315265 0.02313369 -0.9992353 0.07565748 0.3492942 -0.9339538 0.07428294 0.4915373 -0.8676827 -0.01846373 -0.9998212 -0.004089474 0.05802649 -0.002430081 -0.9983122 0.0626192 -0.007011294 -0.998013 0.04068225 0.2015497 -0.9786331 0.03915578 0.1876305 -0.981459 0.07898283 0.1610786 -0.9837762 0.07892274 0.1621488 -0.9836051 0.07904487 0.1313244 -0.9881831 0.03906404 0.186714 -0.9816374 0.0448634 0.1148747 -0.9923665 0.05154645 1.52595e-4 -0.9986706 0.05261456 -0.003296017 -0.9986095 0.05459779 7.32447e-4 -0.9985082 0.07895392 0.1655682 -0.9830328 0.07486248 0.1535703 -0.9852978 0.07345938 0.1157588 -0.9905572 0.04464906 0.00766021 -0.9989734 0.03964412 0.01293998 -0.9991301 0.05597186 0.002319395 -0.9984297 0.05459916 -0.003448665 -0.9985024 0.07510811 0.3351331 -0.9391723 0.07407057 0.2614597 -0.9623682 0.0375995 0.1856782 -0.981891 0.07431352 0.1549749 -0.9851195 0.07422304 0.1564726 -0.9848896 0.06790453 0.007568657 -0.9976631 0.06543332 0.01089537 -0.9977975 0.07468086 0.08664447 -0.9934362 0.036776 0.1790276 -0.9831565 0.07605355 0.2260244 -0.9711483 0.06393766 0.04760992 -0.9968177 0.06262451 0.01211595 -0.9979637 0.06689715 0.05133259 -0.9964386 0.08459991 0.7314597 -0.6766163 0.0780999 0.8131059 -0.5768529 0.07281917 0.06482309 -0.9952364 0.07275789 0.1137758 -0.9908387 0.0734589 0.1474367 -0.9863398 0.07022356 0.0891757 -0.9935373 0.07220798 0.141364 -0.9873207 0.03521835 0.01858574 -0.9992068 0.07232928 0.1528375 -0.985601 0.07419157 0.1599804 -0.9843282 0.07800781 0.1101754 -0.9908463 0.07034647 0.03592097 -0.9968757 0.05713129 -0.002533018 -0.9983636 0.05331629 -0.01373344 -0.9984833 0.03494453 -0.003326594 -0.9993838 0.03732502 -0.00463891 -0.9992925 0.03134334 0 -0.9995087 0.06781429 0.1371851 -0.9882214 0.06781286 0.1371211 -0.9882304 0.06818002 0.1214056 -0.9902586 -0.0185554 -0.9997962 -0.007965385 -0.01852494 -0.9997674 -0.01104778 -0.7337466 -0.5224 -0.4344126 -0.8426005 -0.5385392 -3.05191e-5 -0.7698045 -0.633813 -0.07538127 0.0289933 0.02630764 -0.9992334 0.03381514 0.1163388 -0.9926338 0.03500503 0.08499473 -0.9957664 0.03592085 0.1742024 -0.9840546 0.03570705 0.1796951 -0.9830742 0.03515815 0.1792394 -0.9831771 -0.01840299 -0.9996234 -0.02035623 -0.007080256 0.003051817 -0.9999703 -0.009247124 0.01815861 -0.9997923 0.01913517 0.01895201 -0.9996374 0.03292965 -0.001586914 -0.9994564 0.02884018 -0.002868711 -0.99958 0.03396773 -0.08127236 -0.996113 0.03982686 -0.07312279 -0.9965274 0.04098689 -1.83114e-4 -0.9991597 -0.1774693 -0.9787213 -0.1030024 -0.1569314 -0.9600225 -0.2317959 -0.1551284 -0.9571083 -0.2447018 -0.1629388 -0.007751703 -0.9866058 -0.1544878 0.02191269 -0.9877517 -0.1654117 -0.004608333 -0.9862139 -0.5820563 -0.4352909 -0.6868277 -0.1355343 0.0474568 -0.9896355 -0.1261041 0.05499505 -0.9904915 -0.1362974 0.1083726 -0.9847226 0.04089599 0.00613439 -0.9991447 0.04373395 0.01086479 -0.9989842 0.02499526 0.01339793 -0.9995978 -0.1913269 -0.9587102 -0.2104017 -0.1602537 -0.008880913 -0.987036 -0.1479554 -0.01098674 -0.9889331 -0.100835 0.004944086 -0.9948909 -0.09833085 0.002716124 -0.9951501 -0.04779297 0.01065117 -0.9988006 -0.1507046 -0.01525968 -0.9884611 -0.1489323 -0.01370298 -0.9887524 -0.1533603 -0.01193308 -0.9880984 -0.1469787 -0.06625634 -0.9869182 -0.1603496 -0.182873 -0.9699719 -0.09024572 0.03155696 -0.9954195 0.03466975 -0.232129 -0.9720669 0.03308266 -0.1994116 -0.9793573 0.04590052 -0.0557276 -0.9973904 0.03494387 -0.2501924 -0.9675654 0.0350365 -0.4078336 -0.9123838 0.02902311 -0.3845032 -0.9226673 -0.153602 -0.02005094 -0.9879294 -0.1437131 -0.01654118 -0.9894812 0.01293992 -0.9988468 -0.04623579 0.02072262 -0.9997848 -9.76621e-4 0.01422196 -0.9998741 0.007049918 -0.1599796 -0.9782804 -0.1318107 -0.227486 -0.8688051 -0.4398043 -0.2405822 -0.7737514 -0.5860282 -0.1845771 -0.8811972 -0.4352273 -0.3690709 -0.2960075 -0.881003 -0.1596451 -0.06946134 -0.9847277 -0.2425691 -0.8928486 -0.3794492 -0.2029858 -0.9404001 -0.2728451 -0.2315209 -0.8922682 -0.3876282 0.02270621 -0.347033 -0.937578 -0.1697773 -0.1863797 -0.9676975 -0.2140291 -0.9510607 -0.2228795 -0.0444048 -0.2862356 -0.9571298 -0.02548384 -0.4323713 -0.9013355 -0.05868917 -0.426359 -0.9026482 -0.2350308 -0.9091767 -0.3437414 -0.2354236 -0.9159978 -0.3248444 -0.1093199 0.007171988 -0.9939808 -0.1048636 0.006561577 -0.9944649 -0.05020445 0.02163827 -0.9985045 0.01055973 -0.314809 -0.9490964 0.006500542 -0.1497579 -0.9887013 0.02545273 -0.1703261 -0.9850591 -0.2702463 -0.2277332 -0.9354703 -0.02334725 -0.9997211 -0.003570735 -0.03061062 -0.9995302 -0.001556456 -0.009949207 -0.02023416 -0.9997459 -0.02679586 -0.1412125 -0.9896167 -0.05755805 -0.02288889 -0.9980798 -0.2350274 -0.9221339 -0.3072966 -0.01135313 -0.2947853 -0.9554961 -0.2029208 -0.1795127 -0.9625998 -0.21919 -0.9473513 -0.233412 -0.181377 -0.8060795 -0.5633278 -0.1900728 -0.7920311 -0.5801371 -0.1878172 -0.6768622 -0.711746 -0.07288002 -0.1432881 -0.986994 -0.1169197 -0.03918683 -0.992368 -0.1290333 -0.1575683 -0.9790417 -0.08633875 -0.9956887 -0.03390681 -0.1019334 -0.983658 -0.1484138 -0.05914545 -0.9975997 -0.03601217 -0.1568989 -0.1455764 -0.9768267 -0.07407045 -0.9851038 -0.1551909 -0.1210996 -0.9444121 -0.3056483 -0.1709381 -0.887377 -0.4281847 -0.1230205 -0.1198466 -0.985141 0.03039735 -0.9781491 -0.2056707 0.03232008 -0.9239453 -0.3811572 0.03854548 -0.9779202 -0.2053928 -0.09830099 -0.1005899 -0.9900599 0.002288877 -0.9329265 -0.3600597 8.85063e-4 -0.8679723 -0.496612 0.01870816 -0.9273217 -0.3737975 -0.223858 -0.9433472 -0.2449162 -0.07977652 -0.0857582 -0.993117 -0.1247003 -0.9917735 -0.02890139 -0.1395347 -0.9898971 -0.02517849 -0.08170086 -0.9548959 0.2854799 7.32467e-4 -0.9990549 -0.04345971 -0.008362233 -0.9837867 -0.1791477 -0.06595164 -0.07443588 -0.9950427 0.02179026 -0.998568 -0.04886025 0.0283212 -0.9983543 -0.04986733 -0.1569011 -0.9210504 0.3564382 -0.01532071 -0.9990547 -0.04068243 -0.06393808 -0.07275819 -0.9952982 -0.4171399 -0.3890315 -0.8213701 -0.0202949 -0.7875649 -0.6158974 -0.02032595 -0.8719711 -0.4891352 -0.0463891 -0.7880964 -0.6138014 -0.1725555 -0.942982 -0.284622 -0.02989649 -0.999553 -1.08027e-4 -0.1256471 -0.9819517 -0.1413644 -0.1373373 -0.9811992 -0.1355977 -0.1560168 -0.9461416 -0.2836807 -0.5375107 -0.8416688 -0.05173063 -0.5772666 -0.7329134 -0.3600019 -0.0167244 -0.9379412 -0.346391 -0.04483199 -0.8750332 -0.4819824 -0.5756183 -0.796423 -0.1854027 -0.2282497 -0.9383907 -0.2594705 -0.2315196 -0.9333115 -0.2744603 0.007110834 -0.9817565 -0.1900095 -0.6311084 -0.07761055 -0.7718024 -0.3973272 -0.1565931 -0.9042177 -0.525757 -0.8502999 -0.02386611 -0.03860706 -0.9414334 -0.3349815 -0.1453623 -0.9448705 -0.2934104 -0.18455 -0.5871908 -0.7881296 -0.1831166 -0.4587377 -0.8694987 -0.1835726 -0.4605337 -0.8684526 -0.4470526 -0.8868415 -0.1168599 -0.1614784 -0.88424 -0.4382287 -0.1735329 -0.8023228 -0.5711082 -0.1359312 -0.8807452 -0.4536636 -0.03524971 -0.9986502 -0.03814899 -0.4003428 -0.216804 -0.8903492 -0.6482356 -0.1292809 -0.7503846 -0.3746235 -0.8511506 -0.3676956 -0.1069371 -0.9942646 0.001586914 -0.1171312 -0.9928073 -0.02478122 -0.1042526 -0.9945501 0.001220703 -0.1738661 -0.322249 -0.9305516 -0.1785354 -0.3256667 -0.9284753 -0.3874747 -0.8700784 -0.3046755 -0.3779189 -0.9254939 -0.02526986 -0.3632089 -0.9289126 -0.07211685 -0.3309213 -0.9436583 3.05193e-4 -0.06348031 -0.9435071 -0.3252147 -0.02694803 -0.9851142 -0.1697757 0.01992863 -0.9794958 -0.200477 -0.5614014 -0.8274377 -0.01324534 -0.4103279 -0.9119076 -0.007446587 -0.4134103 -0.9101985 -0.02511709 -0.5689657 -0.820015 -0.06207561 -0.6964059 -0.7175248 -0.01330614 -0.04879933 -0.9855696 -0.1620846 -0.4162465 -0.9081186 -0.04538148 -0.1452095 0.02218729 -0.9891521 -0.1651412 9.46106e-4 -0.9862695 -0.4189322 -0.9055858 -0.06640899 0.03839302 -0.9942822 -0.09964489 0.03790521 -0.9974079 -0.06116104 0.0364089 -0.9981789 -0.04809761 -0.4219944 -0.9024339 -0.08679771 -0.4255623 -0.8985518 -0.1072451 0.01886099 -0.8637304 -0.5036011 -0.07257401 -0.8774192 -0.4742031 -0.1653539 0.001464903 -0.9862333 -0.1450851 -0.004028439 -0.9894111 -0.4295002 -0.8940368 -0.1273882 -0.07529038 -0.6823744 -0.7271153 -0.07648122 -0.7894417 -0.6090424 -0.112006 -0.6847018 -0.7201653 -0.7081389 -0.7026149 -0.06979757 -0.5783907 -0.80487 -0.1328479 -0.1102662 -0.79164 -0.6009555 0.03433352 -0.7924493 -0.6089707 0.01971548 -0.7905133 -0.6121274 0.02108836 -0.707453 -0.7064459 -0.1033392 -0.8791158 -0.4652706 -0.1461264 -0.7950891 -0.5886259 -0.4309594 -0.8900573 -0.1485667 -0.1776213 -0.5408905 -0.8221242 -0.1869617 -0.7049977 -0.6841225 -0.233748 -0.9278811 -0.2905141 -0.4342588 -0.8820682 -0.1826884 -0.1571747 -0.01052916 -0.9875147 -0.2673163 -0.8317966 -0.4864736 -0.269792 -0.8150221 -0.5127879 -0.7029798 -0.7098771 -0.04352039 -0.2722949 -0.7863042 -0.5546002 -0.4493663 -0.8522518 -0.2678375 -0.4454954 -0.8601964 -0.2481858 -0.4419417 -0.8673424 -0.228921 -0.4541845 -0.84199 -0.2911517 -0.0363484 -0.5628054 -0.8257898 -0.04349046 -0.6828463 -0.7292665 -0.06918746 -0.5597566 -0.8257638 -0.004364132 0.02154612 -0.9997584 -0.5829819 -0.7852342 -0.2086612 -0.446859 -0.8416221 -0.3032977 -0.3643106 -0.7568516 -0.5426357 -0.318432 -0.8095694 -0.4931516 -0.3229851 -0.8106826 -0.4883384 -0.7125819 -0.6952472 -0.09411972 -0.7166219 -0.6872625 -0.1188418 -0.4425035 -0.6734148 -0.5922021 -0.5814215 -0.761668 -0.2860261 -0.3461773 -0.8100362 -0.4732892 -0.3447437 -0.8101294 -0.4741752 -0.4524564 -0.8023663 -0.3892194 -0.4554133 -0.7889009 -0.4125943 -0.4716444 -0.690101 -0.5489191 -0.4680808 -0.7177625 -0.5154779 -0.438402 -0.8741794 -0.2088398 -0.445004 -0.8339132 -0.3264359 -0.4474392 -0.8237997 -0.3480693 -0.1286374 0.1480779 -0.980574 -0.1032153 0.06940025 -0.9922351 -0.08993834 0.07477056 -0.9931368 -0.1153638 0.06232088 -0.9913665 -0.1310793 0.1367864 -0.9818899 -0.2732691 -0.7611494 -0.588197 -0.2919144 -0.7905646 -0.538325 -0.5163905 -0.5608879 -0.6471056 -0.5383585 -0.6079728 -0.5835574 -0.7327959 -0.4887341 -0.473444 -0.7361829 -0.597626 -0.3176128 -0.7376796 -0.584046 -0.3387021 -0.5699459 -0.6934265 -0.4408192 -0.5774288 -0.7309113 -0.3637923 -0.3621684 -0.6599724 -0.6582329 -0.2646937 -0.8449873 -0.4646866 0.04067242 -0.9991233 -0.009922742 0.03354012 -0.8612704 -0.507039 0.04287981 -0.9238549 -0.3803336 -0.09128147 -0.9444019 -0.3158687 -0.1404487 -0.3003382 -0.9434359 -0.08850586 -0.2878578 -0.9535747 -0.1006224 -0.4285226 -0.8979107 -0.1515579 -0.6904646 -0.707311 -0.01049858 -0.5725414 -0.8198086 -0.01693826 -0.6867796 -0.7266685 0.008667528 -0.5903686 -0.8070873 0.004303157 -0.6955009 -0.7185124 -0.1602845 -0.3920136 -0.9058887 -0.1875406 -0.5878002 -0.7869686 -0.2583143 -0.8663481 -0.4274517 -0.2619443 -0.8555077 -0.4466451 -0.1112126 -0.08762109 -0.9899265 -0.7282365 -0.4585735 -0.5092956 -0.4919744 -0.5126667 -0.7036578 -0.005920588 0.01174968 -0.9999135 -0.04876965 0.01617515 -0.9986791 0.04626691 0.01617509 -0.9987982 -0.1435302 0.03912514 -0.9888723 0.03567659 0.1843038 -0.9822217 0.03512734 0.1420049 -0.9892425 0.03549337 0.2014242 -0.9788608 -0.002471983 0.2574567 -0.9662867 0.01562571 0.2705817 -0.9625702 0.02722299 0.123816 -0.9919317 0.03537178 0.2056385 -0.9779886 0.03506624 0.2134189 -0.9763312 -0.02835255 0.2480926 -0.9683213 -0.01757884 0.1082503 -0.9939683 -0.06231933 0.2417697 -0.9683305 -0.05499488 0.1040386 -0.9930517 -0.04886132 0.01751804 -0.998652 -0.101048 0.1011396 -0.9897273 -0.1618739 -0.008118093 -0.9867781 -0.1434077 -0.001098632 -0.9896631 -0.162606 -0.008636891 -0.9866533 -0.06668376 0.3766335 -0.9239592 -0.03610384 0.3816694 -0.9235935 -0.01165819 0.3896046 -0.9209085 -0.1417623 0.01388627 -0.9898033 -0.1365407 0.09851437 -0.9857239 -0.09854638 0.01709073 -0.9949858 0.0330823 0.2301113 -0.9726019 0.03433388 0.2222699 -0.9743805 0.03262525 0.2360677 -0.9711889 -0.1308031 0.2291038 -0.9645736 -0.1582408 0.006378412 -0.98738 -0.1541502 0.07116973 -0.985481 0.03509992 0.2950686 -0.9548313 -0.1432855 0.1778023 -0.9735788 -0.1497864 0.1319939 -0.9798682 0.03442579 0.3293035 -0.9435964 0.03482264 0.3132513 -0.9490317 0.03250283 0.3046114 -0.951922 -0.1029707 0.2375895 -0.9658926 -0.1304388 0.2899623 -0.9481074 0.006866812 0.4013888 -0.915882 -0.01800626 0.5114697 -0.8591127 -0.1441723 0.2502568 -0.957385 0.03259408 0.3701934 -0.9283828 0.03369265 0.3491342 -0.9364669 -0.12165 0.3231388 -0.9385002 -0.02160745 0.6231079 -0.7818375 5.49343e-4 0.5196477 -0.8543805 -0.06030642 0.7271264 -0.6838498 -0.04232949 0.6212092 -0.7825008 -0.06573915 0.6209514 -0.7810876 0.03134268 0.4591233 -0.8878195 0.03219801 0.4354819 -0.8996216 0.02819955 0.4347742 -0.900098 -0.100897 0.3731601 -0.9222643 -0.1203079 0.3781976 -0.9178739 0.03012198 0.4778928 -0.8779017 -0.04068142 0.7253381 -0.6871897 -0.04077363 0.5064358 -0.8613132 0.02386617 0.5543239 -0.8319589 -0.1115775 0.4937671 -0.8624063 0.02890187 0.497955 -0.8667212 -0.1084337 0.5256581 -0.8437569 -0.1039193 0.5527107 -0.8268686 -0.02240121 0.7244387 -0.6889752 -0.003540158 0.6271333 -0.7789039 0.02777206 0.5735095 -0.818728 0.02920693 0.5515444 -0.8336341 -0.08664375 0.6220406 -0.7781763 -0.1001639 0.5802304 -0.8082697 -0.09955412 0.6191769 -0.7789152 0.01196366 0.6337707 -0.7734286 0.01532047 0.531579 -0.8468703 0.0257883 0.5884315 -0.8081358 -0.09409022 0.6541453 -0.7504939 0.02020388 0.6290681 -0.7770877 0.02560514 0.6049716 -0.7958353 -0.005554497 0.7245012 -0.6892513 -0.02029496 0.8133555 -0.5814129 -0.03573787 0.8162032 -0.5766586 -0.05154645 0.8192811 -0.5710705 -0.03927791 0.8954578 -0.4434105 0.02340793 0.6715371 -0.7406013 0.02670401 0.6490752 -0.7602555 -0.08890211 0.6806674 -0.7271785 -0.08762049 0.7096926 -0.6990415 -0.07498562 0.7300801 -0.6792351 -0.02725315 0.892121 -0.450974 -0.0844472 0.7367996 -0.6708167 0.009766042 0.7256823 -0.6879607 0.01822018 0.6842803 -0.7289915 -0.07806766 0.7618466 -0.643036 -0.005340814 0.8104696 -0.5857563 -0.01504594 0.8884459 -0.4587348 -0.02359145 0.953029 -0.3019588 -0.07181191 0.8071441 -0.5859707 -0.0605188 0.8231232 -0.5646288 -0.07266592 0.7828758 -0.6179201 0.01760929 0.7354099 -0.6773938 0.01815891 0.7028582 -0.7110983 -0.06930881 0.8255715 -0.560025 0.01690739 0.753508 -0.6572213 -0.05417156 0.8670509 -0.4952658 -0.04510676 0.8958182 -0.4421257 -0.01513755 0.950432 -0.3105643 0.01614451 0.7717337 -0.6357411 0.008758902 0.8074071 -0.5899297 0.01644986 0.7872149 -0.6164594 -0.06173962 0.846898 -0.5281591 0.01635831 0.8139812 -0.5806609 0.01651084 0.8003961 -0.5992442 0.01562577 0.8283489 -0.5599946 -0.003936886 0.9887476 -0.149542 9.76621e-4 0.9878216 -0.1555879 -0.006378471 0.947223 -0.3205121 0.009155631 0.8785181 -0.4776213 0.01574778 0.8567289 -0.5155267 0.01495426 0.8417451 -0.5396679 -0.05346977 0.8901863 -0.4524483 -0.04672449 0.9109603 -0.4098391 -0.03128224 0.9324256 -0.3600056 0.006439507 0.9865339 -0.1634304 0.002716183 0.9430658 -0.3325954 0.01144462 0.9377272 -0.3471843 -0.03521877 0.9242947 -0.3800516 0.01620578 0.9048409 -0.4254413 0.01626652 0.8861764 -0.4630628 0.01147514 0.9993488 -0.03421193 0.01458787 0.9992093 -0.03698849 -0.03091621 0.9580678 -0.284869 -0.02682644 0.9529342 -0.3019883 -0.03381502 0.9506971 -0.3082723 0.01690769 0.9268124 -0.3751441 -0.02380472 0.9649468 -0.2613639 -0.01821964 0.9707078 -0.2395716 -0.001892149 0.9944592 -0.1051071 0.00250256 0.9972454 -0.07413113 -0.004608392 0.9932558 -0.1158518 0.01153606 0.9851458 -0.1713323 0.01843321 0.999056 -0.0393384 -0.01086485 0.9813773 -0.191783 -0.00576806 0.9886041 -0.1504284 0.01709067 0.9480155 -0.3177651 -0.0137642 0.976589 -0.2146732 -0.0106815 0.9900566 -0.1402639 0.0116887 0.9999204 -0.004760921 0.01510673 0.9998859 -1.22075e-4 -0.01208567 0.9859599 -0.1665444 0.01794505 0.9655842 -0.2594708 0.01742631 0.9833833 -0.180703 0.02087634 0.9997821 -1.74401e-4 0.02237045 0.9979732 -0.05957317 0.01925736 0.9850887 -0.1709668 0.02249282 0.9987793 -0.04397851 0.0239101 0.9997142 2.4727e-4 -0.002685606 0.8840111 -0.4674583 0.01303148 0.9999151 -1.52594e-4 -9.15555e-5 -1 0 -0.2867262 -0.006286859 -0.957992 0.02789443 -0.9973039 0.06787449 0.03250247 0.4037027 -0.9143127 0.02017295 0.4174976 -0.9084541 0.0268566 0.2874878 -0.9574077 0.03506672 0.2956717 -0.9546459 -0.06784391 0.503687 -0.8612182 0.03665286 0.1282697 -0.9910618 0.03775227 0.1412735 -0.9892506 0.009796559 0.1140799 -0.9934233 -0.1439887 2.74671e-4 -0.9895793 -0.04751843 0.00363177 -0.9988639 0.03198415 -0.01977646 -0.9992927 0.03225886 -0.08038783 -0.9962416 0.02945065 -0.005127131 -0.9995531 0.04037702 -0.2412246 -0.9696291 0.03689795 -0.1155769 -0.992613 0.0423603 -0.2176308 -0.9751116 0.02090531 -0.02774149 -0.9993966 0.03479188 -0.7163473 -0.6968761 0.02291995 -0.6139864 -0.7889838 0.04492413 -0.8615556 -0.5056718 -0.0355848 -0.9993657 -0.001464843 -0.04831141 -0.998121 -0.03769081 0.04892194 -0.9258248 -0.3747735 0.04886132 -0.953117 -0.2986311 0.04242157 -0.9785345 -0.2016703 -0.2589575 0.9301105 -0.2604529 -0.142953 0.02514797 -0.9894101 -0.1567773 0.001556456 -0.9876328 -0.5964808 -0.6053621 -0.5270176 -0.4258022 -0.8184912 -0.3857001 -0.331378 -0.0070194 -0.943472 -0.6409665 -0.2167176 -0.7363393 -0.3904321 -0.01223814 -0.9205504 -0.1041142 0 -0.9945654 -0.1601346 -0.02835237 -0.986688 -0.182319 -0.2427766 -0.9527955 -0.1463693 -0.08868831 -0.9852464 -0.2004186 -0.3841433 -0.9012582 -0.1979774 -0.1753017 -0.9644036 -0.2740582 -0.008514702 -0.9616755 -0.22294 -0.02780264 -0.9744356 -0.1911409 0.004059016 -0.9815542 -0.4496667 -0.1599195 -0.8787637 -2.44148e-4 -1 0 -0.4925536 -0.2812063 -0.8235983 -0.5112574 -0.4091097 -0.7558076 -0.5117139 -0.5411648 -0.6673003 -0.4968215 -0.6429167 -0.5829465 -0.462332 -0.7503702 -0.4724339 -0.4797121 -0.7049797 -0.522379 -0.1518608 -0.09009104 -0.9842876 -0.5969493 -0.6554539 -0.4626356 -0.5776929 -0.7097789 -0.4030941 -0.1383718 -0.005951106 -0.9903625 -0.6210677 -0.04922759 -0.7822095 -0.6395826 -0.1033061 -0.7617493 -0.6635591 -0.1782349 -0.7265822 -0.6704468 -0.2017627 -0.7139979 0.08365225 0.3799601 -0.9212127 0.06064218 0.423824 -0.9037123 0.09683704 0.1709069 -0.980517 0.09284007 0.1643471 -0.9820238 0.0656464 0.4417631 -0.8947267 0.09509813 -0.8977252 -0.4301695 0.09180295 -0.8963913 -0.4336531 0.09204739 -0.8892217 -0.4481207 0.08102953 0.5661998 -0.8202756 0.0794419 0.5569481 -0.8267394 0.0411399 -0.9901958 -0.133491 0.04477107 -0.982981 -0.1781689 -0.406125 -0.7732153 -0.4870325 -0.4497687 -0.8139297 -0.3677318 -0.4582764 -0.7752795 -0.4346545 -0.4613645 -0.7592052 -0.4590756 -0.4650838 -0.7379265 -0.4890415 -0.4738749 -0.6678258 -0.5739786 -0.4382291 -0.657481 -0.6129226 -0.7200777 -0.6791815 -0.1421294 -0.7235016 -0.6696953 -0.1674925 -0.7260112 -0.6607621 -0.1905287 -0.7295835 -0.6499292 -0.2128384 -0.3387659 -0.8112682 -0.4765308 -0.3285423 -0.8114827 -0.4832761 -0.3336968 -0.8116273 -0.479487 -0.7314032 -0.640119 -0.2351538 -0.7325862 -0.6311704 -0.2548364 -0.5566428 -0.65226 -0.5144956 -0.7364848 -0.5310919 -0.418965 -0.7357717 -0.6084125 -0.2974461 -0.734965 -0.6197547 -0.2751922 -0.7375329 -0.5710799 -0.3604347 -0.3119081 -0.8072074 -0.5011284 -0.1086493 -0.5621384 -0.8198754 0.06903445 0.1375196 -0.9880905 0.05841392 -0.008514881 -0.9982562 0.07684606 0.08096611 -0.9937501 0.08423215 0.1307124 -0.9878356 0.08420234 0.1495744 -0.9851586 0.07931965 0.6266528 -0.7752513 0.07822024 0.6351619 -0.768408 0.07675468 0.5735697 -0.815553 0.003326535 -0.9998602 0.01638859 0.09656304 -0.3310732 -0.9386513 0.09479272 -0.250746 -0.9634006 0.100591 -0.3660156 -0.9251562 0.0639469 -0.01012265 -0.997902 -0.01837229 -0.9998258 -0.003296017 0.1007726 -0.6256634 -0.7735569 -0.01815879 -0.9998351 -3.05191e-4 -0.01812833 -0.9998356 4.88305e-4 0.09448832 0.4090223 -0.9076193 0.09543412 0.300677 -0.9489393 0.089055 0.2749474 -0.9573261 0.07156682 0.4959017 -0.8654246 0.08740717 0.7740604 -0.6270491 0.09531116 0.2032573 -0.9744754 0.1005283 0.3133346 -0.944307 0.09967446 0.2816582 -0.9543237 -0.01010179 -0.9998372 0.01495432 0.0878961 -0.7143695 -0.6942266 0.08734524 -0.611966 -0.7860462 0.09204548 -0.7229358 -0.6847565 0.08704125 -0.9445137 -0.3167301 -0.007904291 -0.9995737 0.02810752 0.00564599 -0.9994667 0.03216701 0.08835178 -0.8978617 -0.4313216 0.0812425 -0.9456725 -0.3148071 0.08557587 -0.8880177 -0.451776 -0.008209645 -0.9999653 -0.001464903 -0.01391673 -0.9999005 0.002349972 0.05313545 -0.9985871 -7.62016e-4 0.0869801 -0.805894 -0.5856359 0.09009307 -0.8123027 -0.5762357 0.08246427 -0.7987926 -0.595928 0.08377462 -0.7090173 -0.7001973 0.09589177 -0.8743791 -0.4756744 0.06283915 -0.06729495 -0.9957523 0.06424349 -0.07074415 -0.9954237 0.08334714 0.2595023 -0.9621393 0.08002001 0.1195417 -0.9895992 0.0429396 -0.01016265 -0.999026 0.04059058 -0.008514821 -0.9991397 0.0448929 -0.01309245 -0.9989061 0.05044823 -0.01467972 -0.9986189 0.06784355 0.1373046 -0.9882028 0.06787341 0.1364793 -0.9883151 0.06164753 0.03454703 -0.9975 0.06061106 0.01113945 -0.9980993 0.06445652 0.05685728 -0.9962996 0.06763017 0.1192683 -0.990556 0.06775307 0.1188426 -0.9905988 0.06793552 0.0880782 -0.9937943 0.06876003 0.1143864 -0.9910539 0.06900274 0.1125529 -0.991247 0.06827151 0.1196049 -0.9904714 0.06994956 0.1102347 -0.9914411 0.05499643 0.6505878 -0.7574372 0.07309275 0.4172849 -0.9058316 0.05977791 -0.004321753 -0.9982024 0.06668466 -0.0689736 -0.9953873 0.07928919 -0.2051204 -0.9755198 0.06445592 0.2474778 -0.9667473 0.0716297 -0.4830656 -0.8726494 0.0786485 -0.6026974 -0.7940846 0.07358109 -0.9723024 -0.221842 0.0650047 -0.9902691 -0.1230512 0.06985884 -0.9794583 -0.189159 0.07794511 -0.703856 -0.7060534 0.07599163 -0.7832636 -0.617028 0.07077491 -0.7445256 -0.6638318 0.1036118 0.3819753 -0.9183461 0.1009256 0.3408948 -0.9346684 0.1041629 0.4206804 -0.9012093 0.08142542 -0.875812 -0.4757347 0.06924921 -0.7862183 -0.6140565 0.07037681 -0.8027413 -0.5921602 0.08704054 -0.945086 -0.3150185 0.08139443 -0.8061925 -0.5860278 0.0772736 -0.8995112 -0.4300099 0.07785421 -0.8844439 -0.4601061 0.064242 -0.9898764 -0.1265613 0.06634843 -0.9890925 -0.1315066 0.05504781 -0.9984827 -0.001434266 0.05494612 -0.998489 -8.32207e-4 0.05483722 -0.9984953 -3.16984e-4 0.05389827 -0.9985463 -6.58063e-4 0.05416411 -0.9985308 -0.001666307 0.03829061 -0.9990583 0.02041131 0.05373823 -0.9985551 -1.47406e-4 0.05347359 -0.9985692 2.68607e-4 0.05284368 -0.9986027 -4.57278e-4 0.05296188 -0.9985964 -6.01849e-4 0.0529378 -0.9985978 -5.41514e-4 0.05264663 -0.9986132 -3.3427e-4 0.05238175 -0.9986271 -2.33432e-4 0.05213701 -0.99864 -2.0298e-4 0.05272632 -0.998609 -3.82115e-4 0.05181527 -0.9986568 -2.08049e-4 0.05249273 -0.9986214 -2.69502e-4 0.05356526 -0.9985644 1.01525e-4 0.05399173 -0.998541 -9.45327e-4 0.0538547 -0.9985487 -5.23617e-4 0.05409759 -0.9985347 -0.001383125 0.05421662 -0.9985274 -0.001935422 0.05500191 -0.9984856 -0.001125752 0.06231939 -0.9909154 -0.1191759 0.06659245 -0.9818876 -0.1773763 0.05716228 -0.9976087 -0.03885078 0.05835282 -0.9967598 -0.05536198 0.04937893 -0.9987796 -0.001098632 0.05517464 -0.9984737 -0.002493977 0.0550642 -0.9984819 -0.001337647 0.05552762 -0.9984572 -1.88463e-4 0.05716252 -0.9975823 -0.0395224 0.06808876 -0.9823581 -0.1741741 0.05835151 -0.9951499 -0.07919567 0.06933933 -0.9626634 -0.2616706 0.07440519 -0.9360471 -0.3439182 0.06509685 -0.9803595 -0.1861654 0.07730394 -0.9390618 -0.3349432 0.07205557 -0.9427657 -0.3255778 0.06503558 -0.9908542 -0.1182299 0.07529133 -0.918298 -0.3886645 0.08789545 0.7940197 -0.6015042 0.07858604 0.8504996 -0.5200719 0.0907033 -0.9137783 -0.3959573 0.09815019 -0.8411439 -0.5318303 0.1045607 0.4652739 -0.8789694 0.08502525 -0.9459597 -0.3129394 0.08697974 -0.9457905 -0.3129135 0.08710104 -0.9455072 -0.3137347 0.07806706 -0.9705895 -0.2277313 0.08133339 -0.9542413 -0.2877647 0.06525021 -0.9896493 -0.1278148 0.08087468 -0.9581668 -0.2745467 0.07782328 -0.9699531 -0.2305095 0.06769084 -0.9860952 -0.1517703 0.06039667 -0.9954925 -0.07312303 0.05835294 -0.9952053 -0.07849574 0.05725377 -0.9982491 -0.01486277 0.05597394 -0.9984318 9.4846e-4 0.05598288 -0.9984316 7.4752e-4 0.05598157 -0.9984317 6.14121e-4 0.05599391 -0.9984309 7.63489e-4 0.05597758 -0.9984319 6.40363e-4 0.05594497 -0.9984338 4.88246e-4 0.05591744 -0.9984353 4.04352e-4 0.05590093 -0.9984363 3.88681e-4 0.05590468 -0.9984361 3.85074e-4 0.05587929 -0.9984375 3.41848e-4 0.05582427 -0.9984406 2.89379e-4 0.05574572 -0.998445 1.70382e-4 0.05562925 -0.9984515 3.88704e-4 0.05572378 -0.9984462 2.17058e-4 0.05575227 -0.9984447 8.80404e-5 0.05574208 -0.9984453 1.49053e-4 0.0557568 -0.9984444 2.27685e-5 0.05813884 -0.9979934 -0.02508378 0.08151632 -0.9539031 -0.2888322 0.08206665 0.616034 -0.7834329 0.1060833 0.4866527 -0.8671306 0.1056565 0.4529922 -0.8852315 0.08362293 0.6346492 -0.7682628 0.085729 0.6457601 -0.7587124 0.1056275 0.5244445 -0.8448673 0.1056581 0.5568873 -0.8238404 0.0894218 0.6654447 -0.7410717 0.106664 0.5888339 -0.8011852 0.1032463 0.5567613 -0.8242313 0.08917677 0.7050216 -0.7035567 0.0919857 0.7005137 -0.7076858 0.1058399 0.653015 -0.7499129 0.1035197 0.663448 -0.7410267 0.09003102 0.7234223 -0.6845105 0.1055368 0.7241082 -0.6815639 0.06136816 0.9980595 0.01055008 0.04814583 0.7129952 -0.699514 0.06202983 0.9980738 -9.85432e-4 0.07730549 0.5671717 -0.8199636 0.07202422 0.2269983 -0.9712283 0.04666388 -0.01245182 -0.9988331 0.06787371 0.1366631 -0.9882896 0.07211738 0.122566 -0.9898367 0.06583017 0.07993006 -0.9946244 0.07077413 0.1328198 -0.9886101 0.06790572 0.1362693 -0.9883418 0.07013362 0.1337971 -0.988524 0.06790506 0.1352303 -0.9884845 0.0694608 0.1311088 -0.9889317 0.0697053 0.1325439 -0.9887231 0.06790393 0.1346787 -0.9885599 0.06845396 0.1162467 -0.9908586 0.05110955 -0.0116285 -0.9986253 0.06802695 0.1180171 -0.9906788 0.06790518 0.1325143 -0.9888524 0.06790435 0.1289114 -0.9893286 0.05929815 0.01336723 -0.9981509 0.04992878 0.105412 -0.9931745 0.09671658 0.6225998 -0.7765406 0.08667361 0.8286185 -0.5530634 0.07916611 0.8833099 -0.4620568 0.08771163 0.8594764 -0.5035942 0.08166921 0.9116678 -0.4027306 0.08603364 0.8397974 -0.5360396 0.09091627 0.7320914 -0.6751123 0.09189426 0.7376263 -0.6689268 0.09412008 0.8193085 -0.565575 0.09305304 0.7421053 -0.663793 0.07602339 0.7324617 -0.6765505 0.08746796 0.9192987 -0.3837176 0.07883119 0.96746 -0.2404306 0.07809948 0.965669 -0.2477577 0.08679658 0.9437145 -0.3191697 0.08298188 0.9432284 -0.321612 0.06946218 0.9942007 -0.08209723 0.07510775 0.9853737 -0.1529623 0.08276671 0.9646045 -0.2503754 0.07178032 0.986888 -0.1445677 0.08151775 0.9400333 -0.3311984 0.06555438 0.9973245 -0.03234994 0.06369388 0.9979521 -0.00589019 0.06808787 0.9953471 -0.06817942 0.08789557 0.9467698 -0.3096793 0.09751051 0.8822336 -0.4606036 0.09149634 0.9334585 -0.3468195 0.0915566 0.8389636 -0.5364301 0.06204503 0.9972074 -0.04156678 0.08588194 0.9604496 -0.264879 0.06541126 0.9978122 0.009605884 0.06702065 0.9977515 5.18203e-4 0.06710207 0.9977459 7.25533e-4 0.06733989 0.9976919 0.008736789 0.06526976 0.9978603 0.003850877 0.02097076 0.9997802 -1.06034e-4 0.06635284 0.9977898 0.003600358 0.05746734 0.9983388 0.004181087 0.05514717 0.9984782 3.35705e-4 0.06112968 0.9972111 -0.04281824 0.0584535 0.9982807 0.004369974 0.01728594 0.9998507 -7.29011e-5 0.06272906 0.9979786 0.01019334 0.05821341 0.9982917 0.004978954 0.06042844 0.9981615 0.004709243 0.06677538 0.9977557 0.004969418 0.06670749 0.9977551 0.005918145 0.06545871 0.9978024 0.01027315 0.06372362 0.9979098 0.01074266 0.01306217 0.2699419 -0.962788 0.06294178 0.9979494 0.01163709 0.01748162 0.9998472 -2.01206e-4 0.0209648 0.9997801 -4.34016e-4 0.02387416 0.999715 1.56431e-4 0.02669036 0.9996438 -2.14277e-4 0.06596267 0.9978206 0.001721441 0.0701307 0.9964526 -0.04651814 0.06578582 0.9977983 0.008414447 0.06406003 0.9978834 0.01117652 0.0266512 0.9996449 -9.89944e-5 0.06628656 0.9977781 0.006714105 0.06174004 0.9242395 -0.3767884 0.06946069 0.9964985 -0.04654109 0.04715263 -0.5112326 -0.858148 0.05932903 0.9981874 0.01010179 0.06332689 0.9979711 -0.006592094 0.06371009 0.9979245 0.009378612 0.0672636 0.9977231 -0.004944026 0.05931061 0.9981366 0.0143454 -0.03286933 0.9420416 -0.333882 0.01617521 0.8708062 -0.4913602 0.09460884 0.9099844 -0.403705 0.0867964 0.8527046 -0.5151324 0.09128242 0.8963745 -0.4337975 0.1007124 0.8429023 -0.5285574 0.02691745 0.6267624 -0.7787455 0.1003164 0.7318184 -0.6740761 0.02954256 0.5257235 -0.8501424 0.1045905 0.7637827 -0.6369434 0.09451842 0.5110161 -0.8543587 0.1059929 0.6213696 -0.7763152 0.1062672 0.6853042 -0.7204621 0.0983321 0.2096348 -0.9728227 0.08850675 0.3949539 -0.9144277 0.09869873 0.4401158 -0.8925002 0.07623702 0.11756 -0.9901351 0.09936934 0.2473553 -0.9638159 0.0980882 0.1670002 -0.9810655 0.09390765 0.1811316 -0.9789651 0.08694869 0.1506419 -0.9847574 0.1031248 0.3465777 -0.9323354 -0.1631858 -0.00262463 -0.9865919 0.03695833 0.02240085 -0.9990658 0.04089498 0.02395713 -0.9988763 0.07175123 0.1541233 -0.9854429 0.03494405 0.02542221 -0.9990659 0.03048831 0.02633774 -0.9991882 0.07892328 0.1639505 -0.9833063 0.08410966 0.1640688 -0.9828566 0.07986861 0.1594625 -0.9839679 0.07812899 0.07361215 -0.9942219 0.08111959 0.06589061 -0.9945241 0.07010203 0.02456772 -0.9972373 0.07355189 0.02838307 -0.9968875 0.02821594 1.48961e-4 -0.9996019 0.09741687 0.1589433 -0.9824699 0.04515999 7.26713e-5 -0.9989798 0.0340901 0.001129209 -0.9994181 0.08902418 0.151802 -0.9843937 0.0929014 0.1848568 -0.9783647 0.04074317 6.10385e-5 -0.9991697 0.029329 0.001892149 -0.9995681 0.02805078 0.001543104 -0.9996054 0.07425218 0.04565608 -0.9961938 0.0886262 0.1433767 -0.9856919 0.0284658 0.00193417 -0.9995929 0.02946257 0.001525759 -0.9995648 0.07165855 0.1573558 -0.9849388 -0.1672439 9.46088e-4 -0.9859151 0.03894174 0.001495361 -0.9992404 0.033266 7.32463e-4 -0.9994463 0.0290842 0.001861631 -0.9995753 0.03329652 1.22077e-4 -0.9994456 0.06784349 0.1370909 -0.9882324 0.05279374 -0.01784718 -0.998446 0.07165968 0.1555271 -0.985229 0.07419198 0.1580585 -0.9846386 0.02831357 0.002545297 -0.9995959 0.02966445 9.15571e-4 -0.9995595 0.04400873 -0.005401849 -0.9990166 -0.4443859 -0.7872964 -0.4274174 -0.1710183 -5.0667e-5 -0.9852679 0.03967422 -0.001678526 -0.9992113 0.06305229 0.02618527 -0.9976667 -0.5598095 -0.7472569 -0.358079 -0.1569001 0.01397782 -0.9875156 -0.1627599 0.02591091 -0.9863255 0.02203494 0.003204524 -0.9997522 0.02780008 0.001735448 -0.999612 0.05112516 -0.01150751 -0.998626 0.0486173 -0.004608392 -0.9988068 0.04921263 -0.008288979 -0.998754 0.06149542 0.01269578 -0.9980267 -0.150857 0.002777218 -0.9885518 0.03038281 0.001851499 -0.9995366 0.04504632 -3.05192e-5 -0.998985 0.05039763 -6.25962e-4 -0.9987291 0.05978709 0.006195366 -0.998192 0.0577411 0.004150509 -0.998323 0.06683576 0.03366202 -0.997196 0.07245165 0.1044049 -0.9918924 0.07129251 0.007873892 -0.9974244 -0.6557968 -0.1537557 -0.7391142 0.04677051 1.07842e-6 -0.9989057 0.04756551 -0.002011299 -0.9988661 0.0643028 8.24004e-4 -0.9979301 0.06958329 0.002014219 -0.9975741 0.06637918 0.001037597 -0.9977939 0.07538175 0.00891149 -0.997115 0.07791531 0.01507639 -0.996846 0.07931995 0.02789473 -0.9964589 -0.4061225 -0.272783 -0.8721548 -0.6831673 -0.2473258 -0.6871043 -0.6771283 -0.2250787 -0.7005975 -0.1618704 0.01046782 -0.9867566 -0.1423082 0.06610327 -0.9876127 0.04016256 0.0163275 -0.9990598 0.03283816 -0.001892149 -0.9994589 0.05027598 -3.66504e-4 -0.9987354 0.05842155 -0.002188444 -0.9982897 -0.4148139 -0.3256984 -0.8496177 -0.6943816 -0.290699 -0.6582769 -0.6890377 -0.2694562 -0.6727707 -0.1712418 0.01983726 -0.9850293 -0.4266561 -0.3762692 -0.822427 -0.442862 -0.4239097 -0.7900468 -0.7041485 -0.3317482 -0.6277884 0.04959791 0.003351151 -0.9987637 0.04986101 -8.14417e-4 -0.9987559 -0.6995854 -0.3119035 -0.6428813 -0.1834482 0.02645975 -0.9826732 -0.1389209 0.09094554 -0.9861187 0.02934849 -3.66226e-4 -0.9995692 0.02874559 -7.18911e-4 -0.9995865 0.04744368 0.002098143 -0.9988718 0.06083625 -0.005606055 -0.998132 0.06255227 -0.007271468 -0.9980152 0.0561695 -0.001331508 -0.9984204 0.06160885 -0.004657924 -0.9980895 0.06361216 -0.005795776 -0.997958 0.07730984 -0.005120754 -0.996994 0.07634508 -0.00760132 -0.9970526 -0.7086588 -0.3517658 -0.6116073 -0.1985275 0.03192305 -0.9795754 -0.725627 -0.4429572 -0.5265496 -0.7199774 -0.4068203 -0.5622544 -0.465999 -0.4671893 -0.7513849 0.03167873 -0.08295077 -0.9960501 0.0299977 -0.001215755 -0.9995493 0.05031841 0.001505017 -0.9987321 0.06853014 -0.01027601 -0.9975962 0.06524175 -0.00752604 -0.9978411 0.077762 -0.005035579 -0.9969593 0.07420349 -0.008307278 -0.9972086 -0.7165694 -0.3894299 -0.5786819 -0.7126218 -0.3705022 -0.5957335 -0.2161689 0.03647065 -0.9756746 -0.1337056 0.1231765 -0.9833363 0.03723371 -0.2514193 -0.9671619 0.02810716 -0.001219272 -0.9996042 0.05002003 -0.04193258 -0.9978677 0.06463986 -0.2073481 -0.9761294 0.07816034 -0.3685227 -0.9263272 0.05850464 -0.0677824 -0.9959833 0.05730473 -8.45025e-4 -0.9983564 0.0781899 -0.002014219 -0.9969365 -0.723486 -0.424887 -0.5440948 -0.2365217 0.04062068 -0.9707768 -0.7353354 -0.5178539 -0.4371605 0.03469991 0.007324516 -0.9993709 0.06003159 -0.2067078 -0.9765594 0.05649143 -0.09314531 -0.9940487 0.04638743 0.003227412 -0.9989183 0.05921834 -0.004470825 -0.9982351 0.05618548 -0.06128215 -0.9965379 0.07292568 -0.0102638 -0.9972847 0.07087689 -0.01060575 -0.9974288 0.07079857 -0.01053768 -0.997435 0.06664258 -0.00996834 -0.9977272 0.06826221 -0.01051682 -0.9976121 -0.73094 -0.4747295 -0.4902639 -0.2595632 0.04379457 -0.9647327 -0.7371345 -0.5592981 -0.3792338 -0.7375739 -0.5451461 -0.398498 0.03200525 0.03983539 -0.9986936 0.0486164 -0.03900295 -0.9980558 0.03598153 0.03543215 -0.9987242 0.06268596 -0.2473258 -0.9669025 0.05110979 0.003564178 -0.9986867 0.04936182 0.003609001 -0.9987745 0.05969446 -0.006402134 -0.9981962 0.09213674 -0.3511512 -0.9317745 0.09540194 -0.3408042 -0.9352813 0.06079405 -0.004739642 -0.9981391 0.0645371 -0.008922219 -0.9978755 0.07524091 -0.00596255 -0.9971476 -0.7347561 -0.5031134 -0.4549841 -0.2854724 0.04406905 -0.9573733 -0.1273576 0.1528413 -0.98001 -0.1375204 -0.2384787 -0.9613616 0.04046767 -0.03827035 -0.9984477 0.02706092 -0.005061388 -0.999621 0.06946223 -0.4466826 -0.8919919 0.06851631 -0.3090407 -0.9485776 0.06720381 -0.3447781 -0.9362755 0.06982719 -0.5306625 -0.844702 0.07345956 -0.6253678 -0.7768648 0.07175064 -0.6383092 -0.7664288 0.08667528 -0.9262963 -0.3666914 0.08539247 -0.9307724 -0.3554868 0.09091645 -0.9035801 -0.4186615 0.08093589 -0.05685651 -0.9950963 0.08804726 -0.1562877 -0.9837794 0.08798706 -0.178965 -0.9799132 0.0664035 -0.01046997 -0.997738 0.0798074 -0.05337786 -0.9953802 -0.3096521 0.004577934 -0.950839 -0.1346216 0.1099923 -0.9847735 0.04159754 -0.4095665 -0.9113314 0.03506714 -0.5297306 -0.8474408 0.04684674 -0.3068387 -0.950608 0.05066198 -0.4004738 -0.9149066 0.04705995 -0.3965305 -0.9168146 0.0667141 -0.6801727 -0.7300099 0.09665304 -0.8344756 -0.5425023 0.07596099 -0.06341779 -0.9950921 -0.3277783 -0.1028198 -0.9391429 -0.1566567 -0.01190257 -0.9875814 -0.2490666 -0.8854514 -0.3923539 0.02542251 -0.5079016 -0.8610399 0.01474088 -0.4745779 -0.8800902 0.04407012 -0.5314058 -0.8459704 0.03500545 -0.6303119 -0.7755525 0.05096733 -0.06018424 -0.9968853 0.05429393 -0.06470102 -0.9964266 0.06784355 -0.07107853 -0.9951609 0.07062155 -0.06991958 -0.9950498 0.1038576 -0.4869375 -0.8672401 0.1024827 -0.4818338 -0.8702491 0.07187205 -0.06878966 -0.995039 0.07883137 -0.05997043 -0.9950826 -0.3005227 -0.7503759 -0.5887461 -0.3420613 -0.2416525 -0.9080739 -0.1835095 -0.1715461 -0.9679341 -0.2337177 -0.9012386 -0.3648903 -0.001281797 -0.4479334 -0.8940661 0.04541295 -0.6316617 -0.773913 0.05331707 -0.4931604 -0.8683031 0.05087488 -0.5195224 -0.8529409 0.06488406 -0.591617 -0.8036041 0.08945107 -0.9064744 -0.4126775 0.09369349 -0.8242589 -0.5584074 0.08810836 -0.3584152 -0.9293953 0.09283936 -0.9122489 -0.3989773 0.09406089 -0.9146369 -0.3931819 -0.3531633 -0.3863677 -0.8520538 -0.2077443 -0.3378478 -0.9179876 -0.1483526 -0.4391371 -0.886087 0.05542182 -0.5690506 -0.8204327 0.0528894 -0.6230761 -0.7803711 0.06638038 -0.6224496 -0.7798398 0.06854534 -0.7184447 -0.6921985 0.06711137 -0.7032812 -0.707737 0.08881038 -0.4970942 -0.8631397 0.08530128 -0.487667 -0.8688525 0.09381502 -0.4970306 -0.8626468 -0.3601034 -0.5290916 -0.7683669 -0.2269077 -0.5009366 -0.8352099 -0.253677 -0.8770961 -0.4078608 -0.152231 -0.5704699 -0.8070873 0.04583954 -0.7932204 -0.6072068 0.05685722 -0.6676988 -0.7422571 0.05371427 -0.7128741 -0.6992319 0.08301293 -0.6081004 -0.7895081 0.09170919 -0.6175187 -0.7811914 0.09656262 -0.6230182 -0.7762243 0.09219926 -0.9072212 -0.4104256 -0.2388132 -0.6497856 -0.721628 -0.181223 -0.7022164 -0.6885132 0.001648008 -0.7884613 -0.6150822 0.05612552 -0.833643 -0.5494444 0.05203562 -0.8629373 -0.5026247 0.05346989 -0.7921296 -0.6080064 0.04599297 -0.7175455 -0.6949915 0.0572232 -0.7528747 -0.6556715 0.05639898 -0.6209689 -0.7818037 0.07065212 -0.7255653 -0.6845169 0.09650284 -0.7330799 -0.6732616 0.1000732 -0.7405849 -0.6644694 -0.1261038 -0.9920146 -0.002227842 0.05298131 -0.9188724 -0.3909816 0.05093586 -0.9389419 -0.3402848 0.05380529 -0.8960122 -0.4407578 0.0573455 -0.7111276 -0.7007206 0.06979632 -0.7674548 -0.6372924 0.0804494 -0.8483504 -0.5232873 -0.05481255 -0.9984683 0.007538259 0.0483123 -0.9638968 -0.2618572 0.05701047 -0.7950032 -0.6039204 0.07883149 -0.8683983 -0.4895612 0.0819137 -0.9476846 -0.3085194 0.08505588 -0.9372633 -0.3380874 0.0993086 -0.9101055 -0.4023007 -0.1663596 -0.9860417 0.006805717 -0.08218687 -0.9958258 0.03970479 0.03799629 -0.9989522 -0.02551394 0.04730439 -0.9734945 -0.2237651 0.05539256 -0.8683974 -0.4927653 0.07635933 -0.9648379 -0.2515097 0.076267 -0.9669948 -0.2431144 0.08551526 -0.9329771 -0.3496299 0.08746707 -0.9256677 -0.368088 0.09650313 -0.9137893 -0.3945583 -0.1474109 -0.7198719 0.6782733 -0.1315188 -0.9913137 -1.64603e-4 -0.05328619 -0.9984911 0.01327574 -0.06637877 -0.9975134 0.02368271 0.03363215 -0.9981924 -0.04980736 0.0612207 -0.9938145 -0.09265506 -0.1400822 -0.6862197 0.7137784 -0.1097783 -0.9934375 -0.03210639 -0.03130215 -0.9995099 2.20758e-4 0.05558186 -0.9984542 -2.38615e-4 0.05984699 -0.9944801 -0.08618462 -0.1314888 -0.9913176 3.51851e-4 -0.02721202 -0.9996297 -3.09355e-4 0.03778594 -0.9991689 -0.01529145 0.05511462 -0.9984781 -0.001956582 0.05565857 -0.9984496 -8.12306e-4 -0.03035163 -0.9995393 -2.46437e-4 0.02664309 -0.9996208 -0.006958305 0.05473113 -0.9985011 4.37051e-5 0.05340147 -0.9985699 0.002581059 0.05490005 -0.9984917 -5.70986e-4 -0.09573805 -0.9953464 0.01095628 -0.01837265 -0.999572 -0.02276748 0.0338245 -0.9994278 1.25698e-5 0.05402058 -0.9985393 -0.001070022 -0.03092312 -0.9995217 -2.84952e-4 0.0246793 -0.9996152 -0.01266956 0.02989345 -0.9995532 5.36397e-7 0.03666734 -0.9993276 1.42591e-5 0.02987962 -0.9995536 9.25919e-6 0.05364346 -0.9985602 -5.69116e-5 0.05390614 -0.9985458 -6.64664e-4 -0.01852494 -0.9997982 -0.00778228 0.03383558 -0.9994275 2.0047e-5 0.03603225 -0.9993506 -2.47035e-4 0.0170297 -0.9998112 0.009369373 0.02541261 -0.9996147 -0.01116913 0.02999079 -0.9992979 -0.02245831 0.03371852 -0.9992815 -0.01730769 0.03398442 -0.9992627 -0.01786595 -1 0 0 -1 -2.06954e-6 0 -1 -3.37808e-4 8.34151e-7 -1 0 1.45983e-6 -1 1.9204e-4 -9.19385e-6 -1 -3.09364e-4 0 -1 -7.08319e-5 1.39855e-6 -1 -6.55171e-5 0 -1 1.46031e-6 0 -1 1.1841e-5 0 -1 5.59414e-6 0 -1 -2.29293e-5 0 -1 1.20395e-5 0 0.03128194 0.9994673 -0.009308278 0.03045767 0.9995189 -0.005859553 0.04098737 0.9977975 -0.0521574 0.01956248 0.9995202 -0.02401822 0.0233168 0.9900199 -0.1389855 0.01599192 0.9985802 -0.05081403 0.02618551 0.9995968 0.01098692 0.02545303 0.9902271 0.1371229 0.01504588 0.9996827 0.02020359 0.03308218 0.9603919 0.2766822 0.03460854 0.9990099 -0.02795541 0.04037642 0.9985766 -0.0348525 0.04632788 0.9989192 0.003784358 0.0385757 0.8989609 0.4363269 0.04107916 0.8185018 0.5730336 0.05612379 0.9978685 0.03329581 0.03738605 0.9639505 0.2634422 0.04614514 0.9989274 0.003845393 0.03302133 0.9987891 -0.03646993 0.03265488 0.999454 0.005035519 0.04464864 0.9989947 -0.004028439 0.0306102 0.9995178 -0.005218684 0.03216707 0.9994693 0.005157709 0.03506606 0.9992772 -0.01467949 0.06036144 0.996459 0.05853348 0.04577833 0.9989444 0.003845334 0.0456565 0.9989498 0.003845393 0.04489368 0.9989836 -0.004059016 0.03772133 0.9992193 0.01174974 0.02539193 0.9992901 -0.02783346 0.05600339 0.9539201 0.2947887 0.06777352 0.9973648 0.02588868 0.01208531 0.9995146 -0.02871799 0.03405892 0.9867641 -0.1585451 0.06442499 0.9978705 -0.01019322 -0.0174266 0.9394822 -0.3421543 -0.01208537 0.9425401 -0.3338748 0.01104795 0.9397798 -0.3416022 -0.001190245 0.9487802 -0.3159345 0.01269584 0.9644003 -0.2641419 0.00112915 0.9001263 -0.4356277 -0.005432307 0.9214562 -0.3884442 -0.03299117 0.8907934 -0.4532096 -0.03732484 0.7728044 -0.6335458 -0.02935951 0.7123195 -0.701241 -0.0428794 0.7193979 -0.6932735 -0.01287901 0.3606747 -0.9326027 -0.02624619 0.3129401 -0.9494103 -0.0525853 0.5259752 -0.8488728 -0.02996987 0.6594287 -0.7511695 -0.04907429 0.6231642 -0.7805499 -0.04751896 0.6544312 -0.7546269 -0.06451809 0.3300985 -0.941739 -0.01043736 0.3389712 -0.9407389 0.01156687 0.4380781 -0.8988627 -0.003143489 0.01098692 -0.9999348 -0.05502563 0.02801638 -0.9980919 0.0203256 0.1010482 -0.994674 0.01556473 0.2307548 -0.9728875 -0.005066096 0.0968672 -0.9952845 -0.0588414 0.1002257 -0.9932234 0.03997969 0.02395731 -0.9989134 0.02496469 0 -0.9996884 0.02420186 0.01446616 -0.9996024 -3.96743e-4 -0.1137738 -0.9935067 -0.05163776 -1.52594e-4 -0.998666 -0.05166816 -1.52594e-4 -0.9986643 9.1558e-5 -0.09335863 -0.9956325 0.04068225 -6.10386e-5 -0.9991722 -0.02465897 0.03491318 -0.9990862 -0.05163776 -2.13631e-4 -0.9986659 0.02606356 0.03015315 -0.9992055 -0.03445625 -0.2635034 -0.964043 -0.05429261 -0.01663261 -0.9983866 -0.02197366 -0.2617315 -0.9648905 0.008118093 0.002319455 -0.9999644 -0.003845334 0.2681062 -0.9633818 0.04623681 0.001434385 -0.9989295 0.007416009 0.12476 -0.9921593 0.001068174 0.1925463 -0.9812874 0.0172128 0.06958371 -0.9974276 0.02808123 0.05096071 -0.9983058 0.0425744 0.09692931 -0.9943803 0.04025435 0.1782301 -0.9831652 0.05398738 -0.002533018 -0.9985384 0.04617476 0.1303454 -0.9903929 0.05789536 0.001617491 -0.9983214 0.05295091 0.08038777 -0.9953562 0.06009066 0.004030823 -0.9981848 -0.0518828 8.8506e-4 -0.9986528 -0.001464843 -0.04254317 -0.9990937 -0.07934927 0.823859 -0.561213 -0.08041787 0.8137311 -0.5756515 -0.07077485 0.8681597 -0.4912125 0.03705006 0.1487803 -0.9881761 -0.004486203 0.1408132 -0.990026 -0.0632044 0.1726753 -0.9829489 0.01306235 0.3404149 -0.9401847 -0.06311285 0.247599 -0.9668049 -0.008331716 0.2276124 -0.9737162 0.03235065 0.3382784 -0.9404898 -0.06659382 0.3926655 -0.9172673 0.02954256 0.4943505 -0.8687605 0.01525974 0.5251802 -0.8508543 -0.06390696 0.4577863 -0.8867625 -0.0335403 0.4902259 -0.8709499 -0.05099743 0.5534642 -0.8313103 -0.03131312 0.6318781 -0.7744351 -0.04467999 0.6956537 -0.7169865 -0.03744721 0.6048933 -0.7954255 -0.02722334 0.7024363 -0.7112259 -0.02499508 0.7380731 -0.6742577 -0.02081412 0.7784556 -0.6273546 -0.01886117 0.8009295 -0.5984616 -0.03436464 0.8020147 -0.5963151 -0.01986783 0.8018264 -0.5972269 -0.04352027 0.8876495 -0.4584587 -0.06589037 0.8485183 -0.525048 -0.01599228 0.8214361 -0.5700763 -0.07083612 0.7355545 -0.6737521 -0.01275706 0.8485888 -0.5288993 -0.06805813 0.8495674 -0.5230713 -0.02557545 0.8957828 -0.4437559 -0.03338825 0.9156451 -0.4005985 -0.01913535 0.8886212 -0.4582425 -0.06128233 0.8902419 -0.4513468 -0.08783394 0.7855614 -0.6125182 -0.1346496 0.07458835 -0.988082 -0.1343753 0.05456799 -0.989427 -0.1346195 0.06463932 -0.9887869 -0.1344373 0.07403969 -0.9881522 -0.1340398 0.0451377 -0.9899474 -0.1335836 0.0237441 -0.9907531 -0.1335823 0.03534114 -0.9904075 -0.1335829 0.02130246 -0.9908087 -0.1336143 0.01379477 -0.9909375 -0.1333387 0.005981743 -0.9910525 -0.1330332 -8.85057e-4 -0.9911113 -0.1324207 -0.03131216 -0.9906989 -0.1342215 -0.003723263 -0.9909444 -0.1352308 -0.04742687 -0.9896785 -0.1370914 -0.00225836 -0.9905559 -0.137764 -0.04962432 -0.9892212 -0.1398702 -9.15581e-5 -0.9901699 -0.1408448 -0.05032569 -0.9887518 -0.1410281 0.00137335 -0.9900047 -0.1446278 0.01623588 -0.989353 -0.145879 0.5168331 -0.8435655 -0.1343145 0.005249261 -0.9909248 -0.1383729 0.4759126 -0.8685391 -0.1346511 0.5581063 -0.8187714 -0.1398718 0.3599494 -0.9224275 -0.1214337 0.004577755 -0.9925889 -0.1300444 0.3755447 -0.9176354 -0.1284539 0.1997765 -0.9713851 -0.11527 0.01763993 -0.9931775 -0.1157585 0.03585976 -0.9926299 -0.1349858 0.1324832 -0.9819508 -0.1339192 0.08218878 -0.9875783 -0.1343451 0.09396833 -0.9864692 -0.1348348 0.1124641 -0.9844651 -0.1343138 0.1903465 -0.9724856 -0.1347124 0.1273878 -0.9826623 -0.133916 0.1384938 -0.9812676 -0.1342833 0.1530829 -0.9790473 -0.1344388 0.166637 -0.9768103 -0.1341021 0.183757 -0.9737813 -0.13291 0.2510185 -0.9588142 -0.1327264 0.1917803 -0.9724217 -0.1330655 0.2077471 -0.9690897 -0.1331537 0.2167143 -0.9671118 -0.1328178 0.2324006 -0.9635089 -0.1312023 0.3051317 -0.9432288 -0.1312326 0.2446725 -0.9606839 -0.1309875 0.2592283 -0.9568924 -0.128334 0.3429769 -0.9305361 -0.1290944 0.2714952 -0.9537427 -0.1292163 0.2882494 -0.9487969 -0.1289734 0.3041222 -0.9438621 -0.1282103 0.3214261 -0.9382151 -0.09845381 0.6806619 -0.7259519 -0.1012938 0.6619653 -0.7426584 -0.09772205 0.6993446 -0.7080731 -0.1250662 0.3798071 -0.9165725 -0.1057811 0.6305056 -0.7689428 -0.1099313 0.5872568 -0.8019006 -0.1047422 0.6258593 -0.7728708 -0.1107849 0.5630195 -0.8189846 -0.126105 0.3331468 -0.934404 -0.1129522 0.5375684 -0.8356207 -0.1255548 0.3528292 -0.9272258 -0.1211912 0.4278163 -0.8957042 -0.1235129 0.3591246 -0.9250807 -0.1229305 0.3892697 -0.912884 -0.1210987 0.4332455 -0.8931034 -0.1162772 0.4940712 -0.8616109 -0.1174061 0.4864402 -0.8657897 -0.09158736 0.7373989 -0.6692196 -0.09198468 0.7491535 -0.6559786 -0.07284957 0.8331162 -0.5482795 -0.02923673 0.9293206 -0.3681148 -0.01947093 0.9537118 -0.3000912 -0.01635843 0.9615461 -0.2741563 -0.01287889 0.9681182 -0.2501628 -6.10376e-4 0.9745872 -0.2240079 0.003143489 0.9775378 -0.2107368 -0.00225836 0.9842889 -0.1765506 0.01046812 0.9722557 -0.2336868 0.001007139 0.9885225 -0.1510708 0.02316397 0.9850943 -0.1704489 0.004821896 0.9919782 -0.1263167 0.01883018 0.9951013 -0.0970503 0.03885114 0.9969455 -0.06775295 0.02087497 0.9963248 -0.08307284 0.039339 0.9973319 -0.06149584 0.0328083 0.9994494 0.004974603 0.03018337 0.9995304 -0.005279779 0.03094655 0.9995074 -0.005218744 0.03186219 0.9994793 0.005096733 0.03109902 0.9995025 -0.005249261 0.04510682 0.9989738 -0.004089474 0.03720253 0.9992192 0.0133062 0.04562646 0.9989303 0.007507741 0.03158682 0.9994879 0.005127131 0.05087512 0.9986734 -0.007965445 0.03036618 0.9995211 -0.005951106 0.03695899 0.9545555 -0.295733 0.03366267 0.976706 -0.2119253 0.01791471 0.9998376 -0.001983702 0.02493393 0.9893937 -0.1431033 0.01464909 0.9998927 -3.0519e-5 0.04272651 0.9777659 -0.2053009 0.0554226 0.9967529 -0.0584135 0.0638554 0.9979283 -0.007849276 0.04443544 0.9990042 -0.004028439 0.02389669 0.9996953 0.006195425 0.05542224 0.9922297 -0.1113939 0.07421469 0.9876442 0.1380259 0.05084478 0.9259184 0.374286 0.03415071 0.9679707 -0.2487297 0.04773157 0.9732487 -0.2247414 0.0435813 0.9320856 0.3596072 0.03872895 0.9339823 -0.3552142 0.04367285 0.9562261 -0.2893521 0.03167927 0.9322813 -0.3603445 0.03488314 0.971326 -0.2351788 0.03235 0.8939591 -0.4469795 0.03024393 0.8792724 -0.4753583 0.02862679 0.8532503 -0.5207153 -0.06668478 0.76805 -0.6369084 0.02255374 0.5718408 -0.8200545 0.0267654 0.7562073 -0.6537845 0.02539169 0.7955366 -0.6053733 0.02890115 0.7891523 -0.6135172 0.0283221 0.6896505 -0.7235882 0.02185159 0.7196996 -0.6939416 0.0263381 0.5274648 -0.8491686 0.02029532 0.6552499 -0.7551397 0.02288943 0.6451476 -0.7637151 0.02859598 0.5992956 -0.800017 -0.003082394 -0.5202891 -0.8539847 0.01489305 0.4246355 -0.905242 -0.05670452 0.8232233 -0.5648788 -0.02347087 -0.9997246 0 -0.02347087 -0.9997246 0 0.9997246 -0.02347064 0 0.9997246 -0.02346926 0 0.02347093 0.9997246 0 0.02347093 0.9997246 0 0.9997246 -0.02346926 0 0.9997246 -0.02347064 0 -0.02347064 -0.9997246 0 -0.02347069 -0.9997246 0 0.9997312 -0.02318924 1.3597e-4 0.9997202 -0.02365309 4.10164e-4 0.9997277 -0.02333205 -5.92148e-4 0.9997407 -0.0227611 -7.8169e-4 0.9997071 -0.02419364 6.36966e-4 0.999759 -0.02192378 -0.001172482 0.9996917 -0.02480751 0.001048982 0.9997233 -0.02352237 0 0.9996371 -0.0268563 0.002157211 0.9997431 -0.02266526 2.26302e-4 0.9997125 -0.02398109 -1.12889e-4 0.9997355 -0.02299547 1.98122e-4 0.9997165 -0.02381646 -1.09386e-4 0.9997245 -0.02347451 0 0.9997138 -0.02392756 -1.9868e-4 0.999704 -0.02432429 -4.79156e-4 0.9997354 -0.0230056 2.18181e-4 0.9997157 -0.02384442 -1.87449e-4 0.9997243 -0.02348589 4.1762e-5 -0.02345097 -0.9997251 0 -0.0234512 -0.999725 0 0.6451498 0.7640534 0.002075314 0.7064037 0.7078076 -0.001464903 0.551046 0.8344733 -0.001678526 0.4390518 0.8984601 0.001709043 0.385575 0.9226761 -9.46084e-4 0.2170822 0.9761529 8.85053e-4 0.1965739 0.980489 -3.35711e-4 0.09979677 0.9950078 6.10378e-4 0.08850479 0.9960758 0 0.812154 0.583441 0.001617491 0.8228728 0.5682257 -2.74667e-4 0.9134283 0.4069989 -8.85046e-4 0.9296182 0.3685206 0.001617491 0.9818518 0.189644 -0.001525938 0.989315 0.1457909 0.00100708 0.9977141 0.06756818 -0.001098632 0.9989823 0.04510724 3.05191e-5 0.9997252 -0.02344173 0 0.9997255 -0.02343243 0 0.13642 0.990647 -0.002868771 -0.1721878 0.9850597 -0.002929806 -0.03033608 0.9995357 0.002868771 0.2762312 0.9610868 0.002929806 0.408008 0.9129748 -0.002563536 0.5562117 0.8310368 0.002563595 0.6477756 0.7618268 -0.002594113 0.7622753 0.6472489 0.002288877 0.8460461 0.5331049 -0.002288877 0.8963464 0.4433512 0.001770079 0.9588388 0.2839466 -0.001586973 0.9731343 0.2302366 8.85056e-4 0.9866501 0.1628496 -0.001312315 0.9922403 0.1243352 3.9675e-4 -0.3086082 0.951186 0.002533078 -0.4648616 0.8853796 -0.002594053 -0.55154 0.8341463 0.001922667 -0.6898553 0.7239453 -0.001739561 -0.7317184 0.6816065 9.46082e-4 -0.8441335 0.5361326 -7.93502e-4 -0.8581143 0.5134586 5.49349e-4 -0.9446506 0.3280779 -5.18821e-4 -0.9564992 0.2917321 0.001342833 -0.9901912 0.1397163 -8.85053e-4 -0.9868847 0.1614136 0.002105772 -0.9982915 0.05841422 -0.001403868 0.9997242 -0.02348458 0 0.9997244 -0.02347964 0 0.6522833 -0.7579706 -0.002685666 0.7465578 -0.6653161 0.002472043 0.5588046 -0.8292954 0.002594113 0.4172269 -0.9087983 -0.002716183 0.3412941 -0.9399549 0.001770079 0.1379168 -0.9904438 4.88309e-4 0.1636119 -0.9865242 -0.00112915 0.04178029 -0.9991269 -3.05189e-5 0.04242134 -0.9990999 0 0.8162933 -0.5776342 -0.001983702 0.8880196 -0.4598035 0.00149542 0.9114835 -0.4113364 -3.3571e-4 0.9712383 -0.2381096 2.44152e-4 0.9721805 -0.2342327 4.57784e-4 0.99055 -0.1371517 -5.49339e-4 0.9921175 -0.1253117 2.44153e-4 0.9997252 -0.02344608 0 0.9997252 -0.02344608 0 0.6205844 -0.7841386 0.001281797 0.6496566 -0.7602267 -0.001281738 0.7289454 -0.6845708 0.001281738 0.4956256 -0.868535 0.001556456 0.5309336 -0.8474124 -0.001281738 0.3439517 -0.9389851 0.002075254 0.3971134 -0.9177677 -0.001831114 0.2377136 -0.9713331 -0.002075254 0.1852519 -0.9826899 0.001556456 0.06219774 -0.9980638 3.35709e-4 0.08169919 -0.9966567 -8.85049e-4 0.01232963 -0.9999241 -1.22076e-4 0.01446598 -0.9998955 0 0.7541922 -0.6566526 -0.001281797 0.8239575 -0.56665 0.00137335 0.8443826 -0.535739 -0.001403868 0.9071124 -0.4208858 0.001525938 0.9218933 -0.3874412 -0.001525938 0.9728453 -0.231454 -0.00112915 0.9645655 -0.2638401 0.001403868 0.9940468 -0.1089541 -3.35713e-4 0.9921713 -0.1248835 6.10379e-4 0.9982367 -0.05935889 1.22075e-4 0.9981036 -0.06155741 0 -0.0234704 -0.9997246 0 0.9997245 -0.02347159 1.09139e-5 0.999722 -0.02358233 0 0.9997217 -0.023597 1.57772e-5 0.9997244 -0.02347677 -3.98837e-6 0.9997282 -0.02331566 -3.27662e-5 0.9997234 -0.02352058 -1.76902e-5 0.9997246 -0.02346885 0 -0.9956724 0.09292942 -8.85042e-4 -0.9956724 -0.09292942 8.85042e-4 -0.9859821 0.1668481 0.001037597 -0.9479449 0.3184333 -9.15564e-4 -0.9031254 0.4293752 0.001312315 -0.8447133 0.5352171 -0.001434385 -0.7265904 0.6870687 0.001800596 -0.6544802 0.756078 -0.001342833 -0.4233365 0.9059724 -5.18832e-4 -0.4452709 0.8953943 0.001709043 -0.1519241 0.9883919 -7.32459e-4 0.175761 0.9844328 -5.49349e-4 -0.1095638 0.9939793 0.001037597 0.2034119 0.9790933 3.35714e-4 0.4623594 0.8866925 4.27263e-4 0.6814639 0.7318512 9.46096e-4 0.6383904 0.7697124 -7.62968e-4 0.8114131 0.5844726 -8.85056e-4 0.8482483 0.5295982 8.54535e-4 0.9236284 0.3832886 -7.62976e-4 0.9473069 0.3203265 7.93492e-4 0.9871395 0.1598589 -8.24015e-4 0.9955055 0.09470105 8.85056e-4 0.9955055 -0.09470105 -8.85056e-4 0.9473069 -0.3203265 -7.93492e-4 0.9871395 -0.1598589 8.24015e-4 0.4363649 -0.8997699 1.52596e-4 0.175761 -0.9844328 5.49349e-4 0.4623594 -0.8866925 -4.27263e-4 -0.1519241 -0.9883919 7.32459e-4 -0.4233615 -0.9059606 5.18825e-4 -0.4452709 -0.8953943 -0.001709043 -0.1095638 -0.9939793 -0.001037597 -0.6544802 -0.756078 0.001342833 -0.7265904 -0.6870687 -0.001800596 -0.8447133 -0.5352171 0.001434385 -0.9031254 -0.4293752 -0.001312315 -0.9479449 -0.3184333 9.15564e-4 -0.9859871 -0.1668185 -0.001037597 0.2034119 -0.9790933 -3.35714e-4 0.6383724 -0.7697274 7.62983e-4 0.6814639 -0.7318512 -9.46096e-4 0.8482483 -0.5295982 -8.54535e-4 0.8114131 -0.5844726 8.85056e-4 0.9236176 -0.3833147 7.62967e-4 0.4363649 0.8997699 -1.52596e-4 -0.9978148 -0.06607335 -1.52594e-4 -0.9973253 -0.07309257 1.52594e-4 -0.9872241 0.1593389 2.7467e-4 -0.8522871 0.5230734 9.46104e-4 -0.8105161 0.5857152 -0.001159667 -0.9236388 0.3832625 -0.001129209 -0.9324095 0.3614033 5.18819e-4 -0.6888863 0.7248688 -9.15585e-4 -0.7483983 0.663249 9.15584e-4 -0.2171112 0.9761461 0.001312255 0.01461857 0.9998927 9.46088e-4 -0.02722316 0.9996293 -4.88309e-4 0.2001758 0.9797598 7.62981e-4 0.3282328 0.9445964 -9.46092e-4 0.1469777 0.9891395 -7.93485e-4 0.5379036 0.8430055 -0.001312315 0.3674778 0.9300323 4.88302e-4 0.8729973 -0.4877249 5.18824e-4 0.8613219 -0.5080584 -0.001129209 0.9554318 -0.2952115 4.88306e-4 -0.04428344 -0.9990177 -0.001648008 0.0443139 -0.9990164 0.001648008 -0.1984981 -0.9800999 0.001648008 -0.284835 -0.9585752 -0.001648008 -0.4298679 -0.9028903 0.001648008 -0.5081527 -0.8612654 -0.001648008 -0.63538 -0.7721978 0.001648008 -0.7015756 -0.7125931 -0.001648008 -0.7970562 -0.6039035 0.001434326 -0.8530961 -0.5217519 -0.001434385 -0.8954561 -0.4451492 8.5453e-4 -0.9606601 -0.2777268 2.74675e-4 -0.9540246 -0.2997273 -8.85052e-4 0.1984981 -0.9800999 -0.001648008 0.284863 -0.9585669 0.001648008 0.4202166 -0.9074227 -0.001434385 0.4975841 -0.867415 0.001159727 0.5815209 -0.8135311 -9.15589e-4 0.7212301 -0.6926947 -0.001159727 0.6487504 -0.7610008 9.15581e-4 0.7711223 -0.6366863 9.46087e-4 0.9554974 -0.2949993 -3.35712e-4 0.9936178 -0.1127994 -3.96751e-4 0.9977798 -0.06659185 0.001068115 0.9973645 0.07254391 -0.001220762 0.9880934 0.1538478 0.001525938 0.9539368 0.3000032 -0.001648008 0.9235491 0.3834769 0.001648008 0.8558774 0.5171765 -0.001525938 0.8068678 0.5907305 0.001403868 0.7219024 0.6919935 -0.001403868 0.6670265 0.7450334 0.001068115 0.5230379 0.8523094 5.49345e-4 -0.1999881 0.9797982 -5.49334e-4 -0.3719955 0.9282339 -0.001068115 -0.4416379 0.8971923 0.001403808 -0.5471553 0.8370304 -0.001159727 -0.61789 0.786264 0.001037597 -0.9880852 0.1539076 -3.3571e-4 -0.04681539 0.9989022 -0.001708984 0.04681682 0.9989021 0.001709043 0.1199693 0.9927757 -0.001953184 0.2118602 0.9772977 0.00213629 0.3006748 0.9537239 -0.002349972 0.3882088 0.9215686 0.002349972 0.4711241 0.8820644 -0.00213629 0.5512646 0.8343282 0.001953184 0.6108906 0.7917132 -0.001708984 0.6823793 0.7309964 0.001709043 0.7310258 0.6823477 -0.001709043 0.7917428 0.6108524 0.001709103 0.8343282 0.5512646 -0.001953184 0.8820966 0.4710639 0.002105772 0.9215467 0.3882606 -0.002349913 0.9537354 0.3006383 0.002349913 0.9788936 0.2043545 -0.002533018 0.99184 0.1274782 0.001709043 0.9939936 0.1094095 -0.002502501 0.9987579 0.04980665 0.001403808 -0.1199693 0.9927757 0.001953184 -0.2078047 0.9781686 -0.001892149 -0.3009234 0.9536463 0.002014279 -0.3676668 0.9299556 -0.001983702 -0.5320155 0.8467323 -0.002014279 -0.4708234 0.8822254 0.001983761 -0.6110259 0.7916083 0.001892149 -0.6789935 0.7341418 -0.001953184 -0.7341266 0.6790099 0.001953184 -0.7916083 0.6110259 -0.001892149 -0.8467186 0.5320373 0.002014219 -0.8822448 0.4707869 -0.001983702 -0.9537163 0.3007029 -0.001739561 -0.9281571 0.3721845 0.001800596 -0.9719803 0.23506 0.001098692 -0.9918525 0.1273882 -0.001007139 -0.994147 0.1080362 2.4415e-4 -0.9987695 0.04959356 -4.27268e-4 -0.9991127 0.0421167 0 4.64219e-7 0 -1 4.15173e-7 0 -1 0 0 -1 0 0 -1 -2.10376e-7 0 -1 1.5231e-7 0 -1 3.75017e-7 0 -1 0 0 -1 3.36585e-7 0 -1 -1.75252e-7 0 -1 6.34982e-7 0 -1 -4.1068e-7 0 -1 1.2827e-6 0 -1 5.03238e-6 0 -1 3.09699e-7 0 -1 0 0 -1 9.69368e-6 0 -1 2.77312e-7 0 -1 0 0 -1 0 0 -1 -3.96027e-7 0 -1 3.70541e-7 0 -1 0 0 -1 -1.46708e-7 0 -1 -1.01097e-5 0 -1 2.51636e-5 0 -1 -1.13739e-6 0 -1 1.73856e-6 0 -1 1.1495e-6 0 -1 -1.33483e-6 0 -1 0 0 -1 -8.36388e-7 0 -1 6.80492e-7 0 -1 3.27839e-7 0 -1 4.92892e-7 0 -1 0 0 -1 -8.65873e-7 0 -1 1.76411e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.79542e-7 0 -1 -1.26714e-7 0 -1 3.63694e-7 0 -1 5.65688e-6 0 -1 9.95819e-7 0 -1 1.5095e-6 0 -1 5.13584e-7 0 -1 -1.28056e-6 0 -1 1.6837e-7 0 -1 0 0 -1 1.45523e-7 0 -1 2.77028e-7 0 -1 -6.62972e-6 0 -1 2.84923e-7 0 -1 1.00101e-6 0 -1 -1.52279e-7 0 -1 -1.41723e-6 0 -1 1.6901e-7 0 -1 -4.15951e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.1025e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.43674e-7 0 -1 0 0 -1 -4.08642e-7 0 -1 -2.87991e-7 0 -1 0 0 -1 3.05894e-7 0 -1 1.55418e-7 0 -1 3.96216e-7 0 -1 0 0 -1 -1.33145e-6 0 -1 -9.18817e-7 0 -1 2.01248e-7 0 -1 -5.53401e-7 0 -1 -2.53235e-7 0 -1 6.42971e-6 0 -1 -1.97201e-6 0 -1 -3.2832e-7 0 -1 -1.81185e-7 0 -1 3.32974e-6 0 -1 3.13752e-6 0 -1 1.65436e-7 0 -1 -3.28743e-7 0 -1 6.81766e-7 0 -1 -7.62363e-7 0 -1 6.03923e-7 0 -1 -6.44181e-6 0 -1 0 0 -1 -2.86691e-6 0 -1 -9.81556e-7 0 -1 0 0 -1 -9.15704e-7 0 -1 5.41615e-7 0 -1 0 0 -1 5.92834e-7 0 -1 0 0 -1 0 0 -1 -8.80015e-7 0 -1 2.73575e-7 0 -1 0 0 -1 2.36074e-7 0 -1 -1.97206e-6 0 -1 0 0 -1 5.15166e-7 0 -1 -7.2231e-7 0 -1 8.0013e-7 0 -1 1.35245e-6 0 -1 -2.33216e-7 0 -1 -1.4024e-6 0 -1 -5.13075e-7 0 -1 1.22206e-7 0 -1 1.39855e-7 0 -1 1.08186e-6 0 -1 1.77758e-7 0 -1 -1.06015e-6 0 -1 5.89406e-7 0 -1 8.67173e-7 0 -1 -2.92892e-7 0 -1 -7.10496e-7 0 -1 -4.05346e-7 0 -1 2.37679e-7 0 -1 1.19486e-6 0 -1 -1.97338e-6 0 -1 1.66223e-6 0 -1 2.32376e-7 0 -1 1.11246e-6 0 -1 2.04719e-7 0 -1 -5.0097e-7 0 -1 -8.37802e-6 0 -1 -1.66997e-6 0 -1 8.37058e-6 0 -1 1.7384e-5 0 -1 1.14845e-6 0 -1 -1.83183e-7 0 -1 4.10244e-6 0 -1 -3.29521e-7 0 -1 4.01643e-7 0 -1 -4.6497e-7 0 -1 4.94169e-7 0 -1 -3.31107e-6 0 -1 1.77168e-7 0 -1 2.34637e-6 0 -1 -3.08882e-7 0 -1 3.65387e-7 0 -1 -5.00126e-7 0 -1 -4.51901e-7 0 -1 2.05965e-6 0 -1 -5.32045e-7 0 -1 -4.96548e-7 0 -1 -1.28642e-5 0 -1 -7.1788e-7 0 -1 1.57861e-6 0 -1 4.48544e-7 0 -1 -1.47099e-5 0 -1 1.1164e-5 0 -1 0 0 -1 0 0 -1 -3.86233e-7 0 -1 0 0 -1 4.89927e-6 0 -1 -6.07851e-6 0 -1 -2.64382e-5 0 -1 1.22686e-7 0 -1 3.22003e-7 0 -1 7.25268e-7 0 -1 -0.02731454 -0.9996208 0.00350964 -0.02047795 -0.9997885 -0.001922667 -0.03985744 -0.9991839 0.006561517 -0.01690757 -0.9998357 -0.006531059 -0.04025512 -0.9989015 0.02398824 -0.02118021 -0.9997741 -0.001800596 -0.01992881 -0.999799 -0.002227842 -0.03744673 -0.9981538 0.04782319 -0.03964364 -0.9985074 0.03756839 -0.03766 -0.9983265 0.04388582 -0.03671383 -0.9982627 0.04608303 -0.03579896 -0.9982214 0.04767096 -0.03482258 -0.9981968 0.04889202 -0.03381544 -0.998197 0.04959392 -0.0327776 -0.9982224 0.04977679 -0.03717255 -0.9977995 0.05490428 -0.04321444 -0.9980827 0.04431307 -0.03830093 -0.9970754 0.06613391 -0.04580944 -0.9918778 0.1186591 -0.05072313 -0.9832723 0.1749368 -0.04974585 -0.9801164 0.1920863 -0.04379498 -0.981893 0.1843052 -0.03378415 -0.9991515 0.0235604 -0.04474085 -0.9806376 0.1906524 -0.03796631 -0.9902688 0.1338894 -0.04306268 -0.9776545 0.2057609 -0.04062062 -0.9769096 0.2097563 -0.037813 -0.9778591 0.2058201 -0.0287792 -0.9900599 0.1376702 -0.03650075 -0.9760913 0.2142744 -0.03763031 -0.9782365 0.2040523 -0.03268569 -0.9742841 0.2229402 -0.03509747 -0.9747337 0.2205954 -0.03018367 -0.9754614 0.2180917 -0.02813851 -0.977342 0.2097879 -0.02569723 -0.9804022 0.1953235 -0.0177012 -0.990933 0.1331865 -0.02572786 -0.9809864 0.192364 -0.02353018 -0.9783197 0.2057596 -0.01632773 -0.983024 0.182749 -0.01931864 -0.9789347 0.203258 -0.01358115 -0.9894725 0.1440825 -0.01568663 -0.9894508 0.1440183 -0.01684647 -0.9911357 0.1317811 -0.01663291 -0.9901935 0.1387094 -0.01721268 -0.9972675 0.07184159 -0.0109564 -0.9996924 0.02224856 -0.01724302 -0.9981436 0.05841273 -0.01889139 -0.9913884 0.1295849 -0.02438443 -0.9934464 0.1116681 -0.0209971 -0.9939152 0.1081291 -0.01458787 -0.9942959 0.1056554 -0.01339775 -0.9957379 0.09125125 -0.01290929 -0.9990549 0.04150521 -0.009125292 -0.9996648 0.02423244 -0.006164789 -0.9999471 0.008240044 -0.008718252 -0.9999501 -0.004896998 -0.004841029 -0.9999883 1.11627e-4 -0.008941411 -0.9999414 -0.006119489 -0.01434373 -0.9993618 0.03271591 -0.0234999 -0.9994791 0.02212649 -0.01802945 -0.9998189 0.006095111 -0.02193552 -0.9996917 -0.01163488 -0.02648442 -0.9995919 0.01070672 -0.03462415 -0.9992873 -0.015033 -0.04513567 -0.9989809 3.99183e-4 -0.02346652 -0.9997247 -1.49018e-4 -0.02350711 -0.9997237 -1.35846e-4 -0.0234546 -0.999725 4.38311e-5 -0.02347266 -0.9997246 7.92777e-5 -0.0234881 -0.9997241 4.11418e-4 -0.02345991 -0.9997248 -2.75007e-4 -0.02338796 -0.9997249 -0.001803576 -0.02356803 -0.9997208 0.001721203 -0.02348047 -0.9997243 1.7916e-4 -0.02346873 -0.9997246 -3.40712e-5 -0.02350503 -0.9997236 4.61675e-4 -0.02339982 -0.9997259 -8.53054e-4 -0.02357971 -0.9997212 0.001264631 -0.02338427 -0.9997262 -8.866e-4 -0.0233857 -0.9997262 -8.63039e-4 -0.02347373 -0.9997245 0 -0.02335691 -0.9997273 1.91578e-4 -0.02351379 -0.9997236 -7.856e-5 -0.0234462 -0.9997252 4.51467e-5 -0.02349495 -0.999724 -4.74282e-5 -0.02346682 -0.9997246 5.9766e-6 -0.02346223 -0.9997248 1.91431e-5 -0.02346765 -0.9997246 3.39805e-6 -0.02345538 -0.9997249 5.91888e-5 -0.02346563 -0.9997248 1.93628e-5 -0.02348303 -0.9997243 -6.2286e-5 -0.02347838 -0.9997244 -4.11441e-5 -0.02347093 -0.9997246 7.40556e-7 -0.02345502 -0.999725 -4.4904e-5 -0.02347892 -0.9997244 1.53685e-5 -0.02348077 -0.9997243 2.35e-5 -0.0234481 -0.9997252 -4.64835e-5 -0.0234732 -0.9997246 -1.02755e-6 -0.02346903 -0.9997246 -8.20455e-6 -0.02346867 -0.9997246 -7.93451e-6 -0.02347683 -0.9997244 -1.4719e-6 -0.02352863 -0.9997233 0 -0.02344781 -0.9997251 -1.35782e-5 1.41513e-6 0 -1 2.54608e-7 0 -1 1.3564e-6 0 -1 -4.39338e-7 0 -1 -1.89381e-5 0 -1 3.70406e-7 0 -1 8.57421e-7 0 -1 1.20963e-7 0 -1 -6.74123e-7 0 -1 6.32874e-7 0 -1 0 0 -1 1.58896e-7 0 -1 6.39632e-7 0 -1 3.4587e-6 0 -1 -6.81555e-6 0 -1 8.08447e-6 0 -1 -1.67644e-5 0 -1 2.15448e-5 0 -1 2.15531e-5 0 -1 -5.22644e-6 0 -1 1.56254e-5 0 -1 -1.04661e-5 0 -1 -7.66861e-6 0 -1 5.29852e-6 0 -1 3.81017e-6 0 -1 -5.31729e-6 0 -1 -1.50685e-6 0 -1 -2.67954e-6 0 -1 -2.33249e-7 0 -1 -1.38976e-6 0 -1 -5.71779e-6 0 -1 5.19322e-6 0 -1 -3.18102e-7 0 -1 6.81696e-7 0 -1 -6.53397e-7 0 -1 8.46047e-7 0 -1 -3.90011e-7 0 -1 -1.09235e-6 0 -1 1.10663e-6 0 -1 -8.73414e-6 0 -1 1.28761e-5 0 -1 -8.04461e-6 0 -1 -1.23119e-5 0 -1 -5.27201e-7 0 -1 -3.67613e-7 0 -1 6.47742e-7 0 -1 2.41756e-7 0 -1 2.50867e-7 0 -1 -2.38107e-7 0 -1 4.22696e-7 0 -1 1.36816e-5 0 -1 5.35065e-6 0 -1 -2.78847e-6 0 -1 -1.09224e-6 0 -1 1.50368e-6 0 -1 1.57897e-6 0 -1 2.17895e-6 0 -1 -5.40895e-6 0 -1 -4.81248e-6 0 -1 1.65317e-5 0 -1 -7.88466e-6 0 -1 -4.48932e-7 0 -1 -1.80185e-6 0 -1 -3.44466e-7 0 -1 5.7115e-7 0 -1 2.36506e-6 0 -1 1.35999e-6 0 -1 1.23763e-6 0 -1 9.93474e-7 0 -1 3.89362e-6 0 -1 2.97013e-6 0 -1 -3.9155e-6 0 -1 7.98005e-6 0 -1 7.02459e-6 0 -1 -3.42108e-6 0 -1 -1.68866e-6 0 -1 1.05278e-6 0 -1 -3.16189e-6 0 -1 3.03549e-6 0 -1 7.48854e-7 0 -1 2.0752e-6 0 -1 -1.50312e-6 0 -1 1.59784e-6 0 -1 3.88668e-7 0 -1 -1.12792e-6 0 -1 -7.55858e-7 0 -1 1.4004e-6 0 -1 5.30496e-6 0 -1 2.68941e-6 0 -1 1.25117e-6 0 -1 -2.27534e-6 0 -1 0 0 -1 0 0 -1 4.36764e-7 0 -1 -2.69995e-7 0 -1 -5.64861e-7 0 -1 4.89484e-7 0 -1 4.19432e-7 0 -1 2.86195e-7 0 -1 6.12054e-7 0 -1 1.37058e-5 0 -1 -2.27703e-5 0 -1 -2.3748e-5 0 -1 3.40575e-6 0 -1 6.72828e-6 0 -1 7.09763e-6 0 -1 -2.84192e-6 0 -1 -3.47483e-6 0 -1 5.12515e-6 0 -1 1.0241e-5 0 -1 -2.46091e-5 0 -1 1.07566e-5 0 -1 -7.12378e-6 0 -1 1.11428e-5 0 -1 -2.29906e-5 0 -1 -2.51823e-6 0 -1 -8.04569e-6 0 -1 3.91605e-6 0 -1 -5.2669e-6 0 -1 5.63191e-6 0 -1 -5.78173e-6 0 -1 -1.36886e-5 0 -1 4.30599e-6 0 -1 3.44196e-5 0 -1 1.56393e-6 0 -1 -1.27832e-4 0 -1 -1.06667e-5 0 -1 1.73784e-5 0 -1 7.36154e-6 0 -1 -7.42274e-7 0 -1 1.40692e-5 0 -1 5.68734e-6 0 -1 -2.61794e-5 0 -1 2.4966e-5 0 -1 -1.26725e-5 0 -1 -1.14301e-5 0 -1 2.43145e-5 0 -1 -8.99451e-6 0 -1 -1.46632e-5 0 -1 -7.80968e-6 0 -1 -1.43597e-4 0 -1 2.40764e-5 0 -1 2.95109e-5 0 -1 -2.43556e-5 0 -1 1.37888e-5 0 -1 2.74048e-6 0 -1 -3.87351e-7 0 -1 8.93914e-7 0 -1 -1.95715e-6 0 -1 2.16992e-6 0 -1 2.09805e-6 0 -1 -6.8451e-6 0 -1 -4.16023e-6 0 -1 -1.68394e-5 0 -1 4.35477e-6 0 -1 -1.87786e-6 0 -1 -1.40416e-7 0 -1 8.0412e-6 0 -1 5.42301e-6 0 -1 5.11828e-6 0 -1 -9.99784e-7 0 -1 3.9207e-6 0 -1 -7.09638e-6 0 -1 -3.38923e-6 0 -1 -3.19294e-6 0 -1 -2.73877e-7 0 -1 -1.68602e-6 0 -1 1.49914e-6 0 -1 7.47063e-7 0 -1 -5.71413e-6 0 -1 2.12719e-6 0 -1 -1.06709e-6 0 -1 2.14142e-6 0 -1 -2.78461e-6 0 -1 -2.26473e-6 0 -1 3.66004e-6 0 -1 -7.439e-7 0 -1 -8.52233e-6 0 -1 -4.21634e-6 0 -1 -1.05724e-6 0 -1 -2.20221e-6 0 -1 6.6519e-7 0 -1 1.22738e-6 0 -1 -2.66107e-6 0 -1 -1.30729e-6 0 -1 7.28047e-7 0 -1 -6.33645e-6 0 -1 0.9997248 -0.02346509 0 0.9997247 -0.02346509 0 -0.1928812 -0.9812222 -1.52596e-4 -0.2563917 -0.9665729 4.27268e-4 -0.1868989 -0.9823789 7.32458e-4 -0.2194954 -0.9756129 -0.001129209 -0.1609881 -0.9869563 -4.57786e-4 -0.1599184 -0.9871301 -5.18819e-4 -0.1494536 -0.9887682 -9.76622e-4 -0.1562571 -0.9877161 -7.62974e-4 -0.103428 -0.9946367 -7.3245e-4 -0.1377929 -0.9904609 -4.88303e-4 -0.1100831 -0.9939224 2.13635e-4 -0.1249436 -0.9921638 -6.10375e-5 -0.0949459 -0.9954825 3.05194e-4 -0.05862718 -0.9982798 -3.96748e-4 -0.07712125 -0.9970217 9.15567e-5 -0.05591118 -0.9984357 -3.9675e-4 -0.04437488 -0.9990149 -3.6623e-4 -0.03518855 -0.9993807 0 -0.3757801 -0.9267085 0.00100708 -0.3438886 -0.93901 -0.001037597 -0.467158 -0.884173 -0.001159727 -0.4903829 -0.871507 5.49346e-4 -0.6076089 -0.7942345 -0.001709043 -0.5951596 -0.8036073 7.32466e-4 -0.6911985 -0.7226638 0.001281797 -0.7368196 -0.6760869 -0.001892149 -0.7761659 -0.630528 0.001068115 -0.8432419 -0.5375324 -0.001434385 -0.8488356 -0.5286568 4.27271e-4 -0.9096259 -0.4154278 7.01942e-4 -0.9236901 -0.3831363 -0.001800596 -0.9614936 -0.2748214 0.001861631 -0.9754409 -0.2202539 -0.001861631 -0.9935124 -0.1137134 0.001586973 -0.9968879 -0.07882934 -7.32445e-4 -0.9992914 -0.0376302 7.935e-4 -0.9997318 -0.02316367 -6.10374e-5 + + + + + + + + + + + + + +

3672 3671

+
+ + + +

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

+
+
+
+ + + + -0.004684627 0.04393965 0 -0.01474958 0.01942706 0 -0.01477819 0.01943939 0.001999974 -0.004655957 0.04392766 0.001999974 -6.17347e-4 0.04571014 0.001999974 -7.46446e-4 0.04569417 0 0.001580476 0.04562193 0.001999974 0.001373708 0.04566609 0 0.003343999 0.04492765 0 0.003343999 0.04492765 0.001999974 -0.002918124 0.04506611 0 -0.002714931 0.04516071 0.001999974 -0.004655957 0.04392766 0.001999974 -0.004655957 0.04392766 0 0.02867293 0.03233665 0 0.02925515 0.03193718 0.001999974 0.003343999 0.04492765 0 0.003343999 0.04492765 0.001999974 0.03653955 0.02643126 0 0.03715413 0.02591532 0.001999974 0.04543775 0.01808708 0.001999974 0.04487532 0.01867485 0 0.04996758 0.01293528 0 0.04996758 0.01293528 0.001999974 0.0209009 0.03716289 0.001999974 0.02019613 0.03755241 0 0.01060408 0.04219257 0.001999974 0.009847104 0.04251021 0 0.04175376 0.01495707 0.001999974 0.03062176 0.01654523 0 0.04254049 0.01479846 0 0.0298658 0.01661276 0.001999974 0.02351838 0.01693528 0 0.02351838 0.01693528 0.001999974 0.04996758 0.01293528 0.001999974 0.04996758 0.01293528 0 0.02351838 0.01693528 0.001999974 0.02499997 0 0.001999974 0.02499997 0 0 0.02351838 0.01693528 0 -0.006054997 0.01948302 0 -0.01031827 0.01964563 0.001999974 -0.01475393 0.01949852 0 -0.01474934 0.01942765 0.001999974 -0.001646161 0.01899862 0.001999974 -0.001655936 0.01892775 0 0.04606717 0.01395547 0.001999974 0.04710644 0.01623392 0.001999974 0.04214286 0.01481366 0.001999974 -0.001655936 0.01892775 0.001999974 -0.009749472 0.03168308 0.001999974 -0.00177443 0.04546219 0.001999974 0.001871705 0.04549854 0.001999974 0.001138508 0.04565846 0.001999974 -0.00445342 0.01930522 0.001999974 -0.00818634 0.01957476 0.001999974 -0.01474934 0.01942765 0.001999974 -0.01192563 0.01959055 0.001999974 -0.00104916 0.04563665 0.001999974 4.07343e-4 0.04573488 0.001999974 -3.21902e-4 0.04572755 0.001999974 -0.002497792 0.04520398 0.001999974 0.002606868 0.04525488 0.001999974 0.003343999 0.04492765 0.001999974 -0.003561198 0.04468095 0.001999974 -0.004655957 0.04392766 0.001999974 0.007490634 0.04341745 0.001999974 0.01283907 0.04117441 0.001999974 0.01800501 0.03867614 0.001999974 0.02298551 0.03592431 0.001999974 0.02351838 0.01693528 0.001999974 0.02778559 0.03291589 0.001999974 0.02755546 0.01675504 0.001999974 0.03463679 0.02792918 0.001999974 0.03125625 0.0304867 0.001999974 0.03289633 0.01627826 0.001999974 0.03897762 0.02428448 0.001999974 0.03819602 0.01554292 0.001999974 0.04313284 0.02038729 0.001999974 0.04996758 0.01293528 0.001999974 0 0 0.001999974 0.02499997 0 0.001999974 0.02499997 0 0 0.02499997 0 0.001999974 0 0 0.001999974 0 0 0 -0.001655936 0.01892775 0 0.02298551 0.03592431 0 0.02351838 0.01693528 0 0 0 0 0.02778559 0.03291589 0 0.02499997 0 0 -0.00445348 0.01930522 0 -0.009750902 0.03167968 0 -0.00818634 0.01957476 0 -0.01474958 0.01942706 0 -0.01193213 0.01959043 0 0.007490634 0.04341745 0 -0.004655957 0.04392766 0 -0.00104916 0.04563665 0 4.07343e-4 0.04573488 0 0.001138508 0.04565846 0 -3.21902e-4 0.04572755 0 0.001871705 0.04549854 0 -0.00177443 0.04546219 0 0.002606868 0.04525488 0 -0.002497792 0.04520398 0 -0.003561198 0.04468095 0 0.003343999 0.04492765 0 0.01283907 0.04117441 0 0.01800501 0.03867614 0 0.03125625 0.0304867 0 0.03463679 0.02792918 0 0.03897762 0.02428448 0 0.03289633 0.01627826 0 0.02755546 0.01675504 0 0.04313284 0.02038729 0 0.03819602 0.01554292 0 0.04710644 0.01623392 0 0.04606717 0.01395547 0 0.04214286 0.01481366 0 0.04996758 0.01293528 0 0 0 0.001999974 -0.001655936 0.01892775 0.001999974 -0.001655936 0.01892775 0 0 0 0 + + + + + + + + + + -0.9240493 0.3819569 0.01554852 -0.9249439 0.3797845 -0.01558107 -0.108952 0.9940271 0.006286859 0.1809485 0.9834822 -0.004516839 -0.1328808 0.9911129 -0.006164848 0.2125964 0.9771315 0.004120051 0.3583559 0.9335504 -0.008057057 0.366318 0.9304898 0 -0.4234204 0.9059255 -0.003784298 -0.3962318 0.918142 0.003967463 -0.5422363 0.8401962 0.007080435 -0.5479703 0.8364978 0 0.3824039 0.9239953 4.88305e-4 0.3484364 0.9373325 0 0.3491683 0.9370563 0.002685666 0.5578373 0.8299499 8.85068e-4 0.5738 0.8189949 -9.1559e-4 0.6349787 0.7725279 0.001617491 0.6539043 0.7565708 -0.003143429 0.7258941 0.6878064 -4.57785e-4 0.7102362 0.7039492 0.004486262 0.7504564 0.6609144 -0.002746641 0.7509884 0.6603156 0 0.4928217 0.8701288 -0.001678526 0.4712432 0.8819979 0.003112912 0.4028838 0.91524 -0.004516839 0.1803953 0.9835834 -0.004608273 0.2039919 0.9789721 0.001037657 0.1064503 0.994309 0.004242122 0.08645969 0.9962553 4.27263e-4 0.05151581 0.9986691 -0.002502501 0.05072301 0.9987128 0 0.2425993 0.9701228 0.002746701 0.2432967 0.9699519 0 0.996195 0.08715295 0 -0.035371 0.9993619 0.004974484 0.005035638 0.999167 -0.04049891 0.07107806 0.9966496 0.04046779 -0.04907506 0.9981654 0.03546345 0.1115152 0.9937494 -0.005157649 0.1251274 0.991498 -0.03570705 0 0 1 0 0 1 2.33042e-7 0 1 1.55343e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 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 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.9961947 0.08715581 1.49861e-5 0.9961949 0.08715426 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -6.77117e-4 -7.35865e-4 0.01999998 -5.46732e-4 -8.37295e-4 0.01999998 -4.01432e-4 -9.15874e-4 0.01999998 -4.01695e-4 9.15773e-4 0.01999998 -5.46948e-4 8.37167e-4 0.01999998 9.86353e-4 -1.6464e-4 0.01999998 -2.45185e-4 -9.69459e-4 0.01999998 -7.89027e-4 -6.1435e-4 0.01999998 -8.22544e-5 -9.96591e-4 0.01999998 -8.79406e-4 -4.76066e-4 0.01999998 -9.45786e-4 -3.24786e-4 0.01999998 8.29121e-5 -9.96534e-4 0.01999998 -9.86353e-4 -1.6464e-4 0.01999998 2.45808e-4 -9.69292e-4 0.01999998 -0.000999987 0 0.01999998 4.01991e-4 -9.15613e-4 0.01999998 5.47201e-4 -8.36967e-4 0.01999998 -9.86361e-4 1.64595e-4 0.01999998 8.79555e-4 -4.75747e-4 0.01999998 -7.89141e-4 6.14213e-4 0.01999998 7.8928e-4 -6.1399e-4 0.01999998 -8.79474e-4 4.75947e-4 0.01999998 -9.45817e-4 3.24699e-4 0.01999998 6.7748e-4 -7.35502e-4 0.01999998 0.000999987 0 0.01999998 -6.77282e-4 7.35724e-4 0.01999998 9.45851e-4 -3.24545e-4 0.01999998 9.45817e-4 3.24699e-4 0.01999998 8.79474e-4 4.75947e-4 0.01999998 8.25793e-5 9.96584e-4 0.01999998 9.86361e-4 1.64595e-4 0.01999998 -8.25793e-5 9.96584e-4 0.01999998 -2.45485e-4 9.694e-4 0.01999998 4.01695e-4 9.15773e-4 0.01999998 6.77282e-4 7.35724e-4 0.01999998 5.46948e-4 8.37167e-4 0.01999998 7.89141e-4 6.14213e-4 0.01999998 2.45485e-4 9.694e-4 0.01999998 -1.47159e-5 -0.001002967 0 1.50447e-5 -0.001002907 0.01999998 9.98332e-4 9.75243e-5 0.01999998 0.000999987 0 0 9.75908e-4 2.31906e-4 0 -3.3959e-4 -9.43853e-4 0 -3.11464e-4 -9.53489e-4 0.01999998 -6.04231e-4 -8.00667e-4 0.01999998 -6.27667e-4 -7.82442e-4 0 -8.3151e-4 -5.61039e-4 0.01999998 -8.47723e-4 -5.36233e-4 0 -9.75908e-4 -2.31907e-4 0 -9.68647e-4 -2.60578e-4 0.01999998 -0.000999987 0 0.01999998 -9.9833e-4 9.75336e-5 0 3.11749e-4 -9.53411e-4 0 3.39888e-4 -9.43717e-4 0.01999998 6.27878e-4 -7.82234e-4 0.01999998 6.04429e-4 -8.00529e-4 0 8.31606e-4 -5.60903e-4 0 8.47821e-4 -5.36028e-4 0.01999998 9.68666e-4 -2.60495e-4 0 9.75925e-4 -2.31785e-4 0.01999998 9.12568e-4 4.16409e-4 0.01999998 6.0439e-4 8.00556e-4 0.01999998 7.89141e-4 6.14213e-4 0.01999998 7.47912e-4 6.68435e-4 0 8.79474e-4 4.75947e-4 0 3.11701e-4 9.53424e-4 0.01999998 1.79645e-4 9.86866e-4 0 4.90348e-4 8.75063e-4 0 -3.11701e-4 9.53424e-4 0 -1.79645e-4 9.86866e-4 0.01999998 -8.25793e-5 9.96584e-4 0 8.25793e-5 9.96584e-4 0.01999998 -7.47912e-4 6.68435e-4 0.01999998 -4.90348e-4 8.75063e-4 0.01999998 -7.27917e-4 6.90155e-4 0 -5.46948e-4 8.37167e-4 0 -9.12568e-4 4.16409e-4 0 -8.79474e-4 4.75947e-4 0.01999998 -9.75908e-4 2.31905e-4 0.01999998 -0.001000225 -0.001732468 0 -7.92182e-4 -0.001836776 0 -4.01695e-4 -9.15773e-4 0 6.77282e-4 7.35724e-4 0 0.001532316 0.001285493 0 0.001373052 0.001454889 0 3.47705e-4 -0.001969337 0 5.74059e-4 -0.001915216 0 2.45485e-4 -9.694e-4 0 -8.25793e-5 -9.96584e-4 0 -3.47051e-4 -0.001969575 0 -1.16154e-4 -0.001996576 0 1.16454e-4 -0.001996636 0 8.25793e-5 -9.96584e-4 0 7.92612e-4 -0.001835584 0 0.001000702 -0.001731574 0 4.01695e-4 -9.15773e-4 0 0.001195013 -0.00160408 0 5.46948e-4 -8.37167e-4 0 -2.45485e-4 -9.694e-4 0 -5.73412e-4 -0.00191611 0 0.001372754 -0.001454472 0 6.77282e-4 -7.35724e-4 0 -5.46948e-4 -8.37167e-4 0 -0.001194715 -0.001604497 0 0.001532375 -0.001285195 0 0.001671433 -0.001098573 0 7.89141e-4 -6.14213e-4 0 -6.77282e-4 -7.35724e-4 0 -0.001532316 -0.001285493 0 -0.001373052 -0.001454889 0 0.001946151 -4.60714e-4 0 9.45817e-4 -3.24699e-4 0 0.001879274 -6.8346e-4 0 -8.25793e-5 9.96584e-4 0 -1.16454e-4 0.001996636 0 -3.47705e-4 0.001969337 0 -0.001879632 -6.84285e-4 0 -0.001787364 -8.97703e-4 0 -9.45817e-4 -3.24699e-4 0 0.001986563 -2.32203e-4 0 9.86361e-4 -1.64595e-4 0 7.89141e-4 6.14213e-4 0 0.001671075 0.00109893 0 9.86361e-4 1.64595e-4 0 0.001986622 2.32244e-4 0 0.001946508 4.61635e-4 0 -0.001986622 -2.32244e-4 0 -9.86361e-4 -1.64595e-4 0 -0.000999987 0 0 0.001194715 0.001604497 0 4.01695e-4 9.15773e-4 0 5.73412e-4 0.00191611 0 2.45485e-4 9.694e-4 0 -8.79474e-4 4.75947e-4 0 -7.89141e-4 6.14213e-4 0 -0.001671433 0.001098573 0 8.25793e-5 9.96584e-4 0 3.47051e-4 0.001969575 0 1.16154e-4 0.001996576 0 0.001000225 0.001732468 0 7.92182e-4 0.001836776 0 -4.01695e-4 9.15773e-4 0 -5.74059e-4 0.001915216 0 -7.92612e-4 0.001835584 0 -2.45485e-4 9.694e-4 0 -0.001372754 0.001454472 0 -6.77282e-4 7.35724e-4 0 -0.001195013 0.00160408 0 -0.001532375 0.001285195 0 -0.001000702 0.001731574 0 -5.46948e-4 8.37167e-4 0 5.46948e-4 8.37167e-4 0 -9.86361e-4 1.64595e-4 0 -9.45817e-4 3.24699e-4 0 -0.001946151 4.60714e-4 0 -0.001879274 6.8346e-4 0 -0.001986563 2.32203e-4 0 -0.001999974 0 0 8.79474e-4 4.75947e-4 0 9.45817e-4 3.24699e-4 0 0.001787364 8.97703e-4 0 -0.001946508 -4.61635e-4 0 0.001879632 6.84285e-4 0 0.000999987 0 0 0.001999974 0 0 -8.79474e-4 -4.75947e-4 0 -0.001671075 -0.00109893 0 -7.89141e-4 -6.14213e-4 0 8.79474e-4 -4.75947e-4 0 0.001787245 -8.97109e-4 0 -0.001787245 8.97109e-4 0 -2.60167e-4 0 -0.001669287 0.001080393 0 -0.001413643 0.001223444 2.00743e-4 -0.00132811 -1.89469e-4 1.21005e-4 -0.001675367 7.17983e-4 1.88408e-4 -0.001546859 6.49367e-4 0 -0.001575529 -8.05548e-5 3.76963e-4 -0.001645922 -5.64867e-5 6.38209e-4 -0.001578867 2.26217e-4 2.11786e-4 -0.001659154 1.07049e-4 3.67603e-4 -0.00164622 7.28401e-4 7.93101e-4 -0.001411974 8.20982e-4 5.40204e-4 -0.001454353 2.63154e-4 0.001044213 -0.001411974 3.41246e-4 0.00135082 -0.001233875 4.96844e-4 0.00113517 -0.001328289 0.001350641 7.31744e-4 -0.001128911 0.001403272 0.001092791 -8.87152e-4 0.001563966 8.46975e-4 -8.8717e-4 0.001089334 5.9066e-4 -0.001328289 9.77248e-4 7.6191e-4 -0.001328289 0.001978218 0 -5.12529e-4 0.001923203 3.21475e-4 -5.94027e-4 8.11121e-4 0.001849114 -1.8746e-4 4.95695e-4 0.001957416 -1.8746e-4 5.73412e-4 0.00191611 0 0.001921892 5.64967e-4 0 0.001994013 3.26103e-4 -2.75595e-4 0.001909792 6.55647e-4 -1.8746e-4 0.001367568 0.001485586 -1.8746e-4 0.001606583 0.001197814 0 0.001599907 0.001233518 -2.82353e-4 0.00177586 9.61054e-4 -1.8746e-4 0.001787364 8.97703e-4 0 0.00202167 0 -2.21892e-4 0.001986622 2.32244e-4 0 0.001999974 0 0 0.001899659 6.52153e-4 -3.63551e-4 0.001211822 9.44077e-4 -0.001128911 0.001758098 2.90722e-4 -8.83028e-4 0.001684486 0 -9.93355e-4 4.08327e-4 0.001614689 -0.001013278 7.14036e-4 0.001628994 -8.87126e-4 6.16486e-4 0.001407086 -0.001128911 4.13243e-4 3.85084e-4 -0.001600623 5.93415e-4 4.57588e-4 -0.001546144 2.9217e-4 6.75563e-4 -0.001550436 -2.86972e-4 6.74555e-4 -0.001550853 -3.23611e-6 9.08188e-4 -0.001486539 -6.0615e-4 7.7357e-4 -0.001454353 -6.78605e-4 0.001036822 -0.001328289 -3.22132e-4 9.2847e-4 -0.001454353 -0.001040875 0.001129746 -0.001128911 -8.40009e-4 9.11013e-4 -0.001328289 -0.001712024 9.26068e-4 -6.03367e-4 -0.001478374 0.001150071 -7.50477e-4 -0.001564443 8.46079e-4 -8.87173e-4 -0.00131464 0.001022458 -0.001013278 -0.001766383 9.55931e-4 -3.63551e-4 -0.001899659 6.52153e-4 -3.63551e-4 -0.002021729 0 -2.23724e-4 -0.001991689 3.32357e-4 -1.8746e-4 -0.001967251 3.28619e-4 -4.53246e-4 -0.001841068 6.31631e-4 -6.03381e-4 -0.001986563 2.32203e-4 0 -0.001999974 0 0 -6.17693e-4 0.00140655 -0.001128911 -8.40783e-4 0.001285612 -0.001128911 -9.73243e-4 0.001488685 -8.87157e-4 4.53769e-4 1.59926e-4 -0.001621723 5.77802e-5 1.1317e-4 -0.001689255 3.24533e-4 0 -0.001657068 -2.90983e-4 3.68128e-4 -0.001625597 -5.29976e-4 1.83773e-4 -0.00160247 2.20454e-5 0 -0.00170058 0.001857697 0 -7.73467e-4 0.001519262 2.54711e-4 -0.001125216 0.001453578 0 -0.001191616 -4.98688e-4 0.001134335 -0.001328289 -4.90451e-4 5.44826e-4 -0.001550853 -6.83756e-4 4.43402e-4 -0.001520395 -7.89881e-4 0 -0.001532793 9.53682e-4 2.46523e-4 -0.00145334 9.43033e-4 0.001025557 -0.001233875 -8.44564e-4 3.01486e-4 -0.001492321 4.64926e-4 8.65835e-4 -0.001454353 -3.77781e-4 0.001488983 -0.001128911 -8.50546e-4 6.60426e-4 -0.001411974 -0.001090288 5.88902e-4 -0.001328289 -0.001054584 1.72431e-4 -0.001415908 0.001171708 4.03305e-4 -0.001328289 6.76932e-4 0.001037955 -0.001328289 1.01336e-4 0.001235008 -0.001328289 -1.03329e-4 0.001234829 -0.001328289 -3.05179e-4 0.001200973 -0.001328289 -0.001204967 0.001308262 -8.87133e-4 -0.001172363 4.01417e-4 -0.001328289 -0.001189291 0 -0.001354932 -1.66748e-4 0.002012312 -1.8746e-4 -2.2942e-4 0.001990854 0 1.66748e-4 0.002012312 -1.8746e-4 -0.001367568 0.001485586 -1.8746e-4 -0.00159341 0.001240193 -1.8746e-4 -0.001458406 0.001372635 -1.2148e-7 -0.001099944 8.5513e-4 -0.001233875 -0.001351296 7.30526e-4 -0.001128911 -0.001366496 2.2904e-4 -0.001238822 0.001452744 4.99429e-4 -0.001128911 8.39633e-4 0.001286387 -0.001128911 1.26187e-4 0.001531004 -0.001128911 -1.27521e-4 0.001530885 -0.001128911 -0.001453161 4.98174e-4 -0.001128911 -0.001453101 0 -0.001191616 0.001127541 0.001225709 -0.001013278 -0.001918733 5.77755e-4 0 -0.00177586 9.61054e-4 -1.8746e-4 -0.001909792 6.55647e-4 -1.8746e-4 -0.001640498 2.68422e-4 -0.001016736 0.001682043 5.77982e-4 -8.87154e-4 9.72386e-4 0.001489281 -8.87158e-4 -4.78207e-4 0.001886785 -6.03349e-4 -4.93053e-4 0.001946985 -3.63551e-4 -1.61132e-4 0.001939773 -6.03369e-4 1.46389e-4 0.001772582 -8.87155e-4 -1.47371e-4 0.001772463 -8.87149e-4 -4.37125e-4 0.001724004 -8.87176e-4 -7.14909e-4 0.001628637 -8.87129e-4 -0.001978039 0 -5.12267e-4 -0.0016824 5.77059e-4 -8.87155e-4 -0.001677989 0 -9.99011e-4 0.001268267 0.001378357 -7.50479e-4 4.59396e-4 0.001815855 -7.50461e-4 -0.001845121 3.08095e-4 -7.54253e-4 -0.001852869 0 -7.81923e-4 0.001711666 9.26766e-4 -6.03357e-4 0.001535773 0.001195788 -6.03329e-4 0.001840829 6.32391e-4 -6.03383e-4 0.00106424 0.00162971 -6.03355e-4 7.81537e-4 0.001782655 -6.03341e-4 1.60344e-4 0.001939833 -6.03369e-4 -7.82242e-4 0.001782357 -6.03338e-4 -0.001064896 0.001629292 -6.03359e-4 -0.001318573 0.001431763 -6.03362e-4 0.001351952 0.001469075 -4.45705e-4 4.89774e-4 0.001935482 -4.45741e-4 -0.001554787 0.001210153 -5.2836e-4 0.001766383 9.55931e-4 -3.63551e-4 0.001111209 0.00168699 -2.83452e-4 8.06797e-4 0.00183928 -3.63551e-4 1.65859e-4 0.002001583 -3.63551e-4 -1.65859e-4 0.002001583 -3.63551e-4 -8.11121e-4 0.001849114 -1.8746e-4 -8.06797e-4 0.00183928 -3.63551e-4 -0.001098513 0.001681387 -3.63551e-4 -0.001360297 0.001477658 -3.63551e-4 -0.001584947 0.001233577 -3.63551e-4 -4.95695e-4 0.001957416 -1.8746e-4 -6.82353e-4 0.001882255 0 -0.001104414 0.001690387 -1.8746e-4 0.001283824 0.001537859 0 9.03522e-4 0.0017879 0 2.41766e-4 0.001987993 0 -0.001102089 0.001673996 0 -0.001727104 0.001013755 0 2.59028e-4 0 -0.001669466 -0.001079976 0 -0.001413702 -0.001223564 -2.00801e-4 -0.001328051 1.89437e-4 -1.20757e-4 -0.001675426 -6.99318e-4 -2.46411e-4 -0.001548528 -6.49141e-4 0 -0.001575529 8.05548e-5 -3.76963e-4 -0.001645922 5.64867e-5 -6.38209e-4 -0.001578867 -2.72455e-4 -2.84048e-4 -0.001642823 -1.07049e-4 -3.67603e-4 -0.00164622 -7.28401e-4 -7.93101e-4 -0.001411974 -8.20982e-4 -5.40204e-4 -0.001454353 -2.63154e-4 -0.001044213 -0.001411974 -3.41246e-4 -0.00135082 -0.001233875 -4.96844e-4 -0.00113517 -0.001328289 -0.001350641 -7.31744e-4 -0.001128911 -0.001403272 -0.001092791 -8.87152e-4 -0.001563966 -8.46975e-4 -8.8717e-4 -0.001089334 -5.9066e-4 -0.001328289 -9.77248e-4 -7.6191e-4 -0.001328289 -0.001978039 0 -5.12267e-4 -0.001923143 -3.21607e-4 -5.94145e-4 -8.11121e-4 -0.001849114 -1.8746e-4 -4.95695e-4 -0.001957416 -1.8746e-4 -5.73412e-4 -0.00191611 0 -0.001921892 -5.64967e-4 0 -0.001994073 -3.25648e-4 -2.75729e-4 -0.001909792 -6.55647e-4 -1.8746e-4 -0.001367568 -0.001485586 -1.8746e-4 -0.001606583 -0.001197814 0 -0.001599907 -0.001233518 -2.82353e-4 -0.00177586 -9.61054e-4 -1.8746e-4 -0.001787364 -8.97703e-4 0 -0.002021729 0 -2.2378e-4 -0.001986622 -2.32244e-4 0 -0.001999974 0 0 -0.001899659 -6.52153e-4 -3.63551e-4 -0.001211822 -9.44077e-4 -0.001128911 -0.001758098 -2.90397e-4 -8.83127e-4 -0.001685202 0 -9.92389e-4 -4.08327e-4 -0.001614689 -0.001013278 -7.14036e-4 -0.001628994 -8.87126e-4 -6.16486e-4 -0.001407086 -0.001128911 -5.40149e-4 -5.01617e-4 -0.001548647 -2.9217e-4 -6.75563e-4 -0.001550436 2.86972e-4 -6.74555e-4 -0.001550853 3.23611e-6 -9.08188e-4 -0.001486539 6.0615e-4 -7.7357e-4 -0.001454353 6.78605e-4 -0.001036822 -0.001328289 3.22132e-4 -9.2847e-4 -0.001454353 0.001040875 -0.001129746 -0.001128911 8.40009e-4 -9.11013e-4 -0.001328289 0.001712024 -9.26068e-4 -6.03367e-4 0.00153625 -0.001195251 -6.03326e-4 0.001564443 -8.46079e-4 -8.87173e-4 0.001403868 -0.001092016 -8.8715e-4 0.001212656 -9.43008e-4 -0.001128911 0.001766383 -9.55931e-4 -3.63551e-4 0.001899659 -6.52153e-4 -3.63551e-4 0.00202167 0 -2.21837e-4 0.001992762 -3.34272e-4 -2.83253e-4 0.001917541 -3.19985e-4 -6.08775e-4 0.001841068 -6.31631e-4 -6.03381e-4 0.001986563 -2.32203e-4 0 0.001999974 0 0 6.17693e-4 -0.00140655 -0.001128911 8.40783e-4 -0.001285612 -0.001128911 9.73243e-4 -0.001488685 -8.87157e-4 -3.61476e-4 -1.45767e-4 -0.001644194 -5.77802e-5 -1.1317e-4 -0.001689255 2.90983e-4 -3.68128e-4 -0.001625597 5.29742e-4 -1.84174e-4 -0.00160247 -2.60642e-4 0 -0.001669108 0 0 -0.001699984 -0.001856744 0 -7.74495e-4 -0.001519262 -2.54807e-4 -0.001125216 -0.001453101 0 -0.001191616 4.98688e-4 -0.001134335 -0.001328289 4.90451e-4 -5.44826e-4 -0.001550853 7.62075e-4 -4.94022e-4 -0.001486539 7.89103e-4 0 -0.00153315 -9.5369e-4 -2.46087e-4 -0.001453399 -9.43033e-4 -0.001025557 -0.001233875 8.78499e-4 -2.18006e-4 -0.001487851 -4.64926e-4 -8.65835e-4 -0.001454353 3.77781e-4 -0.001488983 -0.001128911 0.001090288 -5.88902e-4 -0.001328289 -0.001171708 -4.03305e-4 -0.001328289 -6.76932e-4 -0.001037955 -0.001328289 -1.01336e-4 -0.001235008 -0.001328289 1.03329e-4 -0.001234829 -0.001328289 3.05179e-4 -0.001200973 -0.001328289 0.001204967 -0.001308262 -8.87133e-4 0.001172363 -4.01417e-4 -0.001328289 9.7849e-4 -7.60311e-4 -0.001328289 0.001215994 -2.03757e-4 -0.001331627 0.00118941 0 -0.001355051 1.66748e-4 -0.002012312 -1.8746e-4 2.2942e-4 -0.001990854 0 -1.66748e-4 -0.002012312 -1.8746e-4 0.001367568 -0.001485586 -1.8746e-4 0.00159341 -0.001240193 -1.8746e-4 0.001458406 -0.001372635 -1.2148e-7 0.001351296 -7.30526e-4 -0.001128911 -0.001452744 -4.99429e-4 -0.001128911 -8.39633e-4 -0.001286387 -0.001128911 -1.26187e-4 -0.001531004 -0.001128911 1.27521e-4 -0.001530885 -0.001128911 0.001453161 -4.98174e-4 -0.001128911 0.001453578 0 -0.001191616 0.001506567 -2.52235e-4 -0.001135647 -0.001127541 -0.001225709 -0.001013278 0.001918733 -5.77755e-4 0 0.00177586 -9.61054e-4 -1.8746e-4 0.001909792 -6.55647e-4 -1.8746e-4 -0.001682043 -5.77982e-4 -8.87154e-4 -9.72386e-4 -0.001489281 -8.87158e-4 4.78207e-4 -0.001886785 -6.03349e-4 4.93053e-4 -0.001946985 -3.63551e-4 1.61132e-4 -0.001939773 -6.03369e-4 -1.46389e-4 -0.001772582 -8.87155e-4 1.47371e-4 -0.001772463 -8.87149e-4 4.37125e-4 -0.001724004 -8.87176e-4 7.14909e-4 -0.001628637 -8.87129e-4 0.001978218 0 -5.12529e-4 0.0016824 -5.77059e-4 -8.87155e-4 0.001750349 -2.87356e-4 -8.93466e-4 0.001677215 0 -0.001000046 -0.001268267 -0.001378357 -7.50479e-4 -4.59396e-4 -0.001815855 -7.50461e-4 0.001853883 0 -7.80847e-4 -0.001711666 -9.26766e-4 -6.03357e-4 -0.001535773 -0.001195788 -6.03329e-4 -0.001840829 -6.32391e-4 -6.03383e-4 -0.00106424 -0.00162971 -6.03355e-4 -7.81537e-4 -0.001782655 -6.03341e-4 -1.60344e-4 -0.001939833 -6.03369e-4 7.82242e-4 -0.001782357 -6.03338e-4 0.001064896 -0.001629292 -6.03359e-4 0.001318573 -0.001431763 -6.03362e-4 -0.001351952 -0.001469075 -4.45705e-4 -4.89774e-4 -0.001935482 -4.45741e-4 -0.001766383 -9.55931e-4 -3.63551e-4 -0.001111209 -0.00168699 -2.83452e-4 -8.06797e-4 -0.00183928 -3.63551e-4 -1.65859e-4 -0.002001583 -3.63551e-4 1.65859e-4 -0.002001583 -3.63551e-4 8.11121e-4 -0.001849114 -1.8746e-4 8.06797e-4 -0.00183928 -3.63551e-4 0.001098692 -0.001695334 -2.82592e-4 0.001360297 -0.001477658 -3.63551e-4 0.001584947 -0.001233577 -3.63551e-4 4.95695e-4 -0.001957416 -1.8746e-4 6.82353e-4 -0.001882255 0 -0.001283824 -0.001537859 0 -9.03522e-4 -0.0017879 0 -2.41766e-4 -0.001987993 0 0.001102089 -0.001673996 0 0.001727104 -0.001013755 0 + + + + + + + + + + 0 0 1 -1.36744e-5 0 1 -3.45252e-5 0 1 4.21939e-5 0 1 -2.1141e-5 0 1 6.61494e-6 0 1 2.62232e-6 0 1 -1.89595e-5 0 1 -1.15178e-5 0 1 -1.20127e-5 0 1 -2.76285e-6 0 1 8.63581e-6 0 1 -1.05549e-5 0 1 1.2731e-5 0 1 3.12582e-6 0 1 1.12046e-5 0 1 -5.76154e-6 0 1 -1.35149e-5 0 1 7.00412e-6 0 1 1.86947e-6 0 1 1.27141e-5 0 1 0.9952703 0.09714347 5.18831e-4 0.9999669 -0.00814867 -2.74674e-4 0.971365 0.2375919 -4.27269e-4 -0.3385433 -0.9409509 -2.13631e-4 -0.01464909 -0.9998927 -2.13633e-4 -0.3104997 -0.9505735 2.13633e-4 0.01498472 -0.9998877 2.13632e-4 -0.6023558 -0.7982276 2.13634e-4 -0.6257329 -0.7800375 -2.13634e-4 -0.8289527 -0.5593188 2.13632e-4 -0.8451174 -0.5345808 -2.13637e-4 -0.9728955 -0.231245 -3.05193e-4 -0.9627148 -0.2705184 1.83113e-4 -0.9999666 -0.008179187 2.74674e-4 -0.9952703 0.09714347 -5.18831e-4 0.3107749 -0.9504836 -2.13633e-4 0.3388524 -0.9408395 2.13633e-4 0.6259522 -0.7798614 2.13636e-4 0.6025654 -0.7980696 -2.13632e-4 0.8290521 -0.5591714 -2.13634e-4 0.8452212 -0.5344167 2.13632e-4 0.9627386 -0.2704336 -1.83117e-4 0.972911 -0.2311804 3.05189e-4 0.9168822 0.399158 1.52595e-4 0.593633 0.8047358 5.49349e-4 0.7842871 0.6203981 6.10388e-5 0.7338644 0.6792961 -1.52596e-4 0.8831897 0.4690161 -6.1038e-5 -0.07446521 0.9972236 -3.35704e-4 0.07446521 0.9972236 3.35704e-4 0.1899498 0.9817937 -4.57784e-4 -0.7337613 0.6794074 -3.05187e-5 -0.4889537 0.8723097 4.27274e-4 -0.7376822 0.6751481 3.05193e-5 -0.3170059 0.9484235 -4.27273e-4 -0.5403426 0.8414451 -6.10384e-5 -0.9097111 0.4152418 -4.27266e-4 -0.8831897 0.4690161 6.1038e-5 -0.971365 0.2375919 4.27269e-4 -0.1899498 0.9817937 4.57784e-4 0.3275036 0.9448498 5.1883e-4 0.4888217 0.8723836 -6.40897e-4 0.1023294 0.4155129 -0.903813 0.1378555 0.5457152 -0.8265536 0.1995939 0.4587607 -0.8658528 0.5606929 0.3037544 -0.7702965 0.6282033 0.4814069 -0.6112348 0.6966049 0.3772501 -0.6102656 0.3962872 0.9179458 0.0182197 0.2423524 0.970173 0.005462884 0.2904496 0.9512476 0.1037647 0.9580868 0.2729935 0.08685737 0.9842078 0.1621475 -0.07101774 0.9435636 0.3307066 0.01791477 0.6842027 0.7291265 0.0155341 0.7943 0.6021798 0.08041882 0.7889774 0.6091289 -0.0804786 0.8806454 0.4733439 0.0202338 0.8915933 0.4407305 0.1040101 0.9972977 0.06946104 -0.02392679 0.9890357 0.1235417 0.08090639 0.9936355 0.0571314 0.0970807 0.9335416 0.3215773 -0.1583929 0.918112 0.1576016 -0.3636374 0.1746903 0.6908265 -0.7015996 0.3233546 0.7223976 -0.6112149 0.2591089 0.5816065 -0.7711009 0.3938804 0.3084573 -0.8658594 0.5046929 0.3881407 -0.7711239 0.4410865 0.236123 -0.8658456 0.1407244 0.1209784 -0.9826297 0.04812884 0.1061155 -0.9931885 0.06491422 0.205699 -0.97646 -0.2417715 0.3157496 -0.9175233 -0.2716491 0.4200627 -0.8658834 -0.1289117 0.3782205 -0.9166957 -0.4285145 0.4709051 -0.7711185 -0.3399206 0.3670826 -0.8658547 -0.8700693 0.4683462 -0.1537247 -0.8171858 0.4350227 -0.3781041 -0.9337786 0.324271 -0.1513468 -0.6990745 0.3710533 -0.61124 -0.678964 0.5281679 -0.5099478 -0.5624702 0.4374632 -0.7016076 -0.9969418 0.07327669 -0.02716213 -0.9860824 0.1661477 0.006042838 -0.9595696 0.1575732 -0.2332314 -0.8732129 0.3051301 -0.3799934 -0.9886761 0.1141731 0.09738737 -0.9936577 0.05731403 0.09674417 -0.2564216 0.5838916 -0.7702718 -0.3490247 0.5337001 -0.7702897 -0.433489 0.6630819 -0.6102538 -0.04675531 0.2011516 -0.9784437 -0.1224423 0.0903058 -0.9883587 0.01654112 0.07458776 -0.9970774 0.1836632 0.05142444 -0.9816432 -0.178416 0.03412061 -0.9833635 0.2947538 0.02920681 -0.9551269 0.2266975 0.07971644 -0.9706975 0.3135567 0.0821278 -0.9460112 0.1857994 0.1826254 -0.9654671 -0.1519866 0.1804612 -0.9717684 0.7828386 0.1371211 -0.6069281 0.8531138 0.0624125 -0.5179783 0.7207993 0.05353039 -0.6910737 0.2553209 0.2016382 -0.9455969 -0.01684641 0.289258 -0.957103 0.1250381 0.2909113 -0.9485443 -0.1223529 0.2950937 -0.947602 -0.2447603 0.07879936 -0.9663763 -0.2154052 0.2318551 -0.948601 -0.2845576 0.1905901 -0.9395224 -0.3302778 0.03842353 -0.9431014 0.4290068 0.03851509 -0.9024798 0.3811857 0.1058713 -0.9184165 0.3809722 0.4143298 -0.8265538 0.2874291 0.3149879 -0.9045259 -0.001831114 0.3743715 -0.927277 -0.3491722 0.1284255 -0.9282164 0.498259 0.07898408 -0.8634231 0.3362635 0.2127817 -0.9174153 0.1900416 0.3436742 -0.9196588 -0.2038696 0.4569671 -0.865805 -0.3411781 0.2602402 -0.9032567 -0.4367648 0.2352139 -0.8682804 -0.4251319 0.06552463 -0.9027566 0.4724068 0.1654751 -0.8657078 0.2741821 0.4184145 -0.8658831 0.04022431 0.4956322 -0.8676006 -0.1194222 0.4846169 -0.8665362 -0.5316514 0.5863121 -0.6112161 -0.0433675 0.4948964 -0.8678692 -0.4701494 0.1617826 -0.8676324 -0.4743001 0.03674519 -0.8795961 0.5851473 0.04156732 -0.8098611 0.6297379 0.1107245 -0.768876 -0.07400786 0.9971377 0.01547294 -0.1119756 0.9885224 0.1014158 0.07693743 0.996891 0.01699882 -0.6726166 0.7396372 0.02288949 -0.7907234 0.6116974 0.02414071 -0.7241618 0.6816484 0.1046201 -0.4443649 0.3454509 -0.8265613 -0.5619817 0.2993024 -0.7710997 -0.5519095 0.09366345 -0.8286272 0.6027038 0.2073206 -0.7705624 0.3446864 0.5353413 -0.7711039 0.04834198 0.6348859 -0.7710921 -0.05292069 0.6355062 -0.7702801 -0.1568067 0.6181017 -0.7703 -0.6010141 0.2098803 -0.771189 -0.5949032 0.04684633 -0.8024311 0.4824208 0.5244155 -0.7016114 -0.951088 0.2935909 0.09610372 -0.8835647 0.4678916 0.01977646 -0.9423516 0.3341279 0.01822012 -0.7024534 0.1134082 -0.7026365 0.7489668 0.2577024 -0.6104411 0.4275202 0.6660622 -0.6112183 -0.2271517 0.8962773 -0.3809056 -0.2424737 0.957596 -0.1556166 -0.07654231 0.921438 -0.3809111 -0.06561625 0.7895012 -0.6102314 0.05899411 0.7892641 -0.6112135 -0.1946838 0.7679008 -0.6102676 -0.318409 0.7254159 -0.6102356 -0.7465537 0.2624932 -0.611355 -0.7223289 0.05527025 -0.6893376 0.5858483 0.6366934 -0.5014014 0.2121979 0.8388121 -0.5013646 -0.8521156 0.1390742 -0.5045369 -0.8458345 0.0669282 -0.5292302 0.9571194 0.07046931 -0.2809923 0.812572 0.4436872 -0.3779795 0.7376579 0.5652529 -0.3692562 0.874157 0.3006431 -0.3813965 0.3761224 0.8451463 -0.3798153 0.5036971 0.7798699 -0.3716078 0.07104939 0.9223299 -0.3798152 -0.3715761 0.8466747 -0.3808846 -0.5058886 0.7739399 -0.3809118 -0.6242139 0.6845203 -0.3765487 0.6598246 0.7155526 -0.2293821 0.2374679 0.9451414 -0.2243142 -0.7495181 0.5886825 -0.3027798 -0.954393 0.07123154 -0.2899314 0.86669 0.4714637 -0.1630041 0.5463823 0.8345429 -0.07074308 0.3996213 0.9035581 -0.1545503 0.08209735 0.9855344 -0.1482635 -0.0815463 0.9844461 -0.1556155 -0.4075486 0.9128795 0.02356052 -0.3967844 0.9046294 -0.1555886 -0.5402585 0.8269903 -0.1555891 -0.6690235 0.7267668 -0.1556202 -0.7790033 0.6098352 -0.1457903 -0.2437533 0.9694896 0.02597147 -0.3385154 0.9347628 0.1078232 -0.5461104 0.8376602 0.009430408 0.6315225 0.76965 0.09390586 0.4628806 0.881936 0.08905422 0.114295 0.9884308 0.09970676 -0.5466372 0.8311718 0.1016914 -0.8592129 0.5007624 0.1048341 -0.1023294 -0.4155129 -0.903813 -0.1378555 -0.5457152 -0.8265536 -0.1995939 -0.4587607 -0.8658528 -0.5606929 -0.3037544 -0.7702965 -0.6282033 -0.4814069 -0.6112348 -0.6966049 -0.3772501 -0.6102656 -0.3962872 -0.9179458 0.0182197 -0.2423524 -0.970173 0.005462884 -0.2904496 -0.9512476 0.1037647 -0.9580974 -0.272966 0.08682787 -0.9842116 -0.1620566 -0.07117062 -0.9435731 -0.3306794 0.01791495 -0.6842027 -0.7291265 0.0155341 -0.7943 -0.6021798 0.08041882 -0.7889774 -0.6091289 -0.0804786 -0.8806454 -0.4733439 0.0202338 -0.8915933 -0.4407305 0.1040101 -0.9972491 -0.06970608 -0.02520895 -0.9890395 -0.1235117 0.08090668 -0.9936693 -0.0571621 0.09671479 -0.9335507 -0.3215499 -0.1583944 -0.9180888 -0.1572366 -0.3638539 -0.1746903 -0.6908265 -0.7015996 -0.3233546 -0.7223976 -0.6112149 -0.2591089 -0.5816065 -0.7711009 -0.3938804 -0.3084573 -0.8658594 -0.5046929 -0.3881407 -0.7711239 -0.4410652 -0.2360974 -0.8658635 -0.1530517 -0.1597048 -0.975228 -0.04806768 -0.1032769 -0.9934905 -0.06277716 -0.206124 -0.9765101 0.2469624 -0.3156919 -0.9161596 0.2716491 -0.4200627 -0.8658834 0.1289117 -0.3782205 -0.9166957 0.4321211 -0.4689882 -0.7702736 0.3412051 -0.3660173 -0.8658004 0.6968271 -0.3768274 -0.6102731 0.6253104 -0.486417 -0.6102339 0.5034211 -0.3914446 -0.7702847 0.8687641 -0.4701507 -0.1555877 0.8132669 -0.4398685 -0.3809366 0.9338921 -0.3183473 -0.1627902 0.9135634 -0.160165 -0.3738304 0.9827964 -0.1666325 -0.07965403 0.8768646 -0.2975071 -0.3776216 0.9890064 -0.1244879 0.07980775 0.9972866 -0.06982654 -0.0233162 0.9936217 -0.05731552 0.09711289 0.2564216 -0.5838916 -0.7702718 0.3490247 -0.5337001 -0.7702897 0.433489 -0.6630819 -0.6102538 0.04675531 -0.2011516 -0.9784437 -0.2295041 -0.2165945 -0.9489019 -0.2038078 -0.07779365 -0.9759153 0.1237225 -0.09234935 -0.9880104 -0.1645879 -0.04577815 -0.9852996 0.004333674 -0.0719946 -0.9973956 0.1804587 -0.03512734 -0.9829552 -0.2946962 -0.03650128 -0.9548937 -0.3003692 -0.1034293 -0.9481986 0.1519568 -0.1804621 -0.9717729 -0.782893 -0.1367285 -0.6069465 -0.8529758 -0.06158733 -0.5183043 -0.720965 -0.05270737 -0.6909642 -0.1225036 -0.2899315 -0.9491747 0.01684641 -0.289258 -0.957103 0.1223529 -0.2950937 -0.947602 0.2472352 -0.08173012 -0.9655025 0.215743 -0.2289885 -0.9492204 0.3177309 -0.2022174 -0.9263668 0.3320482 -0.03811836 -0.942492 -0.4269955 -0.03924781 -0.9034017 -0.3812497 -0.1006839 -0.918973 -0.3809722 -0.4143298 -0.8265538 -0.2886554 -0.3154821 -0.903963 0.001831114 -0.3743715 -0.927277 0.3665323 -0.0961346 -0.9254255 -0.4984036 -0.07855552 -0.8633788 -0.3338529 -0.2144606 -0.9179047 -0.1893724 -0.3459671 -0.9189369 0.2038696 -0.4569671 -0.865805 -0.4723706 -0.1654731 -0.8657279 -0.2741821 -0.4184145 -0.8658831 -0.04022431 -0.4956322 -0.8676006 0.1194222 -0.4846169 -0.8665362 0.5367151 -0.5827079 -0.6102364 0.0433675 -0.4948964 -0.8678692 0.4690714 -0.1628779 -0.8680109 0.4380398 -0.2343557 -0.86787 0.3922296 -0.3061966 -0.8674097 0.46621 -0.03564631 -0.8839557 0.4871523 -0.08252471 -0.8694092 -0.5851806 -0.04040777 -0.8098956 -0.629765 -0.1101745 -0.7689328 0.07400786 -0.9971377 0.01547294 0.1119756 -0.9885224 0.1014158 -0.07693743 -0.996891 0.01699882 0.6740506 -0.7382328 0.02584987 0.7907234 -0.6116974 0.02414071 0.7241618 -0.6816484 0.1046201 0.5609695 -0.3032366 -0.7702992 -0.6027038 -0.2073206 -0.7705624 -0.3446864 -0.5353413 -0.7711039 -0.04834198 -0.6348859 -0.7710921 0.05292069 -0.6355062 -0.7702801 0.1568067 -0.6181017 -0.7703 0.6033656 -0.2072562 -0.7700617 0.587309 -0.04602271 -0.8080533 0.623077 -0.1086783 -0.7745736 -0.4824208 -0.5244155 -0.7016114 0.9537996 -0.2868846 0.08923941 0.8835647 -0.4678916 0.01977646 0.9415361 -0.3361648 0.02243131 -0.7489807 -0.2577072 -0.6104219 -0.4275202 -0.6660622 -0.6112183 0.2271517 -0.8962773 -0.3809056 0.2424737 -0.957596 -0.1556166 0.07654231 -0.921438 -0.3809111 0.06561625 -0.7895012 -0.6102314 -0.05899411 -0.7892641 -0.6112135 0.1946838 -0.7679008 -0.6102676 0.318409 -0.7254159 -0.6102356 0.9570757 -0.07022422 -0.281202 0.7493694 -0.2574603 -0.610049 0.7758588 -0.1352305 -0.6162434 0.7157683 -0.05295091 -0.6963276 -0.5858483 -0.6366934 -0.5014014 -0.2121979 -0.8388121 -0.5013646 0.849527 -0.06122112 -0.5239808 -0.9568876 -0.07010173 -0.281872 -0.812572 -0.4436872 -0.3779795 -0.7376579 -0.5652529 -0.3692562 -0.874157 -0.3006431 -0.3813965 -0.3761224 -0.8451463 -0.3798153 -0.5036971 -0.7798699 -0.3716078 -0.07104939 -0.9223299 -0.3798152 0.3751055 -0.8464364 -0.3779437 0.5057669 -0.778793 -0.3710544 0.6263751 -0.6801193 -0.3809096 0.72977 -0.5677752 -0.3808769 -0.6598246 -0.7155526 -0.2293821 -0.2374679 -0.9451414 -0.2243142 -0.86669 -0.4714637 -0.1630041 -0.5463823 -0.8345429 -0.07074308 -0.3996213 -0.9035581 -0.1545503 -0.08209735 -0.9855344 -0.1482635 0.0815463 -0.9844461 -0.1556155 0.4047108 -0.9140404 0.02719229 0.3984299 -0.9026092 -0.1629427 0.5412017 -0.836691 -0.08395904 0.6693579 -0.7257583 -0.158855 0.7795179 -0.6067495 -0.1555861 0.2437533 -0.9694896 0.02597147 0.3385154 -0.9347628 0.1078232 -0.6315225 -0.76965 0.09390586 -0.4628806 -0.881936 0.08905422 -0.114295 -0.9884308 0.09970676 0.5474478 -0.8324027 0.08606326 0.8592129 -0.5007624 0.1048341 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.06420677 -0.005454719 -0.001484155 -0.0639894 0 -0.00149995 -0.0639894 -0.005463361 -0.00149995 -0.06486046 -0.005428731 -0.001220822 -0.06470328 0 -0.001319169 -0.06465089 -0.005437076 -0.001345992 -0.06442987 -0.005445897 -0.00143367 -0.06447637 0 -0.001418709 -0.06423628 0 -0.001479506 -0.06524509 0 -8.20422e-4 -0.06520968 -0.005414843 -8.72227e-4 -0.06533527 -0.005409896 -6.62588e-4 -0.0649107 0 -0.001183688 -0.06504946 -0.005421221 -0.001060962 -0.06509298 0 -0.001015901 -0.06547379 -0.005404353 -2.1798e-4 -0.06548953 -0.005403757 1.11744e-4 -0.06548428 0 -1.23869e-4 -0.06542319 -0.005406379 -4.41413e-4 -0.06544345 0 -3.68228e-4 -0.06536298 0 -6.02543e-4 -0.06533545 -0.005409896 6.61336e-4 -0.06536298 0 6.02543e-4 -0.06542295 -0.005406379 4.40167e-4 -0.06544345 0 3.68228e-4 -0.06548428 0 1.23869e-4 -0.0649107 0 0.001183688 -0.06509298 0 0.001015901 -0.06505036 -0.005421221 0.001060307 -0.06524509 0 8.20422e-4 -0.06521028 -0.005414843 8.71172e-4 -0.06486135 -0.005428731 0.001220524 -0.06470328 0 0.001319169 -0.0646516 -0.005437076 0.001345992 -0.06447637 0 0.001418709 -0.06423628 0 0.001479506 -0.06443029 -0.005445837 0.001433789 -0.06420677 -0.005454719 0.001484155 -0.0639894 0 0.00149995 -0.0639894 -0.005463361 0.00149995 -0.06292837 -0.005505502 -0.001060307 -0.06306809 0 -0.001183688 -0.06288576 0 -0.001015901 -0.06311738 -0.005497992 -0.001220524 -0.06276845 -0.005511879 -8.71172e-4 -0.06273359 0 -8.20422e-4 -0.06327545 0 -0.001319169 -0.06264328 -0.005516886 -6.61336e-4 -0.06332719 -0.005489706 -0.001345992 -0.06261569 0 -6.02543e-4 -0.06350231 0 -0.001418709 -0.06255578 -0.005520343 -4.40167e-4 -0.0635485 -0.005480885 -0.001433789 -0.06253528 0 -3.68228e-4 -0.06374245 0 -0.001479506 -0.06248909 -0.005522966 -1.11056e-4 -0.0637719 -0.005472004 -0.001484155 -0.06249445 0 -1.23869e-4 -0.0639894 0 -0.00149995 -0.0639894 -0.005463361 -0.00149995 -0.06249445 0 1.23869e-4 -0.062505 -0.00552237 2.1798e-4 -0.06253528 0 3.68228e-4 -0.06255561 -0.005520343 4.41413e-4 -0.06261569 0 6.02543e-4 -0.06264346 -0.005516827 6.62588e-4 -0.06276905 -0.005511879 8.72227e-4 -0.06273359 0 8.20422e-4 -0.06288576 0 0.001015901 -0.06292927 -0.005505502 0.001060962 -0.06306809 0 0.001183688 -0.06311827 -0.005497992 0.001220822 -0.0633279 -0.005489647 0.001345992 -0.06327545 0 0.001319169 -0.06350231 0 0.001418709 -0.06354886 -0.005480885 0.00143367 -0.06374245 0 0.001479506 -0.0637719 -0.005472004 0.001484155 -0.0639894 0 0.00149995 -0.0639894 -0.005463361 0.00149995 -0.05798935 0 -0.01999998 -0.06273359 0 -8.20422e-4 -0.06288576 0 -0.001015901 -0.0639894 0 0.00149995 -0.05798935 0 0.01999998 -0.06998938 0 0.01999998 -0.06249445 0 1.23869e-4 -0.06249445 0 -1.23869e-4 -0.06350231 0 0.001418709 -0.06374245 0 0.001479506 -0.06306809 0 0.001183688 -0.06327545 0 0.001319169 -0.06273359 0 8.20422e-4 -0.06288576 0 0.001015901 -0.06253528 0 3.68228e-4 -0.06261569 0 6.02543e-4 -0.06253528 0 -3.68228e-4 -0.06261569 0 -6.02543e-4 -0.06306809 0 -0.001183688 -0.06327545 0 -0.001319169 -0.06350231 0 -0.001418709 -0.06374245 0 -0.001479506 -0.0639894 0 -0.00149995 -0.06423628 0 -0.001479506 -0.06998938 0 -0.01999998 -0.06548428 0 1.23869e-4 -0.06548428 0 -1.23869e-4 -0.06470328 0 -0.001319169 -0.06447637 0 -0.001418709 -0.06509298 0 -0.001015901 -0.0649107 0 -0.001183688 -0.06536298 0 -6.02543e-4 -0.06524509 0 -8.20422e-4 -0.06544345 0 -3.68228e-4 -0.06544345 0 3.68228e-4 -0.06524509 0 8.20422e-4 -0.06536298 0 6.02543e-4 -0.0649107 0 0.001183688 -0.06509298 0 0.001015901 -0.06447637 0 0.001418709 -0.06470328 0 0.001319169 -0.06423628 0 0.001479506 -0.05798935 0.001498818 -0.01999998 -0.06998938 0 -0.01999998 -0.06998938 0.001775026 -0.01999998 -0.05798935 0 -0.01999998 -0.05798935 0 0.01999998 -0.05798935 0.001499056 -0.01999998 -0.05798935 0.001498103 0.01999998 -0.05798935 0 -0.01999998 -0.06998938 0 0.01999998 -0.05798935 0.001498103 0.01999998 -0.06998938 0.001774191 0.01999998 -0.05798935 0 0.01999998 0.116688 -0.01252394 -0.02999997 0.116688 -0.01252394 0 0.124544 -0.01278138 -0.02999997 0.124544 -0.01278138 0 0.1324 -0.01307636 -0.02999997 0.140256 -0.01340895 -0.02999997 0.1324 -0.01307636 0 0.140256 -0.01340895 0 0.148111 -0.01377928 -0.02999997 0.148111 -0.01377928 0 0.155966 -0.01418727 -0.02999997 0.163821 -0.01463288 -0.02999997 0.155966 -0.01418727 0 0.163821 -0.01463288 0 0.108831 -0.01230424 0 0.108831 -0.01230424 -0.02999997 0.100974 -0.01212227 0 0.100974 -0.01212227 -0.02999997 0.09311747 -0.01197797 0 0.08526039 -0.01187115 0 0.09311747 -0.01197797 -0.02999997 0.08526039 -0.01187115 -0.02999997 0.077403 -0.01180219 0 0.077403 -0.01180219 -0.02999997 0.06954538 -0.01177078 0 0.06954538 -0.01177078 -0.02999997 -0.05275189 0.001369953 -0.02999997 -0.05798935 0.001498818 0 -0.05798935 0.001498818 -0.01999998 -0.06998938 0.001775026 -0.02999997 -0.06998938 0.001775026 -0.01999998 -0.03644466 9.68081e-4 0 -0.02688068 7.24263e-4 -0.02999997 1.06044e-5 -2.70267e-7 -0.02999997 1.06923e-5 2.98315e-6 0 0.1691 -0.007720768 -0.02999997 0.1691 -0.007720768 0.02999997 0.168814 -0.01491636 0.004070878 0.168814 -0.01491886 0.01192504 0.1688141 -0.01492774 0.01948016 0.1688129 -0.01493859 0.02545195 0.168813 -0.0149495 0.02999997 0.168814 -0.01491719 -0.02999997 0.164138 -0.007196485 0.02999997 0.164104 -0.007522165 -0.02999997 0.164104 -0.007522165 0.02999997 0.164488 -0.006286501 0.02999997 0.164333 -0.0065732 -0.02999997 0.164333 -0.0065732 0.02999997 0.164215 -0.006878256 0.02999997 0.164215 -0.006878256 -0.02999997 0.164138 -0.007196485 -0.02999997 0.164907 -0.005784392 -0.02999997 0.164907 -0.005784392 0.02999997 0.165161 -0.005578875 0.02999997 0.164488 -0.006286501 -0.02999997 0.164681 -0.006021618 0.02999997 0.164681 -0.006021618 -0.02999997 0.165738 -0.005275428 0.02999997 0.166052 -0.005182743 0.02999997 0.165738 -0.005275428 -0.02999997 0.165439 -0.005408465 0.02999997 0.165439 -0.005408465 -0.02999997 0.165161 -0.005578875 -0.02999997 0.1670269 -0.005157887 0.02999997 0.166701 -0.005123436 -0.02999997 0.166701 -0.005123436 0.02999997 0.166375 -0.00513184 -0.02999997 0.166052 -0.005182743 -0.02999997 0.166375 -0.00513184 0.02999997 0.16765 -0.00535196 -0.02999997 0.16765 -0.00535196 0.02999997 0.167937 -0.005507767 0.02999997 0.1670269 -0.005157887 -0.02999997 0.167345 -0.005234539 0.02999997 0.167345 -0.005234539 -0.02999997 0.168439 -0.005925953 0.02999997 0.168645 -0.006180167 0.02999997 0.168439 -0.005925953 -0.02999997 0.168202 -0.005700409 0.02999997 0.168202 -0.005700409 -0.02999997 0.167937 -0.005507767 -0.02999997 0.168645 -0.006180167 -0.02999997 0.168815 -0.006458401 0.02999997 0.1689479 -0.006757736 0.02999997 0.168815 -0.006458401 -0.02999997 0.169041 -0.007071614 0.02999997 0.1689479 -0.006757736 -0.02999997 0.169041 -0.007071614 -0.02999997 0.1690919 -0.0073933 0.02999997 0.1691 -0.007720768 0.02999997 0.1690919 -0.0073933 -0.02999997 0.1691 -0.007720768 -0.02999997 0.164104 -0.007522165 -0.02999997 0.163821 -0.01463288 -0.02999997 0.163821 -0.01463288 0 0.164104 -0.007522165 0.02999997 0.163821 -0.01463997 0.02341979 0.163821 -0.01464939 0.02999997 0.1087688 -0.01230424 0.02999997 0.1166116 -0.01252436 0.02999997 0.10093 -0.01212191 0.02999997 0.09308385 -0.01197719 0.02999997 0.08522641 -0.01186996 0.02999997 0.077403 -0.01180219 0 0.07737326 -0.0118007 0.02999997 0.08526039 -0.01187115 0 0.06954532 -0.01177072 0 0.06950455 -0.01176917 0.02999997 0.1244248 -0.0127812 0.02999997 0.1322465 -0.01307582 0.02999997 0.1400454 -0.01340699 0.02999997 0.147843 -0.01377552 0.02999997 0.155968 -0.01420074 0.02999997 0.163821 -0.01464623 0.02999997 0.1560096 -0.01418805 0 0.163821 -0.01463288 0 0.09311747 -0.01197797 0 0.100974 -0.01212227 0 0.108831 -0.01230424 0 0.116688 -0.01252394 0 0.124544 -0.01278138 0 0.1324 -0.01307636 0 0.140256 -0.01340895 0 0.148111 -0.01377928 0 0.06954538 -0.01177078 -3.06211e-5 0.06286597 -0.01150536 0.02999997 0.06950455 -0.01176917 0.02999997 0.06286597 -0.01150536 -0.02999997 0.06954538 -0.01177078 -0.02999997 0.06330275 -5.14052e-4 0.02999997 0.06286597 -0.01150536 0.02999997 0.06286597 -0.01150536 -0.02999997 0.06330275 -5.14052e-4 -0.02999997 0.05334889 3.31686e-4 0.02999997 0.05331069 -1.16969e-4 -0.02999997 0.05331069 -1.16969e-4 0.02999997 0.05369919 0.001626253 0.02999997 0.0535441 0.001206457 -0.02999997 0.0535441 0.001206457 0.02999997 0.0534265 7.72148e-4 0.02999997 0.0534265 7.72148e-4 -0.02999997 0.05334889 3.31686e-4 -0.02999997 0.05412006 0.002417862 -0.02999997 0.05412006 0.002417862 0.02999997 0.0543825 0.002782821 0.02999997 0.05369919 0.001626253 -0.02999997 0.05389237 0.002032399 0.02999997 0.05389237 0.002032399 -0.02999997 0.05499875 0.003433644 0.02999997 0.0553478 0.003714799 0.02999997 0.05499875 0.003433644 -0.02999997 0.05467557 0.003121614 0.02999997 0.05467557 0.003121614 -0.02999997 0.0543825 0.002782821 -0.02999997 0.05652689 0.00435692 0.02999997 0.05611515 0.004178464 -0.02999997 0.05611515 0.004178464 0.02999997 0.05572128 0.003964066 -0.02999997 0.0553478 0.003714799 -0.02999997 0.05572128 0.003964066 0.02999997 0.05738967 0.004599571 -0.02999997 0.05738967 0.004599571 0.02999997 0.05783414 0.004661917 0.02999997 0.05652689 0.00435692 -0.02999997 0.05695289 0.004497587 0.02999997 0.05695289 0.004497587 -0.02999997 0.05873066 0.004666328 0.02999997 0.05917507 0.004608452 0.02999997 0.05873066 0.004666328 -0.02999997 0.05828195 0.004684388 0.02999997 0.05828195 0.004684388 -0.02999997 0.05783414 0.004661917 -0.02999997 0.06045424 0.004199624 0.02999997 0.06004017 0.004374325 -0.02999997 0.06004017 0.004374325 0.02999997 0.05961346 0.004510521 -0.02999997 0.05917507 0.004608452 -0.02999997 0.05961346 0.004510521 0.02999997 0.06122595 0.003743588 -0.02999997 0.06122595 0.003743588 0.02999997 0.06157737 0.003466308 0.02999997 0.06045424 0.004199624 -0.02999997 0.06084966 0.003989517 0.02999997 0.06084966 0.003989517 -0.02999997 0.06190389 0.003157079 -0.02999997 0.06220006 0.002821624 0.02999997 0.06220006 0.002821624 -0.02999997 0.06190389 0.003157079 0.02999997 0.06157737 0.003466308 -0.02999997 0.0624662 0.002458989 -0.02999997 0.0624662 0.002458989 0.02999997 0.06269758 0.002076148 0.02999997 0.06269758 0.002076148 -0.02999997 0.0628947 0.001671671 0.02999997 0.0628947 0.001671671 -0.02999997 0.06305408 0.001253843 -0.02999997 0.06305408 0.001253843 0.02999997 0.06317579 8.20566e-4 0.02999997 0.06317579 8.20566e-4 -0.02999997 0.06325799 3.81094e-4 0.02999997 0.06325799 3.81094e-4 -0.02999997 0.06330031 -6.37785e-5 -0.02999997 0.06330031 -6.37785e-5 0.02999997 0.06330275 -5.14052e-4 0.02999997 0.06330275 -5.14052e-4 -0.02999997 0.0529136 -0.01010906 0.02999997 0.05331069 -1.16969e-4 0.02999997 0.05331069 -1.16969e-4 -0.02999997 0.0529136 -0.01010906 -0.02999997 -0.06998938 -0.005224943 0.02999997 -0.06548959 -0.005403757 8.41852e-7 -0.06998938 -0.005224943 -0.02999997 -0.0639894 -0.005463361 0.00149995 -0.06420677 -0.005454719 0.001484155 -0.06264328 -0.005516886 -6.61336e-4 0.0529136 -0.01010906 -0.02999997 -0.06276845 -0.005511879 -8.71172e-4 -0.06442987 -0.005445897 -0.00143367 -0.06420677 -0.005454719 -0.001484155 -0.0639894 -0.005463361 -0.00149995 -0.06486046 -0.005428731 -0.001220822 -0.06465089 -0.005437076 -0.001345992 -0.06520968 -0.005414843 -8.72227e-4 -0.06504946 -0.005421221 -0.001060962 -0.06542319 -0.005406379 -4.41413e-4 -0.06533527 -0.005409896 -6.62588e-4 -0.06547379 -0.005404353 -2.1798e-4 -0.06542295 -0.005406379 4.40167e-4 -0.06547325 -0.005404412 2.17343e-4 -0.06521028 -0.005414843 8.71172e-4 -0.06533545 -0.005409896 6.61336e-4 -0.06486135 -0.005428731 0.001220524 -0.06505036 -0.005421221 0.001060307 -0.06443029 -0.005445837 0.001433789 -0.0646516 -0.005437076 0.001345992 -0.0637719 -0.005472004 0.001484155 0.0529136 -0.01010906 0.02999997 -0.06311827 -0.005497992 0.001220822 -0.0633279 -0.005489647 0.001345992 -0.06354886 -0.005480885 0.00143367 -0.06276905 -0.005511879 8.72227e-4 -0.06292927 -0.005505502 0.001060962 -0.06255561 -0.005520343 4.41413e-4 -0.06264346 -0.005516827 6.62588e-4 -0.06248909 -0.005522966 -8.41852e-7 -0.062505 -0.00552237 2.1798e-4 -0.06250548 -0.00552237 -2.17343e-4 -0.06255578 -0.005520343 -4.40167e-4 -0.06292837 -0.005505502 -0.001060307 -0.06311738 -0.005497992 -0.001220524 -0.0635485 -0.005480885 -0.001433789 -0.06332719 -0.005489706 -0.001345992 -0.0637719 -0.005472004 -0.001484155 -0.06998938 0 -0.01999998 -0.06998938 0.001775026 -0.02999997 -0.06998938 0.001775026 -0.01999998 -0.06998938 0.001773297 0.02999997 -0.06998938 0 0.01999998 -0.06998938 0.001774191 0.01999998 -0.06998938 -0.005224943 0.02999997 -0.06998938 -0.005224943 -0.02999997 1.06041e-5 -2.67245e-7 0.02999997 1.06934e-5 3.02357e-6 0 -0.05798935 0.001498103 0.01999998 -0.06998938 0.001773297 0.02999997 -0.06998938 0.001774191 0.01999998 -0.02640616 7.11192e-4 0.02999997 -0.03654068 9.70506e-4 0 -0.05798935 0.001498818 0 -0.0524885 0.001361727 0.02999997 7.66199e-5 5.03618e-4 -0.02999997 2.02361e-4 8.33915e-4 0.02999997 7.96569e-5 5.12264e-4 0.02999997 1.04594e-5 -2.6375e-7 -0.02999997 2.34658e-5 2.5493e-4 -0.02999997 2.48509e-5 2.59205e-4 0.02999997 2.19032e-4 8.67461e-4 -0.02999997 7.87383e-4 0.001690328 0.02999997 4.92753e-4 0.001312077 -0.02999997 8.21425e-4 0.001731157 -0.02999997 4.65574e-4 0.001271784 0.02999997 0.001307547 0.002282798 -0.02999997 0.001316428 0.002294778 0.02999997 0.001946032 0.002931773 -0.02999997 0.001871228 0.00285685 0.02999997 0.002341568 0.003291428 0.02999997 0.00271517 0.003610968 -0.02999997 0.002843976 0.003712415 0.02999997 0.003531396 0.004236996 -0.02999997 0.00344628 0.004175424 0.02999997 0.004303216 0.004763066 0.02999997 0.004394948 0.004822313 -0.02999997 0.005282819 0.005364954 -0.02999997 0.005188465 0.0053097 0.02999997 0.006109058 0.005831837 0.02999997 0.006211578 0.005886495 -0.02999997 0.007145762 0.006374716 -0.02999997 0.007024466 0.006314158 0.02999997 0.008422255 0.006993234 -0.02999997 0.008298039 0.006936013 0.02999997 0.009746849 0.007577478 -0.02999997 0.01008194 0.007721543 0.02999997 0.01118195 0.008165538 -0.02999997 0.01202791 0.00848937 0.02999997 0.01301485 0.008848726 -0.02999997 0.01387429 0.009148538 0.02999997 0.01511073 0.00955981 -0.02999997 0.0158388 0.009790599 0.02999997 0.01738029 0.01025456 -0.02999997 0.01784813 0.01038944 0.02999997 0.01913982 0.01074892 -0.02999997 0.01997792 0.01097416 0.02999997 0.02089905 0.01121014 -0.02999997 0.02201181 0.01148474 0.02999997 0.02254652 0.01161235 -0.02999997 0.02389693 0.01192563 0.02999997 0.02445989 0.01205128 -0.02999997 0.02592337 0.01236349 0.02999997 0.0266363 0.01251006 -0.02999997 0.027561 0.01269412 0.02999997 0.02833896 0.01284438 -0.02999997 0.02945107 0.01305288 0.02999997 0.03030532 0.01320618 -0.02999997 0.031744 0.01345443 0.02999997 0.03248584 0.01357632 -0.02999997 0.03443294 0.01388192 -0.02999997 0.03393733 0.01380705 0.02999997 0.03611963 0.01412993 0.02999997 0.03663009 0.0142014 -0.02999997 0.03894293 0.01450937 0.02999997 0.03934633 0.0145592 -0.02999997 0.04168438 0.01483547 0.02999997 0.04218733 0.01489228 -0.02999997 0.04363745 0.01504641 0.02999997 0.04464691 0.01514822 -0.02999997 0.04739397 0.01540327 -0.02999997 0.04596531 0.01527553 0.02999997 0.05090475 0.01567876 -0.02999997 0.04917293 0.01555025 0.02999997 0.05243772 0.0157814 0.02999997 0.05417698 0.01588636 -0.02999997 0.0550453 0.01593369 0.02999997 0.05733966 0.01604586 -0.02999997 0.0575813 0.0160554 0.02999997 0.06052243 0.01616251 -0.02999997 0.0598939 0.01614153 0.02999997 0.06211298 0.01620441 0.02999997 0.06325858 0.01622909 -0.02999997 0.06571209 0.01626199 -0.02999997 0.06498003 0.01625502 0.02999997 0.06784915 0.01627051 0.02999997 0.0687251 0.01626992 -0.02999997 0.07017189 0.01625835 0.02999997 0.07186138 0.01623654 -0.02999997 0.07251989 0.01622468 0.02999997 0.07486534 0.01616984 -0.02999997 0.07474571 0.01617169 0.02999997 0.07694387 0.01610177 0.02999997 0.08009368 0.01596969 -0.02999997 0.07763069 0.01607584 -0.02999997 0.08031469 0.01596027 0.02999997 0.08283102 0.01582515 -0.02999997 0.08396953 0.01575779 0.02999997 0.08528232 0.01567345 -0.02999997 0.08645582 0.0155934 0.02999997 0.08791422 0.01548856 -0.02999997 0.08948218 0.01536858 0.02999997 0.09309458 0.01505786 0.02999997 0.09131938 0.01521617 -0.02999997 0.09436172 0.01493942 -0.02999997 0.09555858 0.01482331 0.02999997 0.09697329 0.01468139 -0.02999997 0.09826713 0.01454597 0.02999997 0.1008222 0.01426529 -0.02999997 0.1011471 0.01422631 0.02999997 0.1042097 0.01386278 0.02999997 0.1042327 0.01385897 -0.02999997 0.1077257 0.01341348 0.02999997 0.1070676 0.01350039 -0.02999997 0.1103038 0.01306468 -0.02999997 0.1106653 0.01301503 0.02999997 0.1133709 0.01263064 -0.02999997 0.1144974 0.01246625 0.02999997 0.1163343 0.01219004 -0.02999997 0.1187229 0.01182359 0.02999997 0.1192497 0.01174044 -0.02999997 0.1223652 0.01124149 -0.02999997 0.1254827 0.01072722 -0.02999997 0.1232377 0.01110088 0.02999997 0.1276201 0.01036614 0.02999997 0.1305127 0.009869277 -0.02999997 0.1317518 0.009651601 0.02999997 0.1362391 0.008853852 0.02999997 0.1375335 0.008621156 -0.02999997 0.1403034 0.008114695 0.02999997 0.1448135 0.007280468 -0.02999997 0.1447779 0.007286608 0.02999997 0.1514231 0.006031692 0.02999997 0.151682 0.005981266 -0.02999997 0.1587878 0.004611968 0.02999997 0.1593849 0.004496455 -0.02999997 0.168893 0.002630829 -0.02999997 0.1661778 0.003166377 0.02999997 0.172531 0.001909255 0.02999997 0.1786863 6.82784e-4 -0.02999997 0.1788981 6.40142e-4 0.02999997 0.1914348 -0.001882255 0.02999997 0.1924169 -0.002080798 -0.02999997 0.2024165 -0.004104852 -0.02999997 0.2045742 -0.00454241 0.02999997 0.2117243 -0.005994796 -0.02999997 0.2181063 -0.007293999 0.02999997 0.2221989 -0.008130967 -0.02999997 0.2257267 -0.008859992 0.02999997 0.2281776 -0.009374856 -0.02999997 0.2304381 -0.009857296 0.02999997 0.2318961 -0.01017272 -0.02999997 0.2319239 -0.0101794 0.01999998 0.231955 -0.01018619 0.02999997 0.231904 -0.01017504 0.00999999 0.231896 -0.01017326 0 1.06041e-5 -2.67245e-7 0.02999997 0.2525539 -0.01148265 0 0.231896 -0.01017326 0 0.2830109 -0.01342916 0.02999997 0.275011 -0.01293015 0.01999998 0.283011 -0.01345247 0.01999998 0.275011 -0.01294952 0 0.231904 -0.01017504 0.00999999 0.2544564 -0.01159679 0.02999997 0.231955 -0.01018619 0.02999997 0.2319239 -0.0101794 0.01999998 0.2522749 -0.01146346 0 0.2566248 -0.0117436 -0.02999997 0.231896 -0.01017326 -0.02999997 0.231896 -0.01017326 0 0.275011 -0.01294738 0 0.275011 -0.01294738 -0.01999998 0.283011 -0.01347678 -0.01999998 0.283011 -0.01347678 -0.02999997 0.1971527 -0.0167005 0.02779853 0.206761 -0.01733517 0.02713131 0.2254108 -0.01861894 0.02581286 0.2337906 -0.01926916 0.02598917 0.233972 -0.01927357 0.0258857 0.185191 -0.01605999 0.02999997 0.1877726 -0.0160973 0.0284112 0.1790271 -0.01555061 0.02895343 0.193494 -0.01669406 0.02999997 0.1688129 -0.01494973 0.02999997 0.1688138 -0.01493 0.02152526 0.2162968 -0.017982 0.02645552 0.2252968 -0.01860094 0 0.2065986 -0.01731413 0 0.1971738 -0.01669085 0 0.1877524 -0.01608479 0 0.168814 -0.01491457 0 0.1778872 -0.01546782 0 0.2350424 -0.01929908 0.008037745 0.2160139 -0.01795369 0 0.235068 -0.01929968 0 0.201875 -0.01738089 0.02999997 0.2066749 -0.0175721 0.02913928 0.210333 -0.01812028 0.02999997 0.234622 -0.01928907 0.02541798 0.234735 -0.01929175 0.0253036 0.234836 -0.0192942 0.02517867 0.2349179 -0.01929616 0.0250411 0.234974 -0.01929748 0.02489036 0.234244 -0.01927995 0.02571475 0.234375 -0.01928317 0.02562218 0.234501 -0.01928615 0.02552366 0.234109 -0.01927679 0.02580237 0.2335489 -0.01926338 0.02611565 0.233009 -0.01925045 0.02636957 0.232459 -0.01923739 0.02659946 0.2256039 -0.01886749 0.0277968 0.231901 -0.01922398 0.02681177 0.231339 -0.01921057 0.02701026 0.230773 -0.01919698 0.02719789 0.229058 -0.01915609 0.02771157 0.228483 -0.01914227 0.02787005 0.230203 -0.01918339 0.02737635 0.227907 -0.0191285 0.0280236 0.227329 -0.01911467 0.02817255 0.226751 -0.0191009 0.02831757 0.216139 -0.0182116 0.02847719 0.224789 -0.01905399 0.02878117 0.22282 -0.01900684 0.02921187 0.2208459 -0.0189597 0.02961647 0.218867 -0.01891237 0.02999997 0.23499 -0.01929801 0.02473092 0.229632 -0.01916974 0.02754729 0.176963 -0.01547837 0.02999997 0.2350106 -0.01929837 0.01891142 0.2113312 -0.01763141 0 0.208569 -0.01744639 -0.02999997 0.2350683 -0.01929461 0 0.221819 -0.01835638 -0.02999997 0.235068 -0.0192998 -0.02999997 0.197211 -0.01669305 0 0.1886224 -0.0161364 -0.02999997 0.1827414 -0.01576626 0 0.168814 -0.01491719 -0.02999997 0.168814 -0.01491719 0 0.1691 -0.007720768 -0.02999997 0.225581 -0.00883162 -0.02999997 0.2237579 -0.008453369 -0.02999997 0.1409166 0.008001685 -0.02999997 0.06004017 0.004374325 -0.02999997 0.1689479 -0.006757736 -0.02999997 0.124818 0.01083767 -0.02999997 0.05873066 0.004666328 -0.02999997 0.1198045 0.01165223 -0.02999997 0.05828195 0.004684388 -0.02999997 0.01868104 0.01062268 -0.02999997 0.110806 0.01299452 -0.02999997 0.0218212 0.01143759 -0.02999997 0.02848619 0.01287174 -0.02999997 0.02744281 0.01267063 -0.02999997 0.0430957 0.01498883 -0.02999997 0.08985859 0.01533603 -0.02999997 0.09533298 0.01484525 -0.02999997 0.03776609 0.01435434 -0.02999997 0.05342608 0.01584136 -0.02999997 0.04823088 0.01547199 -0.02999997 0.07370322 0.01619869 -0.02999997 0.06033337 0.01615577 -0.02999997 0.0566914 0.01601475 -0.02999997 0.07655817 0.016115 -0.02999997 0.06192874 0.01619976 -0.02999997 0.06467109 0.01625037 -0.02999997 0.06598073 0.01626342 -0.02999997 0.07229161 0.01622819 -0.02999997 0.06333643 0.01622968 -0.02999997 0.07106941 0.01624745 -0.02999997 0.06912106 0.01626604 -0.02999997 0.06797474 0.01626968 -0.02999997 0.0670675 0.01626873 -0.02999997 0.0700832 0.01625859 -0.02999997 0.05901432 0.01611095 -0.02999997 0.07514476 0.01616019 -0.02999997 0.05783927 0.01606529 -0.02999997 0.05584496 0.01597404 -0.02999997 0.0547586 0.01591759 -0.02999997 0.07826721 0.01605027 -0.02999997 0.07981175 0.01598209 -0.02999997 0.05223876 0.01576703 -0.02999997 0.08139419 0.01590377 -0.02999997 0.05126667 0.01570177 -0.02999997 0.05026346 0.01563036 -0.02999997 0.0828616 0.01582258 -0.02999997 0.04928368 0.01555603 -0.02999997 0.08418554 0.01574337 -0.02999997 0.08583855 0.0156359 -0.02999997 0.04687523 0.01535612 -0.02999997 0.04576647 0.01525515 -0.02999997 0.08753854 0.01551556 -0.02999997 0.04484349 0.01516681 -0.02999997 0.08881801 0.0154187 -0.02999997 0.0439375 0.01507645 -0.02999997 0.04230427 0.01490372 -0.02999997 0.09103792 0.01523828 -0.02999997 0.04130339 0.01479148 -0.02999997 0.09224253 0.01513373 -0.02999997 0.04012835 0.01465362 -0.02999997 0.0932852 0.01503968 -0.02999997 0.03880965 0.01449024 -0.02999997 0.09430563 0.01494437 -0.02999997 0.03676033 0.01421827 -0.02999997 0.09650802 0.014728 -0.02999997 0.09769141 0.0146057 -0.02999997 0.03548699 0.01403784 -0.02999997 0.09888476 0.01447838 -0.02999997 0.03439873 0.01387614 -0.02999997 0.03359717 0.01375281 -0.02999997 0.100011 0.0143544 -0.02999997 0.1014791 0.01418769 -0.02999997 0.03272294 0.01361399 -0.02999997 0.03186589 0.01347315 -0.02999997 0.03096318 0.01332002 -0.02999997 0.1028782 0.01402294 -0.02999997 0.1043571 0.01384353 -0.02999997 0.0300154 0.01315325 -0.02999997 0.02924132 0.01301276 -0.02999997 0.1058824 0.01365208 -0.02999997 0.1070746 0.01349836 -0.02999997 0.02641087 0.01246333 -0.02999997 0.1081665 0.01335406 -0.02999997 0.02562886 0.01230096 -0.02999997 0.1093808 0.0131908 -0.02999997 0.02476274 0.01211565 -0.02999997 0.1125215 0.01275229 -0.02999997 0.02398788 0.01194417 -0.02999997 0.1143473 0.01248687 -0.02999997 0.02337002 0.0118041 -0.02999997 0.1163706 0.01218456 -0.02999997 0.02260565 0.01162594 -0.02999997 0.168815 -0.006458401 -0.02999997 0.02105951 0.01124906 -0.02999997 0.1182111 0.01190191 -0.02999997 0.02018451 0.01102572 -0.02999997 0.01944613 0.01083052 -0.02999997 0.1216296 0.01136034 -0.02999997 0.1228848 0.01115643 -0.02999997 0.01792412 0.01040965 -0.02999997 0.01639723 0.009959757 -0.02999997 0.01727408 0.01022166 -0.02999997 0.1267895 0.01050668 -0.02999997 0.01540482 0.009650826 -0.02999997 0.1289453 0.01013863 -0.02999997 0.01466369 0.009410619 -0.02999997 0.01416939 0.00924617 -0.02999997 0.1306346 0.009845972 -0.02999997 0.01367259 0.009077012 -0.02999997 0.01318365 0.008906543 -0.02999997 0.05917507 0.004608452 -0.02999997 0.1321018 0.009589195 -0.02999997 0.01255542 0.008681535 -0.02999997 0.05783414 0.004661917 -0.02999997 0.1336635 0.009313225 -0.02999997 0.135255 0.009029686 -0.02999997 0.01194274 0.008454442 -0.02999997 0.01145148 0.008267223 -0.02999997 0.01096683 0.008077621 -0.02999997 0.01048004 0.007881879 -0.02999997 0.1375681 0.008613109 -0.02999997 0.05961346 0.004510521 -0.02999997 0.009998977 0.007683157 -0.02999997 0.009513556 0.007476866 -0.02999997 0.1393162 0.008295118 -0.02999997 0.009035229 0.007267594 -0.02999997 0.008558452 0.007052659 -0.02999997 0.05738967 0.004599571 -0.02999997 0.008086204 0.006833016 -0.02999997 0.007614254 0.00660634 -0.02999997 0.143108 0.00759679 -0.02999997 0.007144629 0.006373167 -0.02999997 0.06045424 0.004199624 -0.02999997 0.006676971 0.0061329 -0.02999997 0.05695289 0.004497587 -0.02999997 0.006214559 0.005887031 -0.02999997 0.06084966 0.003989517 -0.02999997 0.005749225 0.005630612 -0.02999997 0.1453883 0.00717163 -0.02999997 0.05652689 0.00435692 -0.02999997 0.06122595 0.003743588 -0.02999997 0.005291581 0.005368709 -0.02999997 0.1474811 0.00677824 -0.02999997 0.05611515 0.004178464 -0.02999997 0.004839479 0.00509876 -0.02999997 0.06157737 0.003466308 -0.02999997 0.1500655 0.006288707 -0.02999997 0.05572128 0.003964066 -0.02999997 0.004394114 0.004819929 -0.02999997 0.06190389 0.003157079 -0.02999997 0.0039559 0.004530966 -0.02999997 0.0553478 0.003714799 -0.02999997 0.05499875 0.003433644 -0.02999997 0.003638684 0.004310607 -0.02999997 0.06220006 0.002821624 -0.02999997 0.003427147 0.004158496 -0.02999997 0.003218472 0.004003584 -0.02999997 0.1530341 0.005721807 -0.02999997 0.003012955 0.00384587 -0.02999997 0.0624662 0.002458989 -0.02999997 0.05467557 0.003121614 -0.02999997 0.002810657 0.003685235 -0.02999997 0.002611696 0.003521502 -0.02999997 0.0543825 0.002782821 -0.02999997 0.002415776 0.00335443 -0.02999997 0.1554827 0.005250692 -0.02999997 0.002222716 0.003183662 -0.02999997 0.002032339 0.003008961 -0.02999997 0.06269758 0.002076148 -0.02999997 0.1571689 0.004924952 -0.02999997 0.001844346 0.002830028 -0.02999997 0.05412006 0.002417862 -0.02999997 0.001658618 0.002646565 -0.02999997 0.001474857 0.002458214 -0.02999997 0.05389237 0.002032399 -0.02999997 0.0628947 0.001671671 -0.02999997 0.1594243 0.004487156 -0.02999997 0.001292884 0.002264738 -0.02999997 0.05369919 0.001626253 -0.02999997 0.001112461 0.002065837 -0.02999997 9.3315e-4 0.001861214 -0.02999997 7.55601e-4 0.001650571 -0.02999997 0.0535441 0.001206457 -0.02999997 0.06305408 0.001253843 -0.02999997 5.84297e-4 0.001433789 -0.02999997 4.24918e-4 0.001210749 -0.02999997 0.0534265 7.72148e-4 -0.02999997 0.161477 0.004087269 -0.02999997 0.1635736 0.00367695 -0.02999997 0.06317579 8.20566e-4 -0.02999997 0.1657325 0.003253102 -0.02999997 0.06325799 3.81094e-4 -0.02999997 0.06330031 -6.37785e-5 -0.02999997 0.1681994 0.002767026 -0.02999997 0.06330275 -5.14052e-4 -0.02999997 0.166375 -0.00513184 -0.02999997 0.166052 -0.005182743 -0.02999997 0.1712842 0.002156674 -0.02999997 0.1741375 0.001589715 -0.02999997 0.1767755 0.001063764 -0.02999997 0.1808542 2.47373e-4 -0.02999997 0.1856078 -7.08228e-4 -0.02999997 0.166701 -0.005123436 -0.02999997 0.1897957 -0.001552283 -0.02999997 0.1942214 -0.002445936 -0.02999997 0.1670269 -0.005157887 -0.02999997 0.1990503 -0.003422617 -0.02999997 0.167345 -0.005234539 -0.02999997 0.16765 -0.00535196 -0.02999997 0.167937 -0.005507767 -0.02999997 0.2035104 -0.004326879 -0.02999997 0.168202 -0.005700409 -0.02999997 0.168439 -0.005925953 -0.02999997 0.2068103 -0.004996538 -0.02999997 0.168645 -0.006180167 -0.02999997 0.2099849 -0.00564146 -0.02999997 0.169041 -0.007071614 -0.02999997 0.213945 -0.006446838 -0.02999997 0.1690919 -0.0073933 -0.02999997 0.2181375 -0.007300913 -0.02999997 0.221223 -0.007931947 -0.02999997 0.2268872 -0.009104669 -0.02999997 0.2282143 -0.009384214 -0.02999997 0.168814 -0.01491719 -0.02999997 0.2295725 -0.009672522 -0.02999997 0.2310668 -0.009993433 -0.02999997 0.182066 -0.01572686 -0.02999997 0.2318962 -0.01017326 -0.02999997 0.247746 -0.01117545 -0.02999997 0.195318 -0.01656985 -0.02999997 0.208569 -0.01744639 -0.02999997 0.221819 -0.01835638 -0.02999997 0.264785 -0.01227664 -0.02999997 0.235068 -0.0192998 -0.02999997 0.283011 -0.01347678 -0.02999997 0.283011 -0.02044606 -0.02999997 0.164104 -0.007522165 -0.02999997 0.155966 -0.01418727 -0.02999997 0.163821 -0.01463288 -0.02999997 0.148111 -0.01377928 -0.02999997 0.140256 -0.01340895 -0.02999997 0.1324 -0.01307636 -0.02999997 0.124544 -0.01278138 -0.02999997 0.165439 -0.005408465 -0.02999997 0.165738 -0.005275428 -0.02999997 0.09311747 -0.01197797 -0.02999997 0.164681 -0.006021618 -0.02999997 0.164907 -0.005784392 -0.02999997 0.100974 -0.01212227 -0.02999997 0.164215 -0.006878256 -0.02999997 0.164333 -0.0065732 -0.02999997 0.164488 -0.006286501 -0.02999997 0.108831 -0.01230424 -0.02999997 0.164138 -0.007196485 -0.02999997 0.116688 -0.01252394 -0.02999997 0.08526039 -0.01187115 -0.02999997 0.077403 -0.01180219 -0.02999997 0.165161 -0.005578875 -0.02999997 0.06286597 -0.01150536 -0.02999997 0.06954538 -0.01177078 -0.02999997 0.0529136 -0.01010906 -0.02999997 0.05331069 -1.16969e-4 -0.02999997 1.06044e-5 -2.70267e-7 -0.02999997 -0.01775187 4.82345e-4 -0.02999997 -0.03533935 9.39101e-4 -0.02999997 -0.06998938 -0.005224943 -0.02999997 -0.05275189 0.001369953 -0.02999997 2.83291e-4 9.81475e-4 -0.02999997 1.65244e-4 7.45782e-4 -0.02999997 0.05334889 3.31686e-4 -0.02999997 7.66199e-5 5.03618e-4 -0.02999997 2.34658e-5 2.5493e-4 -0.02999997 -0.06998938 0.001775026 -0.02999997 0.2157626 -0.006816923 0.02999997 0.1691 -0.007720768 0.02999997 0.1899071 -0.001574873 0.02999997 0.166701 -0.005123436 0.02999997 0.2009288 -0.003803253 0.02999997 0.167345 -0.005234539 0.02999997 0.1971715 -0.003042399 0.02999997 0.169041 -0.007071614 0.02999997 0.1689479 -0.006757736 0.02999997 0.168439 -0.005925953 0.02999997 0.2188968 -0.007456004 0.02999997 0.164488 -0.006286501 0.02999997 0.09310096 -0.01197719 0.02999997 0.164681 -0.006021618 0.02999997 0.166375 -0.00513184 0.02999997 0.1811829 1.81491e-4 0.02999997 0.1856184 -7.10144e-4 0.02999997 0.1785271 7.13796e-4 0.02999997 0.06330275 -5.14052e-4 0.02999997 0.06004017 0.004374325 0.02999997 0.06317579 8.20566e-4 0.02999997 0.1636703 0.003658294 0.02999997 0.05828195 0.004684388 0.02999997 0.08991152 0.0153318 0.02999997 0.04403108 0.01508635 0.02999997 0.03111189 0.01334601 0.02999997 0.1031162 0.01399445 0.02999997 0.164907 -0.005784392 0.02999997 0.0624662 0.002458989 0.02999997 0.1555162 0.005244791 0.02999997 0.164215 -0.006878256 0.02999997 0.164138 -0.007196485 0.02999997 0.100964 -0.01212239 0.02999997 0.164333 -0.0065732 0.02999997 0.108825 -0.01230549 0.02999997 0.164104 -0.007522165 0.02999997 0.116686 -0.01252657 0.02999997 0.132403 -0.0130825 0.02999997 0.124545 -0.01278549 0.02999997 0.148114 -0.01379007 0.02999997 0.140259 -0.0134173 0.02999997 0.155968 -0.01420074 0.02999997 0.163821 -0.01464939 0.02999997 0.165161 -0.005578875 0.02999997 0.08523678 -0.01186984 0.02999997 0.165439 -0.005408465 0.02999997 0.07737129 -0.01180058 0.02999997 0.06286597 -0.01150536 0.02999997 0.06950455 -0.01176917 0.02999997 0.165738 -0.005275428 0.02999997 0.166052 -0.005182743 0.02999997 0.05369919 0.001626253 0.02999997 0.0012452 0.002213418 0.02999997 0.05389237 0.002032399 0.02999997 0.1453131 0.007185697 0.02999997 0.06084966 0.003989517 0.02999997 0.150774 0.006154239 0.02999997 0.06157737 0.003466308 0.02999997 0.05917507 0.004608452 0.02999997 0.136227 0.008855342 0.02999997 0.1411427 0.007960259 0.02999997 0.1264026 0.01057225 0.02999997 0.05873066 0.004666328 0.02999997 0.1312938 0.009730875 0.02999997 0.1225069 0.01121878 0.02999997 0.1132246 0.01265096 0.02999997 0.117701 0.01198112 0.02999997 0.1065471 0.01356637 0.02999997 0.02741867 0.01266598 0.02999997 0.02549284 0.01227241 0.02999997 0.1092715 0.01320594 0.02999997 0.04505598 0.01518797 0.02999997 0.08743715 0.01552289 0.02999997 0.09726309 0.01465046 0.02999997 0.0365408 0.01418811 0.02999997 0.01970976 0.01090115 0.02999997 0.06452161 0.0162478 0.02999997 0.06852453 0.01626855 0.02999997 0.01252382 0.008669853 0.02999997 0.01301062 0.008845388 0.02999997 0.01362073 0.009059727 0.02999997 0.002956449 0.003801226 0.02999997 0.003161668 0.003960311 0.02999997 0.05499875 0.003433644 0.02999997 0.008201837 0.006887853 0.02999997 0.05783414 0.004661917 0.02999997 0.05738967 0.004599571 0.02999997 0.001602768 0.00259 0.02999997 0.001422345 0.002403259 0.02999997 7.35022e-4 0.001624882 0.02999997 9.01115e-4 0.001824498 0.02999997 0.001071393 0.002020537 0.02999997 0.0535441 0.001206457 0.02999997 5.7502e-4 0.001420199 0.02999997 0.0534265 7.72148e-4 0.02999997 4.24302e-4 0.001208662 0.02999997 2.86753e-4 9.88164e-4 0.02999997 1.69543e-4 7.56145e-4 0.02999997 7.96569e-5 5.12264e-4 0.02999997 0.05334889 3.31686e-4 0.02999997 2.48509e-5 2.59205e-4 0.02999997 1.06041e-5 -2.67245e-7 0.02999997 0.05331069 -1.16969e-4 0.02999997 -0.01748847 4.74996e-4 0.02999997 -0.06998938 -0.005224943 0.02999997 -0.03498816 9.29011e-4 0.02999997 0.00178647 0.002773582 0.02999997 0.001973509 0.002953648 0.02999997 0.05412006 0.002417862 0.02999997 0.0553478 0.003714799 0.02999997 0.003791928 0.004418015 0.02999997 0.004109561 0.004634022 0.02999997 -0.0524885 0.001361727 0.02999997 -0.06998938 0.001773297 0.02999997 0.0529136 -0.01010906 0.02999997 0.002163827 0.003130316 0.02999997 0.002357423 0.003303349 0.02999997 0.0543825 0.002782821 0.02999997 0.002554178 0.003472805 0.02999997 0.05467557 0.003121614 0.02999997 0.002753913 0.003638744 0.02999997 0.00336939 0.004116058 0.02999997 0.003579556 0.004268586 0.02999997 0.05572128 0.003964066 0.02999997 0.004545986 0.004916548 0.02999997 0.004984498 0.005186676 0.02999997 0.05611515 0.004178464 0.02999997 0.05652689 0.00435692 0.02999997 0.005438208 0.005454003 0.02999997 0.05695289 0.004497587 0.02999997 0.005888044 0.005708932 0.02999997 0.006344258 0.005957961 0.02999997 0.006804645 0.006200373 0.02999997 0.007266819 0.006435394 0.02999997 0.007732391 0.006664335 0.02999997 0.008672893 0.007105171 0.02999997 0.009147644 0.007317602 0.02999997 0.009625077 0.007525086 0.02999997 0.01010167 0.007726252 0.02999997 0.01057946 0.00792247 0.02999997 0.01106297 0.008115708 0.02999997 0.01154971 0.008305072 0.02999997 0.01203447 0.008488893 0.02999997 0.01424568 0.009272456 0.02999997 0.01473522 0.009434878 0.02999997 0.01534497 0.009632229 0.02999997 0.01620578 0.009901821 0.02999997 0.01707583 0.01016366 0.02999997 0.01781892 0.01037979 0.02999997 0.01870065 0.01062804 0.02999997 0.02061206 0.01113587 0.02999997 0.02147245 0.0113523 0.02999997 0.02223145 0.01153689 0.02999997 0.02288639 0.0116921 0.02999997 0.02365612 0.01186954 0.02999997 0.02450132 0.01205849 0.02999997 0.02848047 0.01287084 0.02999997 0.1055182 0.01369786 0.02999997 0.1078741 0.01339334 0.02999997 0.03009021 0.01316714 0.02999997 0.1044362 0.0138334 0.02999997 0.02922296 0.0130096 0.02999997 0.03202295 0.01349967 0.02999997 0.03277516 0.01362276 0.02999997 0.03366041 0.0137633 0.02999997 0.1004881 0.014301 0.02999997 0.0355978 0.01405411 0.02999997 0.098787 0.01448917 0.02999997 0.03470289 0.01392263 0.02999997 0.09581273 0.01479786 0.02999997 0.03753685 0.01432412 0.02999997 0.09342694 0.01502656 0.02999997 0.03951025 0.01457798 0.02999997 0.09449136 0.01492655 0.02999997 0.03853553 0.01445519 0.02999997 0.09227341 0.01513093 0.02999997 0.04039609 0.01468551 0.02999997 0.09120261 0.01522409 0.02999997 0.04222172 0.01489472 0.02999997 0.04125809 0.01478624 0.02999997 0.04312705 0.01499247 0.02999997 0.08862507 0.01543354 0.02999997 0.04604917 0.01528191 0.02999997 0.04703861 0.01537096 0.02999997 0.08531653 0.01567053 0.02999997 0.08629542 0.01560425 0.02999997 0.04837441 0.01548445 0.02999997 0.04951542 0.01557445 0.02999997 0.08418112 0.01574361 0.02999997 0.08262711 0.01583606 0.02999997 0.05059593 0.01565504 0.02999997 0.05202537 0.01575362 0.02999997 0.08095574 0.01592624 0.02999997 0.05344772 0.01584279 0.02999997 0.0792663 0.016007 0.02999997 0.05452483 0.0159046 0.02999997 0.05544179 0.01595366 0.02999997 0.07782036 0.0160678 0.02999997 0.07651174 0.01611626 0.02999997 0.05645918 0.0160039 0.02999997 0.05772864 0.01606065 0.02999997 0.07539349 0.0161525 0.02999997 0.05928605 0.01612073 0.02999997 0.07423853 0.0161851 0.02999997 0.0604906 0.01615983 0.02999997 0.07313513 0.01621115 0.02999997 0.06135886 0.0161845 0.02999997 0.07224917 0.01622873 0.02999997 0.06222712 0.01620596 0.02999997 0.07097482 0.01624888 0.02999997 0.06333577 0.01622909 0.02999997 0.06969726 0.01626205 0.02999997 0.06591528 0.01626276 0.02999997 0.06731528 0.01626914 0.02999997 0.283011 -0.01342719 0.02999997 0.283011 -0.02044606 0.02999997 0.218867 -0.01891237 0.02999997 0.1017767 0.01415294 0.02999997 0.02637964 0.01245689 0.02999997 0.1103975 0.01305133 0.02999997 0.1114513 0.01290428 0.02999997 0.1148642 0.0124104 0.02999997 0.1163084 0.01219391 0.02999997 0.119129 0.01175892 0.02999997 0.1205864 0.01152837 0.02999997 0.1246005 0.01087433 0.02999997 0.12799 0.0103026 0.02999997 0.1296071 0.01002436 0.02999997 0.1329817 0.009434103 0.02999997 0.1345887 0.009148836 0.02999997 0.05961346 0.004510521 0.02999997 0.1387625 0.008396446 0.02999997 0.06045424 0.004199624 0.02999997 0.1431269 0.007593333 0.02999997 0.1467824 0.006909906 0.02999997 0.06122595 0.003743588 0.02999997 0.1486423 0.006558895 0.02999997 0.06190389 0.003157079 0.02999997 0.06220006 0.002821624 0.02999997 0.1534186 0.005648493 0.02999997 0.06269758 0.002076148 0.02999997 0.1574817 0.004864752 0.02999997 0.1594117 0.004490137 0.02999997 0.0628947 0.001671671 0.02999997 0.06305408 0.001253843 0.02999997 0.1611893 0.004143655 0.02999997 0.1666512 0.0030725 0.02999997 0.06325799 3.81094e-4 0.02999997 0.06330031 -6.37785e-5 0.02999997 0.1694577 0.002518355 0.02999997 0.1718128 0.002051711 0.02999997 0.1751581 0.001386463 0.02999997 0.1930275 -0.002204716 0.02999997 0.1670269 -0.005157887 0.02999997 0.16765 -0.00535196 0.02999997 0.167937 -0.005507767 0.02999997 0.2043555 -0.004498362 0.02999997 0.168202 -0.005700409 0.02999997 0.210333 -0.01812028 0.02999997 0.264384 -0.0122295 0.02999997 0.168645 -0.006180167 0.02999997 0.2078801 -0.005214095 0.02999997 0.168815 -0.006458401 0.02999997 0.2122465 -0.006101548 0.02999997 0.1690919 -0.0073933 0.02999997 0.2214033 -0.007968723 0.02999997 0.2231959 -0.008337318 0.02999997 0.2253395 -0.008781254 0.02999997 0.2273007 -0.009191155 0.02999997 0.168813 -0.0149495 0.02999997 0.2297335 -0.009706735 0.02999997 0.176963 -0.01547837 0.02999997 0.2310507 -0.009989857 0.02999997 0.2319552 -0.01018619 0.02999997 0.193494 -0.01669406 0.02999997 0.185191 -0.01605999 0.02999997 0.247366 -0.01114904 0.02999997 0.201875 -0.01738089 0.02999997 0.283011 -0.01345247 0.01999998 0.275011 -0.01292979 0.01999998 0.275011 -0.01549994 0.01999998 0.283011 -0.01549994 0.01999998 0.275011 -0.01294738 0 0.275011 -0.01549994 0.01999998 0.275011 -0.01294296 0.009441137 0.275011 -0.01294738 -0.01999998 0.275011 -0.01549994 -0.01999998 0.275011 -0.01292979 0.01999998 0.283011 -0.01347678 -0.01999998 0.283011 -0.01549994 -0.01999998 0.275011 -0.01549994 -0.01999998 0.275011 -0.01294738 -0.01999998 0.283011 -0.01549994 -0.01999998 0.283011 -0.01347678 -0.01999998 0.283011 -0.01347678 -0.02999997 0.283011 -0.01345247 0.01999998 0.283011 -0.01549994 0.01999998 0.283011 -0.01342719 0.02999997 0.283011 -0.02044606 -0.02999997 0.283011 -0.02044606 0.02999997 0.2350106 -0.01929831 0.01890861 0.277907 -0.02032405 0.001015901 0.2208459 -0.0189597 0.02961647 0.218867 -0.01891237 0.02999997 0.283011 -0.02044606 0.02999997 0.235068 -0.01929974 0 0.277557 -0.0203157 -3.68228e-4 0.277637 -0.02031755 -6.02543e-4 0.234836 -0.0192942 0.02517867 0.2349179 -0.01929616 0.0250411 0.224789 -0.01905399 0.02878117 0.22282 -0.01900684 0.02921187 0.226751 -0.0191009 0.02831757 0.227907 -0.0191285 0.0280236 0.227329 -0.01911467 0.02817255 0.229058 -0.01915609 0.02771157 0.228483 -0.01914227 0.02787005 0.230203 -0.01918339 0.02737635 0.229632 -0.01916974 0.02754729 0.231339 -0.01921057 0.02701026 0.230773 -0.01919698 0.02719789 0.232459 -0.01923739 0.02659946 0.231901 -0.01922398 0.02681177 0.233009 -0.01925045 0.02636957 0.2337906 -0.01926916 0.02598911 0.2335489 -0.01926338 0.02611565 0.233972 -0.01927357 0.0258857 0.234244 -0.01927995 0.02571475 0.234109 -0.01927679 0.02580237 0.234501 -0.01928615 0.02552366 0.234375 -0.01928317 0.02562218 0.234735 -0.01929175 0.0253036 0.234622 -0.01928907 0.02541798 0.23499 -0.01929789 0.02473092 0.234974 -0.01929748 0.02489036 0.277516 -0.02031469 -1.23869e-4 0.277637 -0.02031755 6.02543e-4 0.2350424 -0.01929903 0.008037209 0.277755 -0.02032047 8.20422e-4 0.277907 -0.02032405 -0.001015901 0.235068 -0.0192998 -0.02999997 0.277755 -0.02032047 -8.20422e-4 0.278089 -0.02032846 -0.001183688 0.283011 -0.02044606 -0.02999997 0.278524 -0.02033877 -0.001418709 0.278764 -0.02034455 -0.001479506 0.279011 -0.02035045 -0.00149995 0.277516 -0.02031469 1.23869e-4 0.278297 -0.02033334 -0.001319169 0.277557 -0.0203157 3.68228e-4 0.278089 -0.02032846 0.001183688 0.278297 -0.02033334 0.001319169 0.278764 -0.02034455 0.001479506 0.278524 -0.02033877 0.001418709 0.280505 -0.02038615 -1.23869e-4 0.280505 -0.02038615 1.23869e-4 0.279011 -0.02035045 0.00149995 0.279498 -0.02036207 0.001418709 0.279258 -0.02035635 0.001479506 0.279932 -0.02037245 0.001183688 0.279725 -0.02036756 0.001319169 0.280266 -0.02038049 8.20422e-4 0.280114 -0.02037686 0.001015901 0.280465 -0.02038526 3.68228e-4 0.280384 -0.02038329 6.02543e-4 0.280384 -0.02038329 -6.02543e-4 0.280465 -0.02038526 -3.68228e-4 0.280114 -0.02037686 -0.001015901 0.280266 -0.02038049 -8.20422e-4 0.279725 -0.02036756 -0.001319169 0.279932 -0.02037245 -0.001183688 0.279258 -0.02035635 -0.001479506 0.279498 -0.02036207 -0.001418709 0.278523 -0.01549994 -0.00141865 0.275011 -0.01549994 -0.01999998 0.278764 -0.01549994 -0.001479506 0.279011 -0.01549994 0.00149995 0.279258 -0.01549994 0.001479506 0.283011 -0.01549994 0.01999998 0.280505 -0.01549994 -1.23869e-4 0.283011 -0.01549994 -0.01999998 0.275011 -0.01549994 0.01999998 0.280384 -0.01549994 -6.02543e-4 0.280266 -0.01549994 -8.20422e-4 0.279725 -0.01549994 0.001319169 0.279498 -0.01549994 0.001418709 0.280114 -0.01549994 0.001015901 0.279932 -0.01549994 0.001183688 0.280384 -0.01549994 6.02543e-4 0.280266 -0.01549994 8.20422e-4 0.280505 -0.01549994 1.23869e-4 0.280465 -0.01549994 3.68228e-4 0.280465 -0.01549994 -3.68228e-4 0.280114 -0.01549994 -0.001015901 0.279932 -0.01549994 -0.001183688 0.279725 -0.01549994 -0.001319169 0.279498 -0.01549994 -0.001418709 0.279258 -0.01549994 -0.001479506 0.279011 -0.01549994 -0.00149995 0.277516 -0.01549994 1.24368e-4 0.278089 -0.01549994 -0.001183509 0.278297 -0.01549994 -0.00131911 0.277755 -0.01549994 -8.20098e-4 0.277907 -0.01549994 -0.001015663 0.277556 -0.01549994 -3.67777e-4 0.277637 -0.01549994 -6.02148e-4 0.277516 -0.01549994 -1.23382e-4 0.277637 -0.01549994 6.02986e-4 0.277557 -0.01549994 3.68712e-4 0.277907 -0.01549994 0.001016199 0.277755 -0.01549994 8.20801e-4 0.278297 -0.01549994 0.001319289 0.27809 -0.01549994 0.001183867 0.278764 -0.01549994 0.001479506 0.278524 -0.01549994 0.001418769 0.279932 -0.02037245 -0.001183688 0.280114 -0.01549994 -0.001015901 0.280114 -0.02037686 -0.001015901 0.280266 -0.01549994 -8.20422e-4 0.279932 -0.01549994 -0.001183688 0.280266 -0.02038049 -8.20422e-4 0.279725 -0.02036756 -0.001319169 0.280384 -0.01549994 -6.02543e-4 0.279725 -0.01549994 -0.001319169 0.280384 -0.02038329 -6.02543e-4 0.279498 -0.02036207 -0.001418709 0.280465 -0.01549994 -3.68228e-4 0.279498 -0.01549994 -0.001418709 0.280465 -0.02038526 -3.68228e-4 0.279258 -0.02035635 -0.001479506 0.280505 -0.01549994 -1.23869e-4 0.279258 -0.01549994 -0.001479506 0.280505 -0.02038615 -1.23869e-4 0.279011 -0.02035045 -0.00149995 0.279011 -0.01549994 -0.00149995 0.280505 -0.01549994 1.23869e-4 0.280505 -0.02038615 1.23869e-4 0.280465 -0.01549994 3.68228e-4 0.280465 -0.02038526 3.68228e-4 0.280384 -0.01549994 6.02543e-4 0.280384 -0.02038329 6.02543e-4 0.280266 -0.02038049 8.20422e-4 0.280266 -0.01549994 8.20422e-4 0.280114 -0.01549994 0.001015901 0.280114 -0.02037686 0.001015901 0.279932 -0.01549994 0.001183688 0.279932 -0.02037245 0.001183688 0.279725 -0.02036756 0.001319169 0.279725 -0.01549994 0.001319169 0.279498 -0.01549994 0.001418709 0.279498 -0.02036207 0.001418709 0.279258 -0.01549994 0.001479506 0.279258 -0.02035635 0.001479506 0.279011 -0.01549994 0.00149995 0.279011 -0.02035045 0.00149995 0.278764 -0.02034455 -0.001479506 0.279011 -0.01549994 -0.00149995 0.279011 -0.02035045 -0.00149995 0.278089 -0.02032846 -0.001183688 0.278297 -0.01549994 -0.00131911 0.278297 -0.02033334 -0.001319169 0.278524 -0.02033877 -0.001418709 0.278523 -0.01549994 -0.00141865 0.278764 -0.01549994 -0.001479506 0.277755 -0.01549994 -8.20098e-4 0.277755 -0.02032047 -8.20422e-4 0.277637 -0.02031755 -6.02543e-4 0.278089 -0.01549994 -0.001183509 0.277907 -0.02032405 -0.001015901 0.277907 -0.01549994 -0.001015663 0.277516 -0.02031469 -1.23869e-4 0.277516 -0.02031469 1.23869e-4 0.277516 -0.01549994 -1.23382e-4 0.277557 -0.0203157 -3.68228e-4 0.277556 -0.01549994 -3.67777e-4 0.277637 -0.01549994 -6.02148e-4 0.277755 -0.02032047 8.20422e-4 0.277637 -0.01549994 6.02986e-4 0.277637 -0.02031755 6.02543e-4 0.277557 -0.01549994 3.68712e-4 0.277516 -0.01549994 1.24368e-4 0.277557 -0.0203157 3.68228e-4 0.27809 -0.01549994 0.001183867 0.277907 -0.01549994 0.001016199 0.278089 -0.02032846 0.001183688 0.277755 -0.01549994 8.20801e-4 0.277907 -0.02032405 0.001015901 0.278297 -0.02033334 0.001319169 0.278297 -0.01549994 0.001319289 0.278524 -0.02033877 0.001418709 0.278524 -0.01549994 0.001418769 0.278764 -0.01549994 0.001479506 0.278764 -0.02034455 0.001479506 0.279011 -0.02035045 0.00149995 0.279011 -0.01549994 0.00149995 + + + + + + + + + + -0.1451162 -1.52593e-4 -0.9894147 -0.08231043 3.66231e-4 -0.9966068 -0.07248324 0 -0.9973697 -0.579811 -7.0195e-4 -0.8147508 -0.4759114 6.40896e-4 -0.8794931 -0.44045 -6.1038e-4 -0.897777 -0.2938092 -4.57789e-4 -0.9558641 -0.324666 5.7987e-4 -0.9458286 -0.1645573 4.57782e-4 -0.9863675 -0.8372344 7.01943e-4 -0.5468438 -0.8122045 -6.7142e-4 -0.5833724 -0.8961053 -6.40904e-4 -0.443841 -0.6141729 6.40908e-4 -0.7891713 -0.7055026 -7.01932e-4 -0.7087071 -0.7357538 6.7142e-4 -0.6772488 -0.9908096 -8.54541e-4 -0.1352616 -0.997087 -0.001037597 0.076267 -0.9965811 9.15583e-4 -0.08261603 -0.9550262 -6.40896e-4 -0.2965211 -0.9693507 8.54537e-4 -0.2456795 -0.9157328 7.93503e-4 -0.4017871 -0.8968431 -7.01946e-4 0.4423482 -0.9157329 6.71426e-4 0.4017871 -0.9585046 -8.54527e-4 0.2850763 -0.9693747 6.1038e-4 0.2455863 -0.9965711 7.62978e-4 0.08273732 -0.6141728 6.71427e-4 0.7891712 -0.735769 6.71433e-4 0.6772322 -0.7065876 -6.71429e-4 0.7076253 -0.8372344 6.71423e-4 0.5468438 -0.8132504 -6.71427e-4 0.5819134 -0.5805623 -6.40898e-4 0.8142156 -0.4759113 6.71415e-4 0.879493 -0.4407929 -5.7987e-4 0.8976087 -0.324666 6.10389e-4 0.9458286 -0.1645276 4.88303e-4 0.9863725 -0.2933844 -4.27274e-4 0.9559945 -0.1446294 -1.52595e-4 0.9894859 -0.08231043 3.66231e-4 0.9966068 -0.07248324 0 0.9973697 -0.7086461 6.71413e-4 0.7055637 -0.7356662 -6.40904e-4 0.677344 -0.6141728 -6.71427e-4 0.7891712 -0.5832831 6.40903e-4 0.8122687 -0.8146232 6.71426e-4 0.5799902 -0.8371372 -6.409e-4 0.5469927 -0.4759841 -6.71432e-4 0.8794537 -0.8976145 7.01929e-4 0.4407808 -0.4440245 5.79866e-4 0.8960145 -0.9158151 -6.71419e-4 0.4015999 -0.3246933 -6.10383e-4 0.9458192 -0.9588837 8.54538e-4 0.2837983 -0.2969818 4.27268e-4 0.954883 -0.96942 -6.10389e-4 0.2454069 -0.1644979 -4.88306e-4 0.9863774 -0.9971427 0.00100708 0.07553416 -0.1483524 1.52595e-4 0.9889346 -0.9965711 -7.62978e-4 0.08273732 -0.08231043 -3.66231e-4 0.9966068 -0.0724529 0 0.9973719 -0.9965811 -9.15583e-4 -0.08261603 -0.9908598 8.24012e-4 -0.1348938 -0.9694053 -8.54532e-4 -0.2454642 -0.9553662 6.40899e-4 -0.2954238 -0.8968914 6.40898e-4 -0.4422504 -0.9158037 -7.62966e-4 -0.4016255 -0.8135807 6.71422e-4 -0.5814517 -0.8371371 -6.71419e-4 -0.5469927 -0.7356511 -6.40891e-4 -0.6773605 -0.7075643 7.01949e-4 -0.7066488 -0.5825191 6.71421e-4 -0.8128167 -0.6141729 -6.40908e-4 -0.7891713 -0.443682 6.10376e-4 -0.896184 -0.4759842 -6.10393e-4 -0.8794537 -0.3246933 -5.79864e-4 -0.9458192 -0.2973781 4.57787e-4 -0.9547597 -0.1488434 1.52597e-4 -0.9888609 -0.1644979 -4.57787e-4 -0.9863774 -0.08231043 -3.66231e-4 -0.9966068 -0.0724529 0 -0.9973719 0 1 0 0 0 -1 -1 0 0 0 0 1 0 0 1 -0.0303362 -0.9995399 0 -0.03512763 -0.9993829 0 -0.03988879 -0.9992042 0 -0.04229897 -0.9991051 0 -0.04708969 -0.9988907 0 -0.05187135 -0.9986539 0 -0.0566371 -0.9983949 0 -0.05187159 -0.9986538 0 -0.02554422 -0.9996737 0 -0.02075314 -0.9997847 0 -0.01596158 -0.9998727 0 -0.01117008 -0.9999377 0 -0.008781135 -0.9999614 0 -0.003996133 -0.999992 0 -0.008781135 -0.9999614 0 -0.003996133 -0.9999921 0 0.02459591 0.9996975 0 0.02349108 0.999724 -5.78941e-4 0.02300888 0.9997353 0 0.02462869 0.9996967 5.73378e-6 0.02495187 0.9996888 -1.70054e-4 0.02693325 0.9996373 -1.08486e-4 0.0264641 0.9996497 3.12366e-4 0.9992112 -0.03971207 0 0.9992122 -0.03968667 -1.08014e-5 0.9992182 -0.03953582 -6.4314e-5 0.9992067 -0.0398252 1.34802e-4 0.9992128 -0.03967392 -1.17991e-4 0.9992113 -0.03971117 5.28168e-7 -0.9854614 0.1698997 0 -0.9945986 0.1037967 0 -0.9945892 0.1038872 0 -0.8458361 0.5334429 0 -0.9079907 0.4189904 0 -0.9079737 0.4190272 0 -0.9543687 0.2986313 0 -0.9543887 0.2985669 0 -0.9854716 0.1698405 0 -0.6779479 0.7351099 0 -0.6779797 0.7350807 0 -0.577027 0.8167251 0 -0.7678009 0.6406886 0 -0.7677733 0.6407216 0 -0.3455654 0.9383947 0 -0.2198281 0.9755387 0 -0.3456022 0.9383812 0 -0.4655163 0.8850394 0 -0.4655402 0.8850268 0 0.1700826 0.9854298 0 0.03967428 0.9992128 0 -0.09088516 0.9958614 0 0.4190272 0.9079737 0 0.533722 0.8456601 0 0.2974425 0.9547398 0 0.297406 0.9547512 0 0.7346712 0.6784234 0 0.8169646 0.5766881 0 0.734656 0.6784398 0 0.6400554 0.7683289 0 0.6401064 0.7682863 0 0.5337576 0.8456376 0 0.81694 0.5767228 0 0.8854585 0.4647185 0 0.9382947 0.3458369 0 0.8855094 0.4646216 0 0.9753316 0.2207451 0 0.9383281 0.3457464 0 0.9753103 0.2208388 0 0.9958866 0.09061002 0 0.9997034 0.02435398 0 0.9958724 0.0907641 0 0.9997012 0.02444547 0 0.9992091 -0.0397675 0 0.9992127 -0.03967547 -5.66796e-5 0.9992109 -0.03971958 -1.20394e-5 -0.008825004 -0.9999611 4.10572e-5 -0.008781135 -0.9999615 2.96926e-5 -0.004003882 -0.9999921 4.70962e-5 -0.05663609 -0.9983948 -5.02203e-4 -0.0522688 -0.998633 -4.96145e-4 -0.05685424 -0.9983824 -4.45266e-4 -0.003999412 -0.999992 4.58206e-5 -0.01602256 -0.9998717 0 -0.0112006 -0.9999373 3.05194e-5 -0.02081418 -0.9997834 0 -0.02554422 -0.9996737 -6.10376e-5 -0.02563571 -0.9996713 -3.05187e-5 -0.0303362 -0.9995399 -9.15581e-5 -0.03042769 -0.999537 -6.10386e-5 -0.03512763 -0.9993829 -1.22077e-4 -0.03521907 -0.9993796 -9.15574e-5 -0.03991925 -0.999203 -1.83116e-4 -0.04001069 -0.9991993 -1.52596e-4 -0.04229897 -0.999105 -2.311e-4 -0.04242843 -0.9990995 -1.98166e-4 -0.04708969 -0.9988906 -2.95336e-4 -0.04720687 -0.9988851 -2.65577e-4 -0.0516833 -0.9986635 -3.36388e-4 -0.03970593 -0.9992115 -7.29351e-7 -0.03970271 -0.9992116 0 -0.03970271 -0.9992116 0 0.9992113 -0.03970879 0 -0.9916042 0.1293104 0 -0.9963969 0.08481335 0 -0.921459 0.3884758 0 -0.9525938 0.3042452 0 -0.9525849 0.304273 0 -0.976031 0.2176316 0 -0.9916082 0.1292805 0 -0.8373088 0.5467304 0 -0.8373178 0.5467164 0 -0.7848929 0.6196314 0 -0.9214699 0.3884499 0 -0.8829142 0.4695345 0 -0.6616297 0.7498307 0 -0.5917897 0.8060925 0 -0.7261765 0.6875085 0 -0.7261613 0.6875246 0 -0.7848781 0.6196503 0 -0.355975 0.9344955 0 -0.4383166 0.8988206 0 -0.5170831 0.8559353 0 -0.1833579 0.9830462 0 -0.09451669 0.9955233 0 -0.2707686 0.9626446 0 0.08471989 0.9964049 0 0.1737157 0.9847959 0 -0.00488305 0.9999881 0 0.4294005 0.9031143 0 0.3467517 0.937957 0 0.3467617 0.9379533 0 0.2613041 0.9652566 0 0.583799 0.8118984 0 0.6542029 0.7563192 0 0.4294123 0.9031086 0 0.5086718 0.8609606 0 0.5086944 0.8609473 0 0.7193289 0.6946697 0 0.7787175 0.6273748 0 0.7787324 0.6273563 0 0.7193441 0.6946539 0 0.8318719 0.5549678 0 0.8318578 0.5549889 0 0.8782615 0.4781805 0 0.8782686 0.4781678 0 0.9175465 0.3976289 0 0.9175575 0.3976032 0 0.9495102 0.3137363 0 0.9738156 0.2273396 0 0.9738088 0.2273685 0 0.9902392 0.1393787 0 0.9902344 0.1394129 0 0.9987421 0.05014306 0 0.999985 0.005493402 0 0.9999846 0.005554437 0 0.9992113 -0.03970992 0 0.9992113 -0.03970915 0 -0.03970825 -0.9992114 0 -0.0397132 -0.9992112 0 -0.03970247 -0.9992116 2.49966e-5 -0.03968322 -0.9992123 -4.3704e-6 -0.0397132 -0.9992112 0 -0.03971272 -0.9992112 0 -0.03973597 -0.9992102 6.07989e-6 -0.03972738 -0.9992106 3.26379e-6 -0.03970551 -0.9992115 -3.63002e-7 -0.03976446 -0.9992091 9.06657e-6 -0.03963685 -0.9992142 -1.24069e-5 -0.03975623 -0.9992095 1.10402e-5 -0.03969413 -0.999212 -2.61865e-6 -0.03971481 -0.9992111 -2.90252e-6 -0.03975689 -0.9992094 -8.17153e-6 -0.03967565 -0.9992126 5.47265e-6 -0.03972995 -0.9992105 -2.54265e-6 -0.03970575 -0.9992114 5.80591e-7 -0.03973615 -0.9992102 -4.88144e-6 -0.03973597 -0.9992102 -4.80472e-6 -0.03967499 -0.9992126 6.22274e-6 -0.03969675 -0.9992118 1.46569e-6 -0.03969091 -0.9992121 3.34979e-6 -0.03970843 -0.9992113 0 -0.03974175 -0.9992101 -8.2593e-6 -0.03970253 -0.9992116 1.20278e-6 -0.03971254 -0.9992113 0 -0.0397017 -0.9992117 -2.90481e-5 -0.03970801 -0.9992114 4.84946e-6 -0.03971529 -0.9992111 2.98477e-5 -0.03970706 -0.9992114 -8.33558e-6 -0.03970652 -0.9992114 -2.08941e-6 -0.03970736 -0.9992114 -1.27849e-5 -0.03970646 -0.9992115 9.13173e-6 -0.03970843 -0.9992113 0 -0.03971159 -0.9992113 -8.27197e-6 -0.0397095 -0.9992113 -9.27645e-6 -0.03971493 -0.9992111 -3.5067e-5 -0.03970843 -0.9992114 0 -0.0397076 -0.9992114 9.68021e-6 -0.03968822 -0.9992122 -5.05245e-6 -0.0397219 -0.9992108 4.17001e-6 -0.03969079 -0.9992121 -3.57311e-6 -0.03971749 -0.999211 1.57527e-6 -1 3.71344e-7 0 -1 -1.67105e-6 0 0.02300053 0.9997355 9.19862e-5 0.02471566 0.9996946 3.59826e-5 0.02462589 0.9996967 5.24511e-5 0.02350771 0.9997234 7.00881e-4 0.0249359 0.9996891 2.17332e-4 0.02645975 0.9996499 -2.97812e-4 0.02692228 0.9996376 1.09735e-4 -0.957728 0.2876755 0 -0.9585681 0.2848634 0 -0.8992211 0.4374944 0 -0.9914686 0.1303463 0 -0.9987035 0.05090564 0 -0.9910293 0.1336449 0 -0.7729978 0.6344088 3.05195e-5 -0.7688964 0.6393736 0 -0.8205518 0.5715724 0 -0.7323956 0.6808795 0 -0.660641 0.7507021 6.10376e-5 -0.6356163 0.7720052 -6.10377e-5 -0.6878217 0.7258798 -6.10393e-5 -0.6953833 0.7186391 0 -0.6259522 0.7798614 0 -0.5877325 0.8090553 0 -0.5456243 0.8380299 3.05193e-5 -0.5850772 0.8109777 -3.05189e-5 -0.5414177 0.8407539 -3.05196e-5 -0.5094602 0.8604942 3.05194e-5 -0.5056405 0.8627445 -3.05191e-5 -0.476464 0.879194 -3.05191e-5 -0.4797992 0.8773784 0 -0.4525038 0.8917624 0 -0.4198457 0.9075955 0 -0.4496413 0.8932093 -3.05193e-5 -0.4209732 0.9070731 0 -0.3362255 0.9417816 1.09881e-4 -0.2927033 0.9562034 -1.25661e-4 -0.1927015 0.9812574 -4.08496e-5 -0.1864826 0.9824583 4.27853e-5 -0.1724933 0.9850108 6.07938e-5 -0.158733 0.9873216 4.36966e-5 -0.130592 0.9914363 -5.431e-5 -0.1181315 0.992998 3.07469e-5 -0.08534157 0.9963518 8.96858e-5 -0.05036574 0.9987308 -5.83604e-5 -0.03662532 0.9993292 -3.43439e-5 -0.017645 0.9998444 7.46207e-5 -0.01340138 0.9999102 -4.71853e-5 -0.005416214 0.9999854 5.02536e-5 0.01064294 0.9999434 -6.43565e-5 0.03180634 0.9994941 3.21457e-5 0.06596577 0.9978219 4.13913e-5 0.07407784 0.9972525 5.76616e-5 0.0983228 0.9951546 -3.52112e-5 0.101861 0.9947987 4.90374e-5 0.1183018 0.9929777 -1.77949e-5 0.1267513 0.9919345 4.63908e-5 0.1343259 0.9909372 1.04651e-5 0.1401172 0.990135 -2.51524e-5 0.1470517 0.9891288 -5.1689e-5 0.15037 0.9886298 5.22054e-5 0.1627473 0.9866678 -5.50752e-5 0.1653579 0.9862336 4.52752e-5 0.1789217 0.9838633 4.46927e-5 0.1858603 0.9825763 -2.3593e-5 0.1919713 0.9814006 2.08833e-5 0.1941101 0.9809798 2.79461e-5 0.1950976 0.9807839 -3.42237e-5 0.1954826 0.9807072 6.87356e-6 0.1973181 0.9803395 -1.41345e-5 0.1983895 0.9801234 4.11253e-6 0.1984306 0.980115 1.20397e-5 0.1989879 0.9800019 -8.79713e-6 0.1992569 0.9799474 2.46589e-5 0.1998265 0.9798313 -3.83419e-5 0.2012971 0.9795303 6.61382e-5 0.2036899 0.9790355 -8.06116e-5 0.2070815 0.9783238 6.39842e-5 0.2097966 0.9777451 -4.29821e-5 0.2119138 0.9772884 7.31031e-6 0.2118351 0.9773055 -3.30549e-6 0.2121984 0.9772267 1.80638e-5 0.2119666 0.9772769 6.35808e-6 0.1972516 0.980353 3.77312e-7 0.1925395 0.9812893 -4.59373e-5 0.1892895 0.9819213 -6.79061e-6 0.1892791 0.9819234 -8.30118e-6 0.1855652 0.9826321 1.00238e-5 0.1819827 0.9833018 7.8615e-6 0.1811126 0.9834624 -5.98428e-5 0.1750289 0.9845633 -4.2697e-5 0.1750379 0.9845618 -4.18003e-5 0.1704137 0.9853726 5.55634e-5 0.1681477 0.9857619 -5.69191e-5 0.158138 0.9874171 1.36914e-5 0.1580551 0.9874303 1.94404e-5 0.1524198 0.9883159 -3.12843e-5 0.1417496 0.9899026 4.99787e-5 0.1334417 0.9910567 -2.82982e-5 0.1254835 0.9920957 -1.49267e-5 0.1178734 0.9930287 6.76308e-6 0.1103111 0.9938972 4.82524e-5 0.1074842 0.9942068 -7.35173e-5 0.09477603 0.9954987 3.62058e-5 0.0905916 0.9958881 -5.29942e-5 0.08569937 0.9963211 9.29134e-5 0.0797342 0.9968162 -9.10012e-5 0.0700916 0.9975406 -3.96425e-5 0.06175374 0.9980915 -5.11521e-5 0.05531865 0.9984688 7.13603e-5 0.05274415 0.9986081 -3.68625e-5 0.04304182 0.9990734 -1.13137e-6 0.04193997 0.9991201 4.83085e-5 0.03397333 0.9994228 -4.29494e-5 0.02379876 0.9997168 1.61765e-5 0.02219623 0.9997537 -4.65331e-5 0.01433879 0.9998973 3.9712e-5 0.005240499 0.9999863 6.5939e-5 -0.002630352 0.9999966 -4.89399e-5 -0.02432996 0.9997041 -5.31007e-5 -0.02831953 0.9995989 5.27531e-5 -0.03722184 0.999307 -8.90822e-6 -0.04794639 0.99885 3.43471e-5 -0.05829185 0.9982996 5.66288e-5 -0.06332546 0.997993 -8.9781e-5 -0.07062095 0.9975032 9.7462e-5 -0.07821762 0.9969363 -1.23003e-4 -0.09245181 0.9957172 -8.10088e-5 -0.09793388 0.995193 4.04895e-5 -0.1035023 0.9946293 -5.40648e-5 -0.1073854 0.9942175 4.08352e-5 -0.1164403 0.9931978 -3.6035e-5 -0.1331974 0.9910895 4.7864e-5 -0.1438925 0.9895934 -4.48418e-5 -0.1463574 0.9892318 2.5939e-5 -0.155054 0.987906 -4.75221e-5 -0.1673631 0.9858953 -6.59176e-5 -0.1809464 0.983493 -6.34268e-5 -0.1979013 0.9802221 4.24608e-5 -0.2062572 0.9784978 -6.10624e-5 -0.2112093 0.9774409 6.52552e-5 -0.2235845 0.9746847 -5.66762e-5 -0.227716 0.9737277 4.13409e-5 -0.2371675 0.9714688 -4.7678e-5 -0.2434732 0.9699077 7.64061e-5 -0.2536252 0.9673026 -8.96996e-5 -0.264756 0.9643154 7.69933e-5 -0.2704725 0.9627278 -5.56002e-5 -0.2856332 0.9583391 7.24986e-5 -0.3106459 0.9505257 1.13902e-4 -0.3212977 0.9469783 -1.29895e-4 -0.3492555 0.9370275 -1.32889e-4 -0.367037 0.9302064 1.54601e-4 -0.3791754 0.9253249 -1.04012e-4 -0.3914353 0.9202056 0 -0.3851203 0.9228665 9.15572e-5 -0.4030027 0.9151988 3.84474e-5 -0.7318069 0.6815121 0 -0.8262777 0.5632629 3.05192e-5 -0.8949576 0.4461513 -3.05186e-5 -0.9984967 0.05481243 0 0.06943684 0.9975697 -0.005766808 0.06515216 0.9978727 -0.002324581 0.06325566 0.9979975 1.29214e-4 0.06256675 0.9980407 4.84599e-4 0.06264686 0.9980358 3.03725e-4 0.06518131 0.997873 -9.67134e-4 0.06404012 0.9979473 -2.63937e-4 0.06309521 0.9980075 -2.03763e-4 0.06318473 0.9980019 0 0.06512719 0.997877 1.2582e-4 0.06533145 0.9978637 0 0.06603085 0.9978176 0 0.06554341 0.9978497 -3.91381e-4 0.06337434 0.9979899 -1.29367e-4 -0.07358109 -0.9955879 -0.05823004 -0.07523012 -0.9934347 -0.08618658 -0.07513886 -0.9930421 -0.09067326 -0.06909567 -0.9937385 -0.08780395 -0.06521838 -0.9972591 -0.03494387 -0.06869822 -0.9963843 -0.04999011 -0.07333642 -0.9904231 -0.1169781 -0.07153666 -0.9952573 -0.06592118 -0.05895996 -0.9982576 -0.002334356 -0.06770145 -0.9977056 -3.677e-4 -0.0705592 -0.9844413 -0.160925 -0.07895237 -0.9789854 -0.188027 -0.08371394 -0.9617189 -0.2609385 -0.07425165 -0.9963094 -0.04306167 -0.07468104 -0.995849 -0.05203562 -0.07358217 -0.9967624 -0.03241151 -0.07165807 -0.9973844 -0.009460806 -0.07278716 -0.9971081 -0.02185142 -0.07522892 -0.9944569 -0.07345885 -0.07513785 -0.9949205 -0.06698924 -0.07495498 -0.9953821 -0.05997008 -0.07526051 -0.9938911 -0.08072352 -0.07486259 -0.9922275 -0.09939974 -0.07431441 -0.9911742 -0.1097778 -0.07336866 -0.9899587 -0.1208264 -0.08050835 -0.9795897 -0.1841804 -0.07266539 -0.9955866 -0.05938971 -0.07230013 -0.9889769 -0.1292186 -0.07110941 -0.9881461 -0.1360539 -0.0719034 -0.9873908 -0.1410297 -0.08661425 -0.9711295 -0.2222732 -0.08661371 -0.9691708 -0.2306648 -0.08518004 -0.9764423 -0.1982549 -0.08624738 -0.9675211 -0.2376228 -0.08548492 -0.9662149 -0.2431483 -0.08423143 -0.9653353 -0.2470484 -0.08191329 -0.9763676 -0.1999918 -0.08426308 -0.9633952 -0.2544985 -0.08331638 -0.9569179 -0.2781486 -0.08157616 -0.9537976 -0.2891637 -0.08145594 -0.9527816 -0.2925273 -0.07089555 -0.9974822 -0.001800596 -0.07080316 -0.9956695 -0.06024372 -0.08612555 -0.9736887 -0.2109801 -0.06546384 -0.9960274 -0.0603671 -0.05932921 -0.9982206 -0.005981743 -0.07087266 -0.9974854 -3.82588e-4 -0.07073593 -0.9974951 -1.91202e-4 -0.06974279 -0.997565 -3.87629e-4 -0.06030464 -0.9981799 -4.79594e-4 -0.06241601 -0.9980502 -3.9594e-4 -0.06086254 -0.9981459 -7.15452e-4 -0.06593763 -0.9978237 -3.96005e-4 -0.06241613 -0.9980502 -3.96147e-4 -0.06955176 -0.9975783 -3.2239e-4 -0.06419849 -0.9979372 -3.94675e-4 -0.06598758 -0.9978204 -3.77845e-4 -0.06777268 -0.9977008 -3.41567e-4 -0.07134497 -0.9974518 -1.38553e-4 -0.06419807 -0.9979371 -3.94715e-4 -0.07133138 -0.9974527 -1.54503e-4 -0.06989687 -0.9975543 -3.28603e-4 -0.0685178 -0.9976499 1.55732e-4 -0.07102572 -0.9974746 1.72078e-4 -0.06630629 -0.9977994 -4.88103e-5 -0.06392031 -0.997955 -2.18759e-4 -0.06553351 -0.9978504 2.4494e-4 -0.06143403 -0.9981112 2.70519e-4 -0.06085324 -0.9981467 0 1.88127e-7 0 -1 1.23311e-7 0 -1 -2.76882e-7 0 -1 -4.17112e-7 0 -1 3.1784e-6 0 -1 -1.18058e-6 0 -1 9.9802e-7 0 -1 -8.38341e-7 0 -1 3.28864e-7 0 -1 8.74517e-7 0 -1 -1.18794e-6 0 -1 -2.87573e-7 0 -1 -2.25493e-7 0 -1 2.81643e-7 0 -1 5.06992e-7 0 -1 -1.81885e-7 0 -1 -4.66667e-7 0 -1 6.21272e-7 0 -1 1.88644e-7 0 -1 -1.60342e-7 0 -1 -2.19941e-7 0 -1 5.01734e-7 0 -1 2.63719e-7 0 -1 1.21445e-7 0 -1 -1.98464e-7 0 -1 -4.47362e-7 0 -1 4.90812e-7 0 -1 0 0 -1 2.74682e-7 0 -1 -1.68281e-7 0 -1 0 0 -1 3.0483e-7 0 -1 0 0 -1 -1.2393e-7 0 -1 0 0 -1 2.29965e-7 0 -1 -4.23166e-7 0 -1 1.86109e-7 0 -1 -4.87048e-7 0 -1 1.5306e-7 0 -1 -4.18362e-7 0 -1 3.95915e-7 0 -1 -3.63169e-7 0 -1 -1.41726e-7 0 -1 -2.64305e-7 0 -1 0 0 -1 -2.8204e-7 0 -1 2.52138e-7 0 -1 -1.23312e-7 0 -1 7.07911e-7 0 -1 1.26478e-6 0 -1 9.99289e-7 0 -1 -3.16811e-6 0 -1 -2.2704e-7 0 -1 -2.25155e-7 0 -1 -2.14232e-7 0 -1 6.3307e-7 0 -1 7.23802e-7 0 -1 1.65387e-7 0 -1 -1.86621e-6 0 -1 -1.22099e-7 0 -1 2.98379e-6 0 -1 -1.26679e-6 0 -1 -1.39744e-7 0 -1 1.04306e-6 0 -1 -1.27166e-7 0 -1 9.56884e-7 0 -1 3.35769e-7 0 -1 -3.85682e-7 0 -1 3.87622e-7 0 -1 2.91711e-7 0 -1 -1.84755e-7 0 -1 -2.74968e-7 0 -1 1.78801e-7 0 -1 0 0 -1 1.24492e-6 0 -1 -9.46769e-7 0 -1 0 0 -1 5.24225e-7 0 -1 -3.80543e-7 0 -1 2.55133e-7 0 -1 0 0 -1 -3.20371e-7 0 -1 -5.14447e-7 0 -1 2.3923e-7 0 -1 1.84124e-7 0 -1 -2.32255e-7 0 -1 0 0 -1 -2.8726e-7 0 -1 -3.65625e-7 0 -1 0 0 -1 1.4074e-7 0 -1 0 0 -1 1.72599e-7 0 -1 0 0 -1 0 0 -1 1.6393e-7 0 -1 -3.14154e-7 0 -1 -3.11028e-7 0 -1 1.96265e-7 0 -1 0 0 -1 -2.9947e-7 0 -1 0 0 -1 4.3614e-6 0 -1 -1.70217e-6 0 -1 1.96653e-7 0 -1 -1.23714e-6 0 -1 1.01517e-6 0 -1 1.26475e-7 0 -1 -8.77895e-7 0 -1 -2.42464e-7 0 -1 -1.40072e-7 0 -1 1.88306e-7 0 -1 0 0 -1 -1.36543e-7 0 -1 1.18106e-6 0 -1 -1.57276e-7 0 -1 2.14476e-6 0 -1 -1.2018e-7 0 -1 0 0 -1 1.29973e-7 0 -1 -5.28473e-7 0 -1 5.49271e-7 0 -1 4.23002e-7 0 -1 -2.11384e-7 0 -1 1.15055e-6 0 -1 -1.94793e-7 0 -1 5.09797e-7 0 -1 -2.82567e-7 0 -1 0 0 -1 -1.55207e-7 0 -1 -3.47323e-7 0 -1 -9.20951e-7 0 -1 0 0 -1 -2.38044e-7 0 -1 0 0 -1 -7.76373e-7 0 -1 -7.81608e-7 0 -1 0 0 -1 -2.99168e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.29573e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1.15055e-6 0 1 2.40996e-7 0 1 0 0 1 0 0 1 5.63962e-7 0 1 0 0 1 -2.59408e-7 0 1 0 0 1 -6.50178e-7 0 1 3.19025e-7 0 1 -9.20951e-7 0 1 4.23002e-7 0 1 0 0 1 -1.38421e-6 0 1 -2.36275e-7 0 1 -2.78409e-7 0 1 -1.84365e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.35499e-7 0 1 -3.83296e-7 0 1 0 0 1 -2.36917e-7 0 1 1.93074e-7 0 1 0 0 1 3.90629e-7 0 1 1.99831e-7 0 1 0 0 1 0 0 1 4.25919e-7 0 1 -2.08607e-7 0 1 4.44547e-7 0 1 0 0 1 2.77423e-7 0 1 -5.90051e-7 0 1 1.20588e-6 0 1 1.34385e-6 0 1 1.38079e-6 0 1 -1.41631e-6 0 1 1.43247e-6 0 1 -1.21346e-6 0 1 5.20422e-7 0 1 1.93539e-7 0 1 0 0 1 -4.90515e-7 0 1 2.8863e-6 0 1 -4.08065e-7 0 1 0 0 1 1.60778e-7 0 1 6.21297e-7 0 1 -2.85055e-7 0 1 2.28396e-7 0 1 -7.36785e-7 0 1 4.51511e-7 0 1 1.6956e-6 0 1 -5.70131e-7 0 1 -6.66482e-7 0 1 3.06373e-7 0 1 1.37588e-7 0 1 3.20565e-7 0 1 1.94753e-7 0 1 -6.24575e-7 0 1 0 0 1 2.78511e-7 0 1 -2.17394e-7 0 1 1.82037e-7 0 1 -3.06824e-7 0 1 1.269e-7 0 1 2.44038e-7 0 1 2.29614e-7 0 1 -1.89098e-7 0 1 0 0 1 2.69504e-7 0 1 0 0 1 1.86561e-7 0 1 -1.64558e-7 0 1 2.52644e-7 0 1 -2.14023e-7 0 1 -3.53191e-6 0 1 0 0 1 1.41891e-6 0 1 3.42324e-6 0 1 0 0 1 -1.49943e-7 0 1 0 0 1 -3.95079e-7 0 1 9.7545e-7 0 1 3.15682e-7 0 1 0 0 1 2.92461e-7 0 1 -3.31394e-7 0 1 3.94644e-7 0 1 0 0 1 5.04764e-7 0 1 -3.8346e-7 0 1 4.74043e-7 0 1 -2.68793e-7 0 1 3.56849e-7 0 1 -2.7886e-7 0 1 -1.32777e-7 0 1 2.12148e-7 0 1 -3.15587e-7 0 1 0 0 1 3.04393e-7 0 1 -2.88842e-7 0 1 1.80172e-7 0 1 6.52699e-7 0 1 -1.32329e-6 0 1 -1.4161e-7 0 1 2.35596e-7 0 1 -1.2925e-6 0 1 1.24851e-7 0 1 0 0 1 -3.28273e-7 0 1 1.53401e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1.32458e-7 0 1 1 -1.92522e-5 0 1 0 0 3.56302e-7 0 -1 1 -2.35368e-6 0 -0.02390348 -0.9997143 -4.73115e-5 -0.0239039 -0.9997144 -5.51878e-5 -0.02393198 -0.9997137 2.31968e-4 -0.0239045 -0.9997143 4.23576e-5 -0.02390331 -0.9997143 1.68448e-6 -0.02390283 -0.9997144 -2.37652e-5 -0.02389889 -0.9997144 -1.24433e-4 -0.02390074 -0.9997144 -1.00185e-4 -0.02391511 -0.999714 2.59482e-4 -0.02391052 -0.9997141 1.43064e-4 -0.02389115 -0.9997146 -2.43315e-4 -0.02389693 -0.9997145 -1.25244e-4 -0.02392047 -0.9997139 2.86205e-4 -0.02389752 -0.9997144 -1.46356e-4 -0.02392029 -0.9997139 2.21159e-4 -0.02389377 -0.9997146 -1.68486e-4 -0.02388966 -0.9997146 -1.78312e-4 -0.02390092 -0.9997144 -3.23354e-5 -0.02390104 -0.9997144 -4.55368e-5 -0.02396827 -0.9997125 7.60025e-4 -0.02387803 -0.9997149 -2.39935e-4 -0.02383607 -0.9997156 -8.17529e-4 -0.02389508 -0.9997146 -8.71439e-5 -0.02396279 -0.9997128 5.99766e-4 -0.02390062 -0.9997144 1.92253e-5 -0.02390903 -0.9997141 3.328e-5 -0.02389281 -0.9997146 -9.67361e-5 -0.0239098 -0.9997142 5.51102e-5 -0.02387762 -0.9997149 -2.31981e-4 -0.02390283 -0.9997144 -7.9058e-6 -0.02390271 -0.9997144 8.98056e-5 -0.0239613 -0.9997128 -3.2081e-4 -0.02382695 -0.9997161 -1.09275e-4 -0.02389812 -0.9997144 3.54061e-4 -0.0242114 -0.9997069 -5.59518e-5 -0.02390277 -0.9997143 -1.37146e-6 -0.02417254 -0.9997079 -4.19667e-5 -0.02388024 -0.9997149 1.04533e-6 -0.02350294 -0.9997238 6.27885e-5 -0.02377498 -0.9997174 2.16752e-5 -0.02390491 -0.9997143 7.27041e-7 -0.02390295 -0.9997143 0 -0.02390354 -0.9997144 1.05996e-5 -0.02390271 -0.9997144 -9.09238e-5 -0.02389556 -0.9997145 5.18001e-5 -0.02385216 -0.9997156 1.46721e-4 -0.0239073 -0.9997142 -2.00609e-6 -0.02398455 -0.9997124 -2.0037e-4 -0.02350294 -0.9997238 -6.55184e-5 -0.02390533 -0.9997143 3.3287e-6 -0.02417254 -0.9997079 4.19667e-5 -0.0237779 -0.9997173 -2.24306e-5 -0.02385979 -0.9997154 0 -0.02388024 -0.9997149 -1.04533e-6 -0.02374911 -0.999718 -1.85127e-5 -0.02387899 -0.999715 -3.83081e-7 -0.02368557 -0.9997195 -2.27972e-5 -0.02420622 -0.9997071 3.68324e-5 -0.02370601 -0.999719 -1.60947e-5 -0.02414083 -0.9997086 2.60388e-5 -0.02454036 -0.9996989 5.82847e-5 -0.02373814 -0.9997183 -1.55205e-5 -0.02389591 -0.9997145 0 -0.02292943 -0.9997372 -8.00585e-5 -0.02454036 -0.9996989 -5.82847e-5 -0.02292943 -0.9997372 8.00585e-5 -0.02370601 -0.999719 1.60947e-5 -0.02373814 -0.9997183 1.55205e-5 -0.02368557 -0.9997195 2.27972e-5 -0.02414083 -0.9997086 -2.60388e-5 -0.02374911 -0.999718 1.85127e-5 -0.02420622 -0.9997071 -3.68324e-5 -0.0238775 -0.999715 0 0 -1 -1.55071e-6 0 -1 -1.56406e-6 0 -1 0 0 -1 0 0 -1 1.07048e-6 0 -1 -1.15973e-6 0 -1 -9.22233e-7 0 -1 2.4967e-6 0 -1 -2.4967e-6 0 -1 1.04985e-6 0 -1 -8.07769e-7 0 -1 -2.98696e-7 0 -1 1.687e-6 0 -1 1.36869e-6 0 -1 -1.55721e-6 0 -1 0 0 -1 -1.95523e-7 0 -1 1.67975e-6 0 -1 -8.07887e-7 0 -1 0 0 -1 -4.1218e-6 0 -1 3.35733e-6 0 -1 0 0 -1 -1.68737e-6 0 -1 1.14851e-6 0 -1 1.5569e-6 0 -1 2.98743e-7 0.6156316 0 -0.7880341 0.7361487 0 -0.6768198 0.7367334 0 -0.6761834 0.8372115 0 -0.5468793 0.6148424 0 -0.78865 0.8375955 0 -0.5462911 0.4772326 0 -0.8787771 0.9152656 0 -0.4028511 0.4762477 0 -0.8793112 0.9154689 0 -0.4023888 0.3258252 0 -0.9454301 0.9695218 0 -0.2450051 0.3246934 0 -0.9458194 0.969598 0 -0.2447037 0.165839 0 -0.9861528 0.996712 0 -0.08102726 0.1646217 0 -0.9863569 0.9967218 0 -0.08090597 0.08252263 0 -0.9965893 0.996712 0 0.08102726 0.9967218 0 0.08090597 0.9695218 0 0.2450051 0.969598 0 0.2447037 0.9152656 0 0.4028511 0.9154689 0 0.4023888 0.8375815 0 0.5463125 0.8372115 0 0.5468793 0.7361487 0 0.6768198 0.7367334 0 0.6761834 0.6148424 0 0.78865 0.6156316 0 0.7880341 0.4772326 0 0.8787771 0.4762477 0 0.8793112 0.3246934 0 0.9458194 0.3258252 0 0.9454301 0.1646217 0 0.9863569 0.165839 0 0.9861528 0.08252263 0 0.9965893 0.1633992 0 0.9865601 0.08258324 0 0.9965842 0.6131945 0 0.789932 0.4743255 0 0.8803496 0.4761642 0 0.8793565 0.3235065 3.05195e-5 0.946226 0.1642554 0 0.9864179 0.3251224 0 0.945672 0.8373178 -3.05189e-5 0.5467164 0.9158426 -3.05189e-5 0.4015375 0.8368363 -3.05192e-5 0.5474533 0.6141582 -3.05187e-5 0.7891829 0.7362807 -3.05194e-5 0.6766763 0.7355788 -3.05194e-5 0.6774393 0.9965485 6.10387e-5 0.08301264 0.9967144 0 0.08099693 0.9965435 0 -0.08307325 0.9694129 6.10385e-5 0.2454357 0.9153591 3.05191e-5 0.4026384 0.9695218 6.10376e-5 0.2450051 0.8368363 3.05192e-5 -0.5474533 0.9158426 3.05189e-5 -0.4015375 0.9160017 3.05191e-5 -0.4011742 0.969491 0 -0.245127 0.9694292 0 -0.245371 0.996551 0 -0.0829823 0.6135222 -3.05189e-5 -0.7896775 0.6131607 0 -0.7899582 0.7350807 -3.0519e-5 -0.6779797 0.8371373 3.0519e-5 -0.5469928 0.7355788 3.05194e-5 -0.6774393 0.4743255 0 -0.8803496 0.4759842 0 -0.8794538 0.3244195 0 -0.9459133 0.3235338 0 -0.9462167 0.1645277 0 -0.9863726 0.1633992 0 -0.9865601 0.08258324 0 -0.9965842 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + 0.8910279 0.453949 5.18752e-8 0.27511 1.96761e-8 -1.52896e-7 1 -0.00852365 0.453949 -0.8910279 -1.45167e-7 -0.088114 0 0 0 1 + + + + + + + + + + -4.37114e-8 -4.37114e-8 -1 -0.372366 -1 1.91069e-15 4.37114e-8 0.00297635 0 1 -4.37114e-8 -0.048658 0 0 0 1 + + + + + + + + + + -1 2.46003e-14 1.50996e-7 0.107634 1.50996e-7 1.62921e-7 1 -2.36548e-5 0 1 -1.62921e-7 0.0265809 0 0 0 1 + + + + + + + + + + -1 2.46003e-14 1.50996e-7 0.107634 1.50996e-7 1.62921e-7 1 -2.36548e-5 0 1 -1.62921e-7 0.0265809 0 0 0 1 + + + + + + + + + + 0.9971619 0.075285 -2.49954e-9 -0.307002 -3.17528e-9 7.52582e-8 1 -0.00102365 0.075285 -0.9971619 7.52836e-8 -0.102975 0 0 0 1 + + + + + + + + + + 0.3797808 0.9250761 3.84592e-7 0.302018 -4.6941e-8 -3.9647e-7 1 -0.00852365 0.9250761 -0.3797808 -1.07148e-7 -0.0979736 0 0 0 1 + + + + + + + + + + -1 2.46003e-14 1.50996e-7 0.107645 1.50996e-7 1.62921e-7 1 -2.36548e-5 0 1 -1.62921e-7 0.026758 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_fuselage_collision.stl b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_fuselage_collision.stl new file mode 100644 index 0000000000000000000000000000000000000000..8338196dbf3f44be1be445f73e339aa6ea77aba1 GIT binary patch literal 421934 zcmbTfbyQT_`}luUY{eE-ENnqSdgg?pprRt?wHxeKR73$g5D`%k8v|5C$$^;@SlEHx zSFyVh74`S*Jq|vH`~Ix&T0j4|cdyyc>#3dR>^+0moT*c$&-5SNC}8@ONsT-w`cEG1 zKfO&`I}ay2SLXl6zb}m#=2V!y($-HSoSDB?To>TLJAKX6$2i?#+gdyF8y(y0H$r*K z9S6Rd-8%i7vq>z&tjY0EJW4ny+OapqZ9sHAmZBlVz%LH`pp1nYi>pcO^bU@^&HVz8 z_3$~vc$uG*KW2_sYPCvJNntwbh&|tP)(OqF>BL6Y2~M(2`Cz5Z_A~>o!Nl8adp{&+=;tP$^vdsPszKxyD`joY{{PQ+3;a&;Wl*Nju< z&Ccat>|3nL2_~>6hVkDk%V$?k5=662Dq<}}`#9mOemg{qv(7NVbDiW><$?v@#c2i- zVM_W*+8$U6(+uXEdVY&Wul_Yj7Z^!R_P)<+Upj|zCerQ3a zeiLnvwe8OGcb<$F;#a4rYJ9+6nSE#V)21b{SQEpHYBNjNbtH<zHf7fWH9 zVTOE?_}#4tO|+PGZ%-HAqyYe@M(x!q#ypEyi0G0ejjvt327L2`wqh>ak} zVRWqEEHKRV;}*KQ5CA)=c~plQCCK|Fk*w1WREWW`;3Mb$R<)Y9k@dfp52KJGFuBVVYr{ z-@fNMJik6AaE-UEBj0p+GfHDk3^R-o(j{I`vx|v&T^;!qi*j_NFJamk$CW<>sd?S7 zj)q8Kf@m`JV}|*9p-s9C)A>JMVJS>A%=GY|u0tRW(yy=-@xA$!P1GK?%`l4~S1Hb{=VGIEOuGKxqI)@!24yuvUU`W;)|l$huCA7G$6pve+ZLalUF8h876so87|SuDvFMjgCSkZq0yy^bxm06f9L?Yz3*0SB}nm`oLnu z%6bF1@0Dyc_jZLS7c2v$hM;$Nf;Wo^tchVh930H`+i9JayTeEX^EtXf#R#m4VFuU? zV2^ffr`LWDQLN3axN3uQbQydgi(^v9p}o|FjXrSLqwJ3m#TJO>;8l;BY65Fwn2>Ad zM9#LMKJ-*W2aDoG&koMD*B$;uQ~rBM8MXEPr1vzn4F`#?QutC zk72r<3!y!|Nuo8!XU>xvfc5X6HnRi6gQO-_RoUsKJX!KNv-S)71wLn(K0v%I7vj2i zhc$<#>{bOy-y^@UO_sDTM)Uxp-M$v-LcE$NZjbbZcfZ?%jT>`I^E15}L-wWlioQo6 zwf@on5F3{?g_a$fCbJpGr&DilbxQ_f;V5f)yz3p!rlY|MuEE5|YZEE)b@U-1R!?*n zj%{dd=oRj$vf(;zE|ofSem@(vIEdQ2ov;^()B9%&%k|Z?9+6=(uE9j?OJlCQzLH!$ zD=|Y@SX1!$R(_|9YcR3@zA@_)@(Gdt;sM{%L#xgE=C6ta6F4Ig0{qP0CD= zF@dG*s*ItUvbS%AINq(8p{(7}NWcEsZrYj21nqVE#+%%EWH)%*}e12coykQ`l@c_2GA ze4Mz>Cr9_*Vk{eaSgZd5^oy8DKcbdFHg@KLj5iA@Dc0x zt3Q=`vG)sG`O`pZdx!gbAnvTll{cjL>ib2HQ#zOFL2FKRVYt=$zO?*d&3CqAS3gQ0 zzxx}AA0b)%Q{M=;xtk{|p5_9TS~2(s8-3E7mLDcD+|Y)dC~@~9!!b;&A#DZTBFp1> zoSU*J-h)aNj{3kp+R7WHPJd@x_4lCVm#c_Z?u*6!Kkhtl5OoxjcEp06fg3@YA}LQ*&EwU)}+4d=+r*>Tiz7Snq`6B+ZJ zK@%N=$^_-2b1V>83e#mkQ%e|wok0`B9Nufq1#}yeMr@sh9m^ZgRVm;w-A9w%OLZtW z^>O6=>!!JvdPknNrvc$>SvkWGi2c3n_&Xyk^{am#WDD2X@veIp>U&jBV%0X5!0gj4 zcySu+HWbqyhv-e%WzUaJIjK({o5T*Zg!fv5kLfS0CN{)OYmP0L=-Qzefu+n79Qb-2 zcIy`#2+`-QHP_(2x0^K(eQG%Jk4p5^AHJ8QibG9&o@mYebT6x$2}DSHM?P)8A*3d!s2d34zGW%i8X^*tf)d3q0_Ktk!w~CsHPm@@jX*JPrpEb-u z4AUKmhi@GCH+ge33At(lYl3%u^Q^gE`QKb801-9Kf&Vo*Nn^KPO<+w7lXS?M^I4Ib z-USHk38roD+w*M}9MSmABiXfs-JV+)E9c_91WPR)XV3p=DQPtQ2+%}y~eB5HqJ$u+Tvo8=>7nWK&*^ZyS zsiS6E8RAtLh@+BjW?tU;>Xch8YevUiX_rM=c&vnD(k_&)dhP z>2G_G$fxYL=B)N_)cJx9JW{a~rr~)o&YD|TwOTsaWndeaz$2LS+EAg=rwa7VI3Y~$ zUQA`v^ZDPWBGa=uVNJbcw%+&@Pu^dUCt*VWeV0Lqs$Rn~{x5<&VVg9Od5p*zpa0|M zH+02uV5$Gwxa~SDov@f7WgL?_j?+tO6%i(X{}(}KK3JV6ielrcN8IM$B(oMSBVe zT!RUo5Iz<}}&BG${3(m~px0 zg4Nvh`p8**1T3|zQ!XVM)HUOFh3lMshJIS>IPui9==e}3ZfV^~Ge_0uelV4f}9ITg`_rA;J^6GxrUmy%1y1 z@n(%U^0eKjhXdF6VF#`mcsTEtJrLvmStGTqQd93eEJWyY{XR>cOiop@=Q1mWv4v0$ zI%>mR`p}oP1|s@qYao(huS$HG`I@|~3j{0`8Z}P)6Nstd&5IEO9p6dM%S7pC2n&SJ zJ_q&W?NHBGO;l2tW|*N%YRk<@ap^K zZt}z71NFnM2MKQm#!6ODGxO{%*6Ywq$qb&`n8Pvby`W!G9r%23L$WU!Sf;N$B%zy| zb3l;LBl;J8&a^(Zj6FH$mlS^avbNQoWhxq;QXBsxf7>x$^G}x`0qezt+QzvtK62NX zW}3o}Y65#Gb93mErTx7R;8ln1Ub2374gF{Pd8#-@Mmf>v<;LC0aB6~i(q49`TS7B& z=sW>SEvQ*j`VF~qhqrEO!l$xEemJPS-cgz-RBClyByUoFAFjb+0&8NJ&5hd1O>O&V zE?Wi*SPIj)Z5SqQijBPBRvEq7s9*uN6qdp?!&D5YCdW4k(R>*LZI1d9CUEazn5dZb zl3AnX9`F1@1l&ivC0}QoKuiS*84lA|9vq@GpFE3<+95Uz_^(f* z^yWWj3;Gs%I*VpLugzg8Of$@ic`Nz3JN-3YvjPPyh3S?XW$p{~{9wnLU}GQ~&rkF_ ztRMAdn#u;AwbjJ=Jv#nU-UdyTuai}CJD$(g#BSTi{IH#u+?{Rx1uTVE1H6_nOyld- zgy1nASxp0a3AhFm>J_K@rV)bY2Mg_7<|B{SLA>_$+H;q#kF`6Hl{2`-OkrBpP5OWj zn|Lgh6LOcXmgimXuxi43#1hHndu>DVOxOX8u#p$R4#_HFB>Qv9FUhJ*j;`OAWvtaY zC%FR5sO3fs1RI9QOQeWimWF5`a7|N?S`2je-vd~z3EsWdUo6=K&({ae4iT_kmDETZ zd89>-?jk!9Y$Q)#C}}=hdb|o!+radZ4ZkGf6`!{Zh->U(DWv%U4-RZxnGLgkiyU2t zpUc=^5L0}e9NitSk!%Z?=PhB(AFW1K1OL>;(#(BTojV7H2v~}g*TQ+r{r?ay+GWzW zyra(Fr-le5+DMQZvuOZJ%C$i6I4EP9VPwlC(xAzM^pj^9ZJ6|8qL^0?qPb7na`M~? z^ObKkM5z!W)Yqubdan+WVpo4*f0p%R>t8=1&D#Gj8>p=halE$O#XYpTBQ~}SQ6f*3 zke@2KY-X=7+Khmb@^+82?AU3awX9c3+3N0jcK3qMT6nWPuM9Ul&q`XI7@}0^_)GG* zbcgM>HeZYBylafSv*mU6?(Q!@v~k|XxtFXZ2ZshLj+S4fe-1unv+MoPVoxy5FulJ_ z;F5P{Ngo$4P!U)P+h&+^jRUxl)I(CxUNwQGde8bMjeq};jXqZZUKJic$bGmKEpy*z zsB9d(@<_S>dFywaVQ~%_=F68koKH(<`M}b73YNk#ec13?I=AsHJMqp>uwlJ<8+ZCi zRaw~+tZEM&Ii?w=ug5H|d#E7hF9}g_8{o)Y9M4OQ9ddLF4%C4bG;6hntN47EK5m%0 z1+fh^QMYdxH@AMLEQk3a%3e5$X{F84)o$d;Vkz8Xz(&1DZfkwptjHm1uQ2g4sHFV5 zagMHL0O=*yc7$V25N9x}}1N=vy0?;h(1&j?Z42A7lv!x+rA&DSmf zI+DxL`E~VVThA{k*M+g-{^%>%@W@-lUF%(6^L2KJf@?5A&XE3|{EWXeI~AV3=zIOE zL-*4)s@#tT+<>}W={gvDis2HQrqItPcB%)ffy=}26ce#+sW;sTyX>&%%sV>K9l$kf z2X6e_YP9^$(g6tLzfeUp?s+DbYQDZPl`1C`Ct7qFN>5)eE+65BZD75fR~OPf%7FD` z7hdAxu%h!?OkgRW1OHHOtKYK&Lcg$H(RnSd!9>*~xztAgZG?zFX;oz7$(ji?KOXTG@%(=zVvp zE0)4^Ou;hx{4u*MdB)khuO%e{tHz|`nxP|B(PyW&LtAlJ6T{4}YEzV}7?G#CUNmjZ zVFGJnm`XQYsEw;P&2^Y)9BzC*8#=3niiXp^eiqb5x2`4JA`iURlINwlUM)FHU`-4& zwN%5R?0WBsp}sfV*-S-XO$^h;iYX#KKG;Ef_0@~k9H!O8xYnI0aqRMq3`}6DcJVc} zX4uf<_0Ov5{U+b%Tn z7HcnNghyYXPhPzS)KqzbJ%smghpJQJp?;w&Chp(pKu6Ta{l8gt998x#ri9nALm6qS zPEfCG&8w*LbyuEb#**fu<+cKt}RTQz`j#kz2` z?e_Md9?qyi&b)4vty^T{(ad(VrrE_p7TdtK;r*^vZAz4V8JSVm|2*~gSBr8S)*Auu zXUN+YuTo}UBh1n`qAtqUU9ql#BRFbr&FKOb+h&+ohiXzAwP&|L6oi;^o9-Gc8k(wHopb0xSMvAX#9GjbNCzMN#$jS zXDs$avwWgdA6l@(#C#xbcWOh4>shayu@t6pd_bHx_L5Jv3(~9iG@kJGy783dI~v~z z-Y@a2m{<3&8ws+mW8(Bk`1dO%GJQl zM&f4jEf&*i!s7lLI--OT=9$ek(`f%0-8q>(vu-jihfhDuVoeNlyt;86BynH@OKo+C zp>M)EOeN2Qui}i6Z|c%09TQk;+Tv4EJ!p@#p=m(a-z{Gh$4bo%>Pgzi!z`xN#OY1O z)qr?a*Jc(a+P*%-Vp>haOsrF60~1(E{v1d(eXB`M8fx{eS47|%Or(U*p@e8T!RVgJI0$lSECYuc=x$Mkq!P{5Y?4kcMprDFb$_NeHv5ZQwMujT(d3Jcw;B6 z?RFMxVwmhW%OV??=-&91M0Um1ZDLqV!&$-gs+34x-q6*4vGHx@40z(jQkaJIBiA^W zq{YOiVFK@?G0iXs%XTdC3KKo5?xiDj$LluqzSrMfc=bkqdwXGL3)upEpX@uE#RS#_ zHyW2TE3)xKbJy78Jgcb)tO?%lPApYK;2PU`#wUn^QJ=L~6Pz2gHtt?0x(B;pDNN%h zZ-&XsGR{7v?_vT=k#cQ_&+6(0cw#AWzcTg8<3br1zOV5XQe^aY)y<=!$;~A4p1R51 zKG3hqZ!xa58wUBf;E{^Qc|ex&=2^=pq_=;wHjeY?;B78=q+(hUK8QgeX4trjni;aNlqv2&c9&Stt!vAfpUQ5L)C2vhKWA&cQwE(GS*wU zoY7v(M&#bonr7E%cAb{Qxz4?mO?R*JS65f=D42J@8Fzgyt!lZo{M3)`kj}3v zQ0=MIyS~yf4QQJ$?5c6W&rbMBNbS|hZN?TXX#X`0?^5w@8Sl;+=7^bbtu1r3XFA^9 zVGq@D=>F`&e+D(lz^(RuxUtn5dE95!EqJ8b-~AQtOPIi#7-n{?aXo(*x7!61_+%XS zF@~vOZ6tbE`IUzIE+()hc>CecJDbkw$$Cd_e@d_-Uuz>urJ!7DgiKdw^0@)ld4^e9 ztBo_cc~8bi_KoHAG<1f!E!XEl0zD<|)1wV%*=`;^eZA*L-b_s0Qj6N?1hXg^okZ6K zm@S9G4v^g6ybL=)GFOt%GwHm0xT$NA4KgQ^npQA#F2B)+CFivrtf#RWSXapBonT#I zn7QE}ok$!9ntw~jHJI@0R#PPBxXDAu0daX;cj{HE6{A!HmYP`Sl}OHRV*`f(F>ywf zqFnX5=^~L6*PHEosytB>fjiwPQG2PA$_A#%ZCr95*?1JWDO>MtGfMoh4obs0!MVaQ z!8o6-p#*!kzALW5dBd9E1gpVsnk&+RSZ`#;4VIjYm)bj1m1%~V)u0-+(P3F{9VT#V zk~x^PM-#d_k32ev5@yTSr((UBR^MVR+0lX$=Q_4^!vvPH@-W``UAvCll!ZM5C0zQg zam9MECuILXyjlj&32ioA*oyg{u8zQ|`=!~96RItBBi`S5G>&cyw>Kfy+XV*&N*-m*omWwmE% z%`Hs@&J*4(5Mmm*uD*drsT>w=9w84g4Ljrzt|+@Wa@^)P>#)jDAEYE*{Ts{8vfUf%FUT2@vfA16-??yG8XZ)@ji5wHATR}t$#|Ph) zSx}SO=r?a@I*t}g;d^onGrCDVN?d$1-x=%0QkaHw=e)nG0nSfTcoRbU(qecMqRy4( z&-!t$$$D2@g9)5N7*S=6*(H(VnwjvPiP*4&_e?m`@WyM?-(G^HaBo)=wU_=gN@Gd z*Ntn`y2Y-z1{3~iM<_A#V>KWiF1SdEnZw&>U@5=#dMb4$rZ%T0;(o8BUXkpEj7_C? z3bw@6{M zMDX(_T$%XYR8#(t#t=u+DF^D+!8$IwAnRqcovRIL&Efrnde4yd@@ap1s+rWBpKW3O??jA)pFrn(=M{*t9d zUSYyvWHWkqu>64r9Htqj?8Z)X491Kd?uMl>{RB>$$gI5wPMR2|RQacrm~Pe371z{U z8$oUKxmAb5nqVgrJh;fK$2)UGvJ>uBz7~fGtO@3l62@LaBF8ngwWa7jdaPd+4r^kV z_eoW$jV3)V=rHjB&WecdZ{Vy5(+qQEw{dmeRyWw~37pChsYY-rgQYOdFty_yi{eOn z*G`tBICfw1u z1E|vcSvr<#cs+vpe(-&s${yUB>~3sxzfu)kFoAdXm}Z!)IG3U}$Ir`H3ezx`bTW<) z(s#+5fAZ9D2+j>KttO6_{yWYwK~4k+Z3kxvn1{xCKcy&JW?_LzwU}8eud>TjN3TuEE{<3Y6SIyzh4VkZ+>f5te3e)hbLur+Y zdI^@ov^rN~ezc=R$L-D2aSbM3IKs z{|7bq#fi!(i?nbKPAT_4!lCr4{OrQVF)yBLE&?fMW>^}sl zA!XBkhm`-G%HZsh8WOoFT9Xv{+~nc^_R3@fdu6gmf0KjukpJZswqdf(FrO|RV;|Ni zpV{e6h_b5nOQ~1ndp2hGFD;G(_ezGz0ph8@ccvE*UTr=}N7g@Q7q|VPBCsZSj=FJ- zoz*qU-5Ut37t`@Gze(mF9Q;=vQkUSqs9CG)?5TKiU$jQyG4}3}Ngf;!6X8y3u$0Rdy#B0;Lrt{LJH{SL z&vfqq1P`}W=fiE)nyb|W)&y@qwjX0HpN!4wQH&sWE_cJdSIe1d8lG{kA7lL!dS{Wy z3%|9ITj?@9W?Eg*-tK27x1PL6)A{OU?Nhh|>Dl+1TY^8i1G(YqF?RdrY>$pW5UJAJ zSLk2EH$@1&A?RWj1GJjBaPb(s)YeT$Y!p9HH1!g!iD6>r9cMc$19Z)RXnWUA&N!jd z@1Am*=E_8T9AGc6Pd=%)s&W~;>hoM;hwuCB?*CTp6=_Wqfi=OqrDw<3W*#S8+ZXc+ zd!mjb>Gm;Jy0($F2d=@9;~c_$(SMJz)lbJ|kQT&kfN7j*m_>85*;-%cX5Rc0`Tgi* zjVW@|xKk6at{h|U%uRMB;{)5kQn*jUZYdP9JI~LpDG(%!Qs@y4$s(2_xiZ;in19P1 zXI+l(bkzcZr7%78j=h}GOw<${$c6TZm~xC|&u+=+UyQ&~6(&2#wH9vD6le+YxcW(U zS-zwD-q#^Yw`&gatYjBW@T*HIuhc~HhZAhwbwAwh1CdbLQC|D~zWe(VY65G5Z?gV4 z%6k6mmp1v2SEinUW5SwXW~eT+wF9QO4~Bk4bk(onsW*9LqV-=L3~DXdpb)HOfJZdIHz;~@?b;fs{*dXf|3m5Ii-;rr(kkFn2w#<~tH z76+zDro-Xax<1qPh^l&=T^ufEcmRP%4z{5tYOL+)+NEq=x_a)0-Vpdmrw@V^r{+L= zxd6r;DHmS{;mvdHMwIaNu$QMtXKRQQu|ZZivX&4VGV~JiIaxIz7RI=DC;54lf8V`0 zLFm8h2O-kx7~cb6z1SY{>hBJK5Qpm+-%gPH^no5nY+z5YCiuOKb3voIqSA}8l}Sc*ix6ncg!j=#h(euJx>N5i7XO?q*g zV;b&dG`o`4r`6x~FcG+CU>e?+tlg3p_@~WrOPRfIBZnu zw3^5`J;ZHMwJo#-aSe_GYl2(%^H#cc9GFOL5W>_)HrLfecyW$d8hr>k81@`is9=V!IZ*sMm zh7*&Uk9cnn_$8~fX(EYIZKkK4{E%Ix4~8BCJLIPR%7H_V_zQ_<9Immu*G6WoR=SsSx}wFJ;Iwasr82o! zcjcz1R;oSQUS8>ut0D8bL$aMb@6G{D!J5n3=RexWZJ(FZ%%L_OU;Ia2XcMG(Mx9|X zK{BdYbVNfkifM)s_V!cGdskFe4*AVuPq1D!vCuwP$@R10Ej*h@n7}b%8rq{)lzeK? zEFnnPslgHU1Fsy*p4N{BuW;Vr4a?He%JNeSSl1m-LU|t%T<2tlCQ$&m+luzu%|vdTG?4OM0^tdM4tL}m;3>wG&c$*EQM)?33o~7Dw$Oi zM;0znev6ysLeOPpV=1@IilsJu3M}NZ7dFceKvPgFOBud>_VyL$a43qc+kSz9r7*o^ zTP)R-_}l`BeC`H+a%hN{&5u*MyK#1af@_KsBqK(`Zfj3@ zOU>0{&y_(6_P5&mEmUvI!xnP%)h*PkhsTMHpUvE5Z%t*ke(pR4*Wfs?CWd+I{6Su? zoy_K)9HAnx4ct!f?se%`ummThmcy0eQlte*YpMyZ%yk<1f;D56`-?Zok3gz{Wlb4p zft3G7-e+%1p?Ud0@k~TJC9~UV`6UqU?aRq)%~s3LAwONumzA$9Tp_=O&%10Z0sic( z(poq05fm)7(QSqN00^IoC5jOpx^qIuh%meYUNd!@>Mdx@!MU`;TK`V5!*MjT>WWX%;Ke3r?Vz!xb>+!+Yw{mU4m5HtEB#U;*o`)O9PBD*f?WF&hKj zyUBTdt8+PrgH%MB?px)L5bf~u-y}@K_-OHxe4kSY+L7aw*k}puSFL=WOM@3Krg`ge z>a|qAjSvsh86y3u-USM5+fUvTwSOu zA0~15heSHzEQ*WcsFb@@sImv|LY*%s6XNooL?^5Z+rYFjZqtp%*7?S@c48w-`Kqh2 z+`qo1?7G2NzDn0xQ?AJWF@f`@&XtLfQ}(9g8f*h=GRl)Unm#diIiWMQ$Fs8*a!o5^ z8wAd@P_@lpf|M|UTM&B)w_XN4pzX1yRA(2wdSM$cI~jL4w*5()m#F-k66Fu*ov{rp zg=wQ#rtD%VyuM=Fa55HDo7&j%Al3=D+Vevj>H3=ERIAwPY_wwhwJEF%+rTvZQb@qj zLnOPA)t;$rFcsI+72t75by-bR`(~C*;y9wc?=(9!imp+Q!>h=cz}_-U{i7>sPki7K zqZ%KWRufYbd(qxrzTlkG{;HAkYZy@-2UU_Wfkztr7Lu7wDv2Y*?rqz?mBZ!7KGqeMaLuwg5p-slbN9V8aKLi;E@&zRzYGLVsmv@I z$D<}IoN$fZu~n29UG<%mHGC-@k1HO00V1@u1${zoJ>iH`POTMG>Wr+OanwZ9aV2OR z^I9!*!gCasQqNbj!;)znV>;Au#sr@2)ayruihXGd9zPhP$}Y~;cfE0U*7#*P$kpud zy0j;f{)MB(F<}qkbSb+IC92jv;Dj@ZX`Dm2WpTMVC2sF1bi$rs8n+YtcEYsMZAnkG zDV^ek{lzry3k(x^r7CT~Yonr6JrNVQzrh)ceKktFs#n*d zcFIkrM1JcqRUDYcD>d8;w~vLs!Z0PhLj=4!V<}9-EpIy`Q5pzbL(0Ek9V8xNO$-zB zp{FDCMaD>&6V#vQ&T^{3Q3*^o5Bj|{9%Xu0?OxBRgl#-riFBDONfrGwy6lR z!V#LRmY9Y(zUiq~*|}#@@iQlu+OQ;!(&J$jh2LCmcA4ht!RW+PtQSjR8v0d?fy|;x z{;srCGF#?>CuDZUQe+M`JyS8v&Q1)CgS0zY@5uA3X{{w?veuIIkr2jR29YG~QJf$v zG9k!{Ojc17P2|YGP(^X>oKDt0qAL-0FJ$c_WwNVL+lcyQ^y=2hz3JF1EQM*K1!CjQ zQeI_)tbN1=S)IxHNXlf@{!3(!DoxjOQw`ROz5PpMl8fPqp>HqCjTxoA7tP8gqrs3Pm`#i}wS6tJkrr|cn1l9!aOM1Cef_ew*>tpbj ztgpD2U`=q#BEp6C#I5ZPq+%(u4n83?th?&*QE%lBN;o^*PsLK0CM&hcHhe3-XMai@ z+Zdpl88D4!3Fz&8jJ+iHV2o;Jz*1yBCL`FmepElQfvo4sWxL5Lg3QjZK#Hu?WNv>0 zW#j7HXAyzvTlGDU-FG zVeZ=wrS0)~;(=5wg=w;?ktYk|dOp6z_@Yru*4i&nL!KbWT1%cx$&&?Hok`jFG;zA( zDVp7t*8isB8mt#~2-ahCLQM+CT7T4g_2Wx^j{3i-Gvl6(nuN9ef43op$Qw)IXFbmx+wY+4saqD2J6lS@T_l3{*KiCOGh5awmpeG7T9NOqw9x+-!Sz?Ri zGk!bY9i$HWZj%;v+(C(lZ?^-X`BzKNSKiHYPY-Rii`qCHksw{IxSRI_V%PRWsdk~! z-iJ$RK%5NED~cR@g=sbMZ*_BO@SYvb8TZrJ{P7y)`9wbNoZ+;=Z8+h**$ z@6`Pm-i42yO>@U>n#r+(?<>Nxf=!V`~Pk!6O)JA}vk+8K2J!_H3i$xq(xp z6!g$o_AC=6Ev#r9X)AKpLwk5NXh=^*35RC@tQXsZ`z75u>eb#PKUYlPxx~iOXk*cE z@*GjEtUo0h+H6V3Qh6`7P!A9E+9auogL{@yf_Qb|j!`ObQjCNNtO@RgZ+b`8LE-bT zxC}f;VOmZ6P&QH2!0~2_5Wthal$BIT2wt=NE4Zm79p}z1>!xG94`+7?1#bkbqMVwf3V763ClfqY- z8ZVw$ElK>IWZrx80r7A}1={1YUm*YF=WxaF=CVBe<6(Yh>|wD%DOn|TI6RqO-!WON z*-ivvyY*f!{o-8Z<%J$Ht~vAWF#n-?s@SNCLBg8gx7E3eTwkrH;wUv$27EirM+{F8 z=S|2~*-#Ui!V>VxO!+myPZbCD9czNW?igQ5sPW57Y5i!YjHAUKVj9lV=GWzy9#|t+ z*f(97S|*vF%f*V{Cm)e;-qbd>hm7R27PpnPyJo3~W9O6kF>I`;(PgV>hA|g8;mWN? zQgCo9RUDYuH8F*E(8h{)-${_&92;-Jy+@cld~;0|fu(SKaLe1L30-Ty>Rr;jqax*k z)=TxyE8j~shi#RQLD}ciWr=+L5XzHlkvH^}3!Bn@b*;V4e~3FEb$Ld}4OceL3;X_F?SSLDCs z-`De7`IdVvq{K^cA}Qy+Ya(6nHx!l0=S1%BUFYHip)o>yJ4mEF7s}CXtRxcOia+JQgkM!J6@jHlIr5JthFQnj3WKYUNw@Lm1owAySh?hR z!*0(|spX)ltb<#kfr(lm^-mhldar9H$(`my3)c0p70T{k*S61CPQX&bL2BjZHHK`E zQWG26*$M;Bb<0>bf)j8}+RQN4r{OC@IsY&T+lHBevlT8b^-6y=iW9IDrn~iA&Teg6 zTAc8CA$Vo2wG~!0&u|S6P}?ZCFM=)1uOf!~FP7BAU5%~KsPYb1sTh%XaszwGy{=e? zUn*f5o+fx(;aB0Uj1Axw_9T4rc6QLoM&e*d%~ z%=B0(VVYqkxY-J`PWgG<9mffeU)^U1%&sKO+_OP??3%-Nf;MIiaxAO;$;$BXzQd-&;qtnwVADRuE@2*W|C^gh=1Z?C#tK(t(_H5~kI} zIU8GH)G5hh;!HJxrPOVHzoV@%dFy_+okO5KP}|~Of@%2X3ykxS)+JoOk~T+u3DdY& z!tH1v*4KXK>;U}=*WiAPHNoAeiG5SaEcbfwsdOxr7V|*#g1$R+(K4w~wfu782**jMko3DtZX|~2vr*3)CdGPs}HN}WhDRF7!El%h$i*zjI+{HL*TU1`&cVL+d6RNUp9{k~fBa=efCqRW>qPTwvQwzG67_aGj(k zZiiRqzA}!&c+p+JQrO1KH!{05yo^|0hy)uW+7A+(HeBMb`Nql5_f2Cjd>U!6Yqd~1 zd~`ZHD>l|(2EX+^)nyd>Z%`S7ZJ$Lz?7bogPj?LFA9ib`+k0KBlHWs|x`p3$nmz{T9=aZd1<18Wn}-g){gm z7QO;*15Dt&!FPU!*b49S?ZlCuobZ0Kf&KSQ195s(gcKYW&)T~;6-QNEDYe_0!glN0 zM4TK&*4p-AwnA*-c2QSLO<)_Ch8>wrJ;D9zTE2!Auks2@VH& zS|qXCr_>T7t-@7a;rQS$fb}@U^}0V!xEOs_)pv15#lvxI?3Get_uvSKqr-u|-0_P+ zLdgo=DgsN{cHF~$x>QyyWlbW#I>JFn4{_uRS~v@dJvXx}t27XMwOgk03VRE?rR)`a z>N8&OEN>;?5rw7Haom{_!>7%iE^O=knJX9)!yZ^xQry*Ng@ir99>RHTObcP$?5@&% z%l4|7;dsk+?4(w;#mVEBNZ4Dr71qCi-+tX%XtAS?fc0Xpu(u3jkzGbO;-eJ~T)f9) zua=u_WLG?^DAxb5ROKQ3F6YdOf>SeBp-KBkJl2ctVH&m*EI8+U6gVY{EYX~@l91~$6aswU*{orIjxD`i|0nYfTGH(xg7cUr8{1oy&sOcuUY z+0V!Ctf5-fc34ehQv%Bxwp0mKttIeedajF*e7UCZD9~3G2eyG%ANcEztJ@2$t(pj- zUFz_-21kzLW0GX;+`CBFD6vaO*lo@EfV)2boXfu@qjp)r|&sT6l@D% z$7@gN`0n#1Ov74h9w_v;UCBK!yMo6xn7|$~OqE{QtXQRT#s~NgRxfcL9~~q}mN5mQ zEtH$XJAl?uUXr(j-+#_cDv169?*OzNvf1}7m*@zArA9qo$ToO!-M(cG4|4#UGSTOh=yO9 zg1-qkY1jgEGD))++GT0=V1Cs=LGrVAk^I^P z^JOl3Nao*qOWnE#^X8virIynN0pSBggXbN!lHE~uj&(5au!M(Qr68rX4d#DDuu`z- zBVkQ&G6qCnzh`j2^@z#_Ca^uY6$XEIklC!$wtaUJ_8xz&N9NDtVX#RvyEZ9i;}O_+ z^6*3EzftO3VL~1G0w79QMrmFI9%ZofA`jv8kYXsxJ43yzM9LzpleEVb& z0@qyW^^2Po-CnxztE_}I!TGrt*x0@2KLqv))9`c$qjk=KH?AN-e&6Ku2lR z`_ht{2!$DL#C$IuA-0TY!*{RcE$xdhC1C<n7^wT;k@+3fD%XXzwY+j{x)H$6K_`_C7Om{t?3 z+h?<6M13w6IgxttXB1&g#(CFkUAxRmowM1Okq5b@2P~vFGuEqG?Zc{roL|d^Qth~C zXhF~|INzG(zKqRgaSJwIe2{xSqM3BD_c}>UdcU2SElM>L6zvsJ4-M-!0vnjXxxzFZwZgvHF|Pj59yq&L3e(1M?zd*K zYh|x&G16lrC+v5V8egv@t%q_$7JXadWo#>17PJeYJ!1?~(|WUNun-=ERga z>pdK{D=Hh9K5{FD`&rsqdUIeE*r-M3-KJAKsx4PUTr=Zb47dB5i)0?SLS+wr0TI0F z)l9En-{YuwT8ZJB{&JPV`YlsQVcHnE-NQ!iRUmSlpW78Tai4;kNbP^GlW-R3_)r4Q zX1TgSc5w~P8`fkTdr8kqW#0Ex+jw7N6PGZ^N?PB4y@c%n-q8XR)(@Dy#P*uWGm}Z!kFt^`Z{*lgbn7~qtp&yscbd%~sKW3QqK*X;wqq|ou zh2v01e*ayFz&?I!cys6gJEd#5l=!p0)ULxKY1x8s>1Ken#GB2M)&zu0Kbtj{7Azv~ z`X0bIKk3#wv&H^w7E58hHz2$9eTXzo>M! z%Bzz;;Zi+lwWD5(inU+>^guFS!D=9wP87+>VNc7?QZAf9PB>Ra!sn52s{e<8_V^EB z0X7JMX?O=v*Z5li#17VlrA+0tQsjx{|3wfflP2TI=!E2?%u{f`J+E8~EjgVGhSSN` zU3ZCYy^UwIeIBe3r%efy$JX;U-1P|u8=o7za-RdlwknGaE<3|y%U0e7-|`XkjMhY} ziFOlLy1+YqI=^EZ#c9*|FvGNXJzW^B^XDC0N6Fh=!sHotDTd)AHi#ZQ!{l<2-iDhO zSBUjp!{h_6LkwoQE5NJE-hsl|UcUUpSXRbTm@d~nOdcG)%P_VqxpTMGtcsxdY#}`C zT2uKQ5hl02y^5@Du&ih+U1NqM&YHL)Z_YbyU5z5#3$C$JQz|K>`{E@0)J z*ZAa(W0g|3ljVU?n+)Zyrqgrzpi8laK+P603vL^hYMNs3e!2~8OfOr=j*j2VFFZ1X zp6UmJSNUgjBBs^EDCc;dA5&GEkUvcs>lY^LfQYWOMa=Lw#!=zD(FXDM`fg$)<@YS1 z!`>3wvFWR2OyDe}I~eH(<4EK!I*k_C?9GP6%x5yzi)l5XU9Rv|Egd}$kDH|Oiui8w zswkC~@Q!zf@%-Df{JfEObxXU6;&A<0zR;Z!{niJI;qA`x+~6g; zn2vja*w=NAa;0V;{(10H4Rd?!uKB|6uet0Ez8r5AbCz#j z=8ECc?epRicsG8%b4l^$xznnc;4gHqo-f$#dBjGIt-#}GaU56^*qAk3iJ0aukG*kA z#srQj8ti>N*hDO-LT2@}0rQoq_p0;%e%-8%e0i2{>}b&OKi`VjcN`P^7HjMR<*WV_ z7hJ9ehY2i&?ZNL;+ijCBL@`RQ;K2&^3VVXH0Dp~k<~${ht-yN?EX`wG&7cLZHEC}W@W;(x_8(+ziivqnPnhz2W@7pY50&9Z% zC7VK&r%i@%m8;BTV}LlmeU$jxC0rcy<}9CD^|WrJmndRQ472Az2>ez?4{rTCe^m=& zDNMtS#-tGCLbtBmp*zu9Y$FZq$&dZTayx@n_Tcn2GekK$PT=Z}=%&X~vUrwfyE5X~ z9mR<+^+yXGT2_)fh2N8XUu5!8vtz}{aQ(@nAd?Rmzg-+ZXqjZzJB5GpXqRX%OE5lk z_uC4csy0?S4@#2z%+BOvN+yc8*DsUCJV@pzW*iiIJQRx&Lp`etZr8k&a*I~WSPIkr z4KjJ(gd{O=^K!7Egg@qIX@@E+1`bsbSZYALjz4(qusEPSIh&aGdM!Wj_H@M|s*=o< z*YTlaQ^Zw?;nI>m$-Mu{6miF8gQOF;VILVLtFkidd(rK}|F7HlE{uYW7U7oN%tOhLZgq(mDdUTRqcUWEjlfe zAJk}{IJp8j|8VZnUN|h&Rm*Qkq8uUrD=8 ztl!Qcor6ptdzLKjenxJ8UUKR!U79jOne4JfUN^NrpL>0z7`0he5kBMl^ACEB7e6E! zfOuUqk)6>joA0HWq|AbQmOuDd(P`2Vsd{vOo^|#RM@={)DN~~P^OZwIE4Wq8Fb=PM z#fhE)vd_f1N~wkYd1;`psJoD@BCsYn`B~Rlvh6ui*;e>Q&i{NE=Ej5K+8T<=ckC_v za{Z*5(!jW;%9q>@O54K2{Ms>l#Mta?3Dej%5U=`*w=PbR4R_|K2rQ-cs==7r(t!!h zm0{gH6>J?7*dF{X?EC;}K(l$umj|4T+W^z*_LzKgzI?M_lG63iD%pGCKm4mo!^Ibo zvNUH(e?GO%Xz|f}S=u|UKYuZPyx1U_w8!+u=VUR-Tq&5UQMMibhwql(Ra|%?Tf%f+ zsekyFC%cGGTVw+fYUn3#e6UIKUprTcUeccryVFI~)juL(y3CV)yso{6IBgvvj&8Xi z=bjrYPsDagZ;3U*T4FCW5I`g=ip8xS* z+4r3yvSlYFsqQ^9Sqs^-WLJbNWv3mL$`UH2WK9c&sBYbJ<{VinA^RE%NyxtMzd1Me z{eDgF&+pqGJ?3%e^?bc%dCi&e;Vd(~~|V?mDk{i$?HpeHNvx7N=zKK&v@D0Q)YD4KO8M}1^UWum11Bzz`px$y3K z9X#r6D7v1XqkcL1B*};g)$UMubN>XX-h7*OS4!kX*+yi{JlxSMSh=Y6Jp^M)8g4^w zmvhv0ucZ^HiLM;TScP(CEm4hJvWBs-{P|YoMeT*HI>FeZr^+{f$&FpJo*zES2cMx* z@=l~Xn={b6Ir5v@qDFLM* z&F)?5Y%oXrhWf<449P3)`HMMfdAAdkg0w#Gb zUVwtDIcj-t29$y{-JSWDu%`r+f;8M!KyN6}pQHVbqgYWU%6mQrU&~R;dp@8Pr0Gc^ ze~HP<%S0#zX}EiY?&n-wQ6GA(=HQ79Vv$JmF-VMH_LxALp7Q^fcty($>VmW!mUo}Y zn&^q7!`DdfHHN}uleOr_wcY4B_3){qqe#)6ihUZk=~1L#?O3fJC!dgs3p18VsY~6J zcOnlX7&D-LEILU`;WQsXpeDL2Wy~xoYC5m%pZQrt9b!=~mAW4q&Ddax!oCjD(0kkY zr=|@hNMx8-r2XhkmR2Yx|E?nad>pQv5Il_`+MSO@&a~Vn80;pHrf1OId@b4z|EziL z?j+U8|EsqVD+Ot~mNR{bl-qs1>iLci(slDVH2PkS`uofjV)-&oyA$ok_*63He#L&g z6Jru+S#cj*NxkW6ko%eu5{&66RP42De|H~=v^jv{Z|A5T>mH&+l`T1D@v} zkFKmOKJp;(_> zOZsKEPAFM4S%TJ~UTBZLu^hFQ-rTSfo_022at`wZHBsMfJykl{C_%6tUX3AEJ0C)G z@8_t0o2N77Mpx+-xJd!C53Be`C&cpk6+7qr#%428kX9)C&n%M~KE9wa_B+53P^!kf zcw|_Vqi#7~etz706>5HaTbeviCjF#O7Kffz!eu%tg8S|`I$GLHM@#bWbpEQ1NxIyZ z$ZKEMO|D3lygN@0H=}yxa0nfD-FaFOrgwl=3o*B`$&~kiNKhA~Wul>Vv>?;;UVte^ zS{pI}bwMde)6#wVDD7$1L2W)@+MyJ*O~1aL>0ln=VEUh&|DdHXhCW~Alt4}N`H`bX zR~5^DeiDqSOw6G@MnygrY9?Tdo#p(J(t47AE4n9&=J2H?k)qWnkmd6n^^H0rSwct4 z^6$OrXj!31-Ijwo&hh0fKQCm6Q8g>d$1pUT46K!k)U#w_I1XNPN*T4Q1{7r0x}QjOg`ALqo?r*4UdK)8?anX^y%gAK`8;SmoC~t6t3_ z5lWpLnuhc(2Jn$9k5(c+y1L+FAz!oFv?>ziGSTURMC}D>sOWb9-_9|G=Ddcl3y!_$ zX$IZ;^CWVXj)t@Z+It($t|Q6iX*hF zvWgF7xjlL)HmjYE&JDcBNA*r*2&hS+7`oU6JMTMa8QiEyeDEn9&42!hKN`G`A)aQY zqiCzo{Kj<$Xg;?2xL~v;$@*sALvb|yc6q+eK*2dXm_WJ?%0NbEUh^OO?xDo6r7n2b z?LC=){;&kBHAvI;;p~FTZ_L(Qwk%?7G~AGZs-_h48@|Pm4remZ`(GD$!{@uG4R040 z+_Fezy{>1G_~Cs9+FC7x-#DG#scx)BhB%Us6nByonp)5D9Q774m=Y5gx!~0BAS?G~ zMIw}XGFFX#cbm%hw2!Dn^j_|QAAVVt)#d9$5lU@cq(-XO_4rqA;gyJ3n)84WjWQ4X zroIcL26(E`u2u^)%RYxyBGRdirsfLGyH5{AD5dsRqh615)cYS-CYCItIrkW)w)^pr z$vMm|tS7n-U={VNId!aBmOm6>DZ+AN2@Bdjl$*9@hSXx~1J*OF8+ytOZG*N~T3O!G zD-!!jnW(`#Pr<@3nDHytMjc9|%^G0UwK_}GewvA%EQ}WH?SdGZ?gpIif?pP-TN!sO z5}_}_o`LnghK{dj&YezoQRmQ9!FCSY9i(aL`rbojk`ld4 zcfvclG*n>TjmOzX$)XNvsOH{>YMTSc$j#in=so!S(V;#<@w1xL0Y3-@Y@F+>Rbbsh7|3o1U*DJMSMs$&+LFTbH!+4={A?~mK&g8p zQc#q6j#|}Kw()eoM!b+!2b(+?z~lqw7M2@bCo?EkEVr}3^$)a{pcE`omROWGOLUwt z4ZB#p6rq%AUJ~lD^$}m7UQb{>QNJ2yEZ!+vg7Y@UiH)mdpe@tC^0#~LBanca=n9DF zdSZFE<#_##P=>hBB@uZZdCPxXvw@+hCyuixg>`&z2difU+SuR~kIK$};omOtCy=Id z$lXG?qChX)VSoXGQjlgn@wV%3uIgz|EKTpq5Kt;NG!9)^^OA3~DuC8U)@D;=w`w8w z9+-xp6!dnMxOI9XYI1WJHZf?xv?$nCpeDLz+xZ|m^0PPguiq69>9QZ?rtRWKHs44f z0ox{Bjk`mQhW%-bMKcb=)(L5r*kYE8JVKwMHC0D31Z?NyI_^Ve{SY5VccLj2edpgm z4`1y;dY`5+eF^M8SmKOdA#$zN9d(-IjG+|lecJBdi|&t`q6yH*HllG6Y8W$#d;W7S zhB1(sw{tHlK{@IjqD+JYtj^=-L$1o+(2Bhg|y=pXB_q`XoAL7ZBE+n8P`Yko9 znbhmn9W?u`DU%PFLYAmDVja5i)*Y{XGgmD3KcE`;LIK7DiLn%xDAl1+g2l%_+69`L0 ztuT-@&-Af+el3RRH0Gk}aJ{Acv+I!r()3Kg8b(s7d0o71Wg`q@AR(A;R~>n@nx9l6 zKb_}y=`BTU%S9hb+v1=jk*eIC?f3&X5(t!nG@Vbp-%mPvFBbjz+@2wz)U>=CD)VRC zG(pv(sEzXzETyjna}lTCl_8*%a3)$+r%s~g@% zJ(RZEHwTe%6Bm4C(Jm4CYq94Bl}Xw)e)b%?gNyN9uhhG!%y=B0WPV0exTjhgzm@p= z4oL(OP!s){;o1Oy8rlVKUsP3U)O~@fyWq+nGV;kKObV1zMPEi8j86iPNVFy8o~wvU9RIiEz$QKgc{R=ltVb z>DQdbR#8Gn)4DJ==+2 z-#IFGw;c7ifc2!f+Dv|jdye``v|Q)c?p6>!_4=gMF*YaRlz10?m{@=BL(FN3hUO-d zQ6Kvff&PAS(Gg0#$?UAPQU0@g8jOL&<40!XGbP#%lvA~Ieg*Nzr$<`I!MXiodLYmFT!@tC{E+(uEPzo$@w`#>%VNNz*Pv-rcubN8Br%jD@ zOj*G)R47vPJ8E-oTW*pD2`JSrcfP7Q)wJk`56yY|zr?}QCQN-~ZgNqTEXh&-9OX?| zqOeWHJwo@4Owynfv=Q(sp9~+7qgGUxN3YXvRFv*FyfDpC{}Sm+V|u9qN#g+*Ne>$C zyD5OM#Dtm^CzvH9b!7-BwdvF)VovFA?c@b8d$)ktu-qk(`n4zwLt_*L0X~k zX;DGE5AVYePzvUWp4o3yK|H?Dn<*=UN0-R{k#r_)MFfGi>HKb8bE!*oJM((K`eCT+ zeYqJ~L4E9weG-wwa{IVV!xhAUy(_f@jFD+s>LqO}P*cVHraZ%$p1!8P?Ctld)Ct-S zWDl3aZK#LK9x8{o(6;g~F`jqr2V-Opm!;m))&(_H5W4eTWe=C7+S2v`38;zg7`fD3 zd)k7`!kEl6YSkl3oA@UXsEO{v?rQiC0i|HhS)!z2D>}dHCpqP;HiuG>ZWP=~^^n@T zFjC&35Zlg3O9-HmC4X_RdIs8mUu8;&)jC| zda)Ok`eQ{1B%p1DVnx^9+Oi7w``Wj-p_|x`62}IeB9LZ@fZFoiQSzT3hUXN?>ufb2 zⅅVRys2-BUDP2=df9~DGpDcvbY^6&qiQ>3&oCE-bQ=a$Q3;Xz8Gc-C$oU#ERJ z=|)Sp;f*-{UdRhFeMPEh$Hnolk?e_QM=v3_TzsXZ>?Q;fQ0jU12~l-?AHV9e+&-L7 zyd*A(-V#4+8#(s$r06p>nlGW_T1c}*ryotk$78&tjfEM+!|brwWKSr6@4+jEfSMEv z)7*~Y$Yq|=nbqeR8;`%HiEZz0=Y3q_8BO%t#D?+Ww!%1#7q^RJ#Rl@2@jVv@!0qIQlsTFMb)7cv95KQ z=JDlsj1;8lO7iJhqVv&t(h`0SLqI9h^;zObu_gb+c^}P3LeN$5cJwUCWS}2IK&iT( z8u4=eWzFcJ@=2a%MWv#(jia=9*B0^g2wq%eI8QTR_8tOL$P(k-zl&p*kCj?T(V|HY zLCn1LNL{izmLZ@f+V3hpiBV_9OP??86dQa#Dz0jnqwX;F14BSf^frg-y@VR{%-7jB z3wY?^XXB5HOAf^G?J`p;d3&~FGt%>nr_}ONKk?kkB=J{NG~c1tE23wZATB8l=R23b zC0~aph|3?x^To6$QYbcDzbiJPIUoCBpE&Vbve+iORP#3fBkB4lS@dYpmao?M9jX8G zsCdbqdXy9%qohhm*O>2`P#!olO zY?1JdA)syA?^a#SPw(y|&3O1mgt{g@j~BY6;QgL&vz4Sh$z68?_ z?Lkd+CiQC-65ey7wBb)(X$DCWOIOw9`*iq5pbeH7;kHODIX^;5vTVrY1JW!};xSip>+dN3R9GWCfykePIFY70hDrk?s z342(p?l$$3zL=PaiFxtjmnUWFX(m4jq@U_1il)bps>@>JGvYh7?8te9w3QNwodgM( zb4b&ZLWJGq?1q)n_=B57=zY*D*_@ZPPb4v&J4j7`3}*5H)1H6ju$Y*AN$q1Pr%KPw zRGe(RLb6!v!PGgl0sV~<4z0!6MLndDbSnw!f;QOF&2)$m=f0aOjhUIq_%3W8(0l0a zfm?S)KQd0TT60Q-EeEy9@uV`+MGdS+t1Hvt-VuZj~88#m8U%jYM;vlJ_y zm^JGkRR3tUuBRNMld4ST8|0`xu6&_o_0}qyleyT*gfZ76UTNL%UMN?Xab zFkbvn|CJ^==^KGGOFU^^z%}`7C@tG*CqcdC$2Nr#zB$$now6#Sxu0j z6r|-m{hJRz|7`AJ=f+Zr$5?HB=xPe4@Fs1W9a`k5L%PY{K48sTRehVal3)Bhaagki zah1^y-tx;k^6TSfQQ13~Z*--U%%tPTP1_UsH9ik1acP>rs!6_=^!92yhJaEX=*a1W z@(^#YeH!%c=Et2jo+xos>q<~Bw8xg!kG1Q#n~7tkn~Ek9jDZBq6Fq&eSmgNfy3(+^ z6PWsteMwgeux{usy1|Xnvs#W)i>rFlmAdQ27vcoIv-Fs(8opZGQ72Y2BmOb*Te?P^ zXV-u)`B6l3Zev;p^=vm!+FSFg2xE5E_7m@Sp2n9PDk4ym{8lswt^8#s4O-AgD$83b z_Mk^3Pevu=!0IL9v=8U|UmIP_*rVf;!Fk-+jHQxTf4}(4*i<(FJ}Oo?~9wy2t|^Olwc*QfWy|0}hOdPcL=hxmHl56P8U zTSUJjQT*!;C6tI>lFC{1YA)pzj*`Zl+bl|5tMUg1ydt%ZZx-wB(92xZ{w?`w6(U|* z7^QBf|ArE;Q#mwf=~QV*jn5*i16WqD)D?=All!2UHzv}qBy*;8AanTf{F39Ki1ty&#q^JqhDnN5-_#&O!9m51Z87G>80r~33>x8H<&_t?%=yb?qkL<$*Z3s<5$oIv`uY< z%;Z`wSSTH{%4JdoQ^NYLp1MEhW3g7+e{?S6?NAER3PtCkW?YNY-qJ&dKjc8kDDmRn z5PojWOrqDsO$@;ayw8wRRS-^ae53Etr4d zAoo5U`o7@YUb#tUk0pvH^u5H1;THVIYekGbmWZtSi3>lzL~3^EsOVH^EuM|)&36<} zFa*>@&u)uvgKp1plB&f$Vr8BbJl!El`4NJtG{qL)j7Z%f;$2C=<_r4C&vwW6-QsW#u ziCyV;&T7Zy_jB9x?%4KbGAb)?$@TAELY53z$bV?Klf29+C39!h$h7RRlXw@D5cj^* z`QY=xlt_Kule64H?|2rvaSuA&CO$sdd~sR?X}RYi$r>T>J)TF9h;Da@$|jF*w?-xc z=RXihqzgX$*_erm$hb=8J>JSU986bM0ZsJ#NA+1!Skh+{6UPypc7<$l_2)}BQoVqP z^eQ0BpP$jJ=_T7R4tJA|8mA$_aj(iK_7d6D@Vk1cKxy?Fs6C` z0^&jE7Grt@6R3&K$t3GZp&h2-YI)vDm=c&mHXoCWjqpWehlAU7WlA@}qnNxbJ<5+h z63mnv-HGJqh_VzOc(k%UQ&zBaAx-;|ZoTol7$x4-%s>TWU~RHB_!17eC?ae3ywXc?QV%cU9Z}f`)vOR#@)Gs0@&KB}F+6IzuMNi3C zUgBG($*FS9pNWN{3+U9yt>{8R39-Vn`5Jk_Nli@hMAvbkcAnIz~s4PfV_>ZEpvY_H^Oq4EtPlgJwYtO=q_IDG;%6;yfe0@yK4K z#P#(Key(94=~Y%nHs?RqY;8uvJD-yh^T~Yr6**N~x%wz8KT8?1*&E~9FNw#PPipB> z0GS#2f)wCann8C07@E$0h?B^Ufg6PA-M;w3*Jq^N^(fvYCxFQK12DjW3kuTGz1AK#n#8Xqm9wn(B>F#vB$91AOY)! zzSzXK;JS@$jGC*wG4vl;o6z4B3KNT9vC~zA9R?ZVn!Y!PyTeKTSnNguY3RrFETm8G zg`r_vgxPoLO_jiR`!y{j?UJer4HvO~OxN7it|D3V--s5hABSNpf~^a-8-=3m(*&u9 z2S)9?R%3`aOD>XKUoNW`BnFW2mIcJ&)mhD`6|!ILTsJ_9jatS%e$g4fynBfx@HuMR zksBE)NYhoUdA{86A$`ceLB2TV&IPh8b1px*N&pE{Tp*E;+VM@l_!9%0OQh-LD87aE z%g^#w`^56&J-OEOoCYXWMU_uVZ|16Bz4j-p4b1^#lu|`Og8aNNl!7!rEuYNq8mSrg zQ$81G{WnkPlIJt7`=2`KQR@N{Uh}PbQMX_wA25G(m(a;=;sT2aTvXqc7+QxV4eimp z;xk>PZcm+1$)6+yOA*>LUUiv_{AI@1FqfY=Hwx!UQ=A{sU6SjSkbqKbpE&cRQfd;i z85IvU!Y~G=3TmSJ&qH>J^Dl@?$W0%^_6*w~OIVB^EnK}z%)x)cG)xV`-i}SxuIyFfOk{;8g&8wF z9F&4Iy$9>@c`~(z7s|S|ipe?b;b5NVx#!C=#HLA0aCC+*2X(>Hh0kExi*_Bz-CSjh zm3r-%o*MSf(4IoEr`2ecNo*lfD(5lJS||l+h2nnCTj-B@XFNK#1M|dz&qS8!Gwu^f z{aRIwtm4JkfY0zY=}$s>aa`Pu1#&wp+lY+rWfV|rjVYYKl&ot z`~C^C?>7=d8<2qZ=t%$D2vnxm8EF=*X2%R*oWR-$`ql%#IMWr6`JBw;1Ew90aOj;D zoAq&U_8v4jj>B+_1IHyWwe(b#&W-RLr(k5SZ-=22%m+&xdpZ+4+7_S=twWgc6|~0^ z(t=tj@XHi#yrVZ}#ycSA(6&Oc*mNJ&I+6b5a;@f>X**UWI$??qf{?S2>% z5oXWHhC^r7ADRbN8uh&h>w>59&fMH812B|=DS`IrO@BRGqh*QnR3X*aF&reIrivY5 z`^SjdTYKbh!VkNh6vll%FUVn!A*n)ge_k8jTbLqz{&j?&6rx)LAkPTPQo0y99JVPz z&|e;{B|dwe6b=X9rv#isu1x5p1DJxjIx)PP`=}JM?{O^|rIYw7gau^c2 zx~U*;yA1oM&SB}ox?yct-ngRH05c zGcB#tR6#tsT_sZv$<~Mee8;n|I`PR(ycFnsr_%x-+B1)?#Ekc^+H0Yse%}=tlB@m z3-eJW(pS*mYNyT9#v87}+bx!V^MTJ*`6pGn7&#^WCN+f}7j9??ou>agRk|C%WLlTP z3c_q&%s)1CF|yQxh`oG}%CS;eRc;>}JDUsc4-B*^fvL)FIYGD)*!_Rh2h+MH2wE4$Npp9$Q@AE6%vbFXQ{>m5c$^UDkoqO~@Z4gR9`q8?2LfX`N|07i} zCAyVIaw)K>S~1`0pBn5vN5ciV(&+JHT^P72chCE$|`rcg)!m(ZnGoAbXdRSxUu z{}Q_PEK9-m@&EUB*gkaLC(}BwtZ3&~)B*q0pe{z1f?mSPVK5smBe zr;Lthr68fxRAHm`BQ0ntjLp&uCUQ|SlfSc z4yAfNIj6qTrozU*M6VTAO0N?duJE;wBhI6$9l!AS`&K~{pGonoM{jx6(h%w}3y}I1Ol*lEb%M(3Utyfi5 z$H`0Z(n}gqj)5hrqhT4+vKmd4bw2gN?w6I?8q^W8)NuFx{LuWgO7(H$}>OHF8Lnn$!BFI^<2FHYK%Qo>R-`%gVp&PK(vH4{WBk(>|kMj2zaT3M+@( zzAM*k^_P8@wsX9C%tmedfH86y+GB0VocvdrfHt;Fa^#z|KKj>2du8fBsmgt|g|{=T zxbajcC2P{rvgUtJZ!Lf5Dn=Nu60W={vX;Z|=*q(;@f!p=oK-tVeTx46Ujj-&I*Mv) zL}_{&N!N7r{vdC?)ZGnV?6Od6W6hcN%1&(;igT#mJClu+_e&Ov^=P-EikE8jbCtbOfa!4Qe_>ZOAlTJLr9cD_yx3`#VoSS7O* z8s7Veo_JifF717$@8P*>rS^E;;g-^FN;q`iEZliDQz)fUo%(MTt_V@WTN<9yd#y0; zl^?B-ljAj9%!=OFwbV+IC~@T8QhMVl$4I@VgxY1SP!ceW66sw|a;K-(#rJnikYrs? zvO5ZE2oercdP2Y9LZ{)K1eSQPJf5?*BPj91B59|bkJD|0vfhogHgxn0sww6H&zIlr zKy5ts9Kg-|(L))V;VThJ{JMQkeWO}c;TR2@?Unel!BvGEN=!)0Rks_|iW1YM6I@uc zS$O+~4RLMr>^WEIZ7YWF|?ouq*`A#}emVk8rNddDMNvVl3Cxs8U10a@ueL?Xg5!?M&{>ylOb&i6g#82~B@H zVQ20ja*L+0<_23mp6hl}K-1+D_>b>j z$1U{o#pmiaQ^FWXz;;7-J5BZB=C7l778SkIKmtnTP#fO|(RsMq=V^;NoF2_(KK8&H zT~s2BfdtzIg`bJs#1Zb8TXsZ*F*&pjbgh#u`c*{1X8f}5)ZV_+W)dsl^`-ko*awofw=H*_u2@4~(o_NWSlo970u z?p+P{+{H(NF_4hU>fe61;<+aO_ml1|jS(Gon+rCd8VWv-qr~^0T`-S2drjQ2Xa zuc+d!0upj~{HK2j9j(><&xj04Ri-CU+jlm|=jp?dj4Y*#k;6t`f8s7WT|zl!-j zIqkaie)}9KI#Rt?4s_?CJ-YJjtF?B2)W9dj=8#Z)2^6PNqET@#0n+qtrz35&gxYw! zc@a&?L@L!Yx*{byduaRtt?gQVTWCHky7bZ#a@t@FOo@woqBxFf@(2i}MB9Tl{}2%u zQ^YYeW=8vM0+jL$%oK;y-`!g^ro_QR##-V)iznugfKmzNC&f{eDBdmG$oS)^-RG6Q z&E8y=vZpb6CR+t41!;QP^nyMWsVeg_hbe*iV2Sr@{t`6jPzshPOKkL2{*!Z92e58- zJP#44(9~X>XixLuzr#sO6cl#uSGW0gZ9U)UvQ$_;WUE$c{>|B1Ki1U^9lffmYKcM{ zy?#&^v;k?lvSxd~e^S-|ceps2T6g*5CqR3UrYj)YbkUY>+{_yNR#Q)$LmP5^_CHMKSDDbYT1eBCnbrI`zRs+)wAH?nY+ct5WGP7KY|~X?lvwIfn0As9&_?Av z=`_(3Xok6}ydV1D;CdoCa%m$nuoxvM8opHq_6tBUR<^?AJ{GELT{olpCiX(LK^;}J zoqykC?XhesHos9-vM2~fv(8xw&o)g}?MdE%&XrgRYu`*!rL|v=ERS{+hF|uj#PjS( z!I9oZQ?_KBDnS{Fj9iBa_uHRTLVK)@YzG6?xJhgA!dvsu(S9K)FLZ$LHGM5ZKuvT^ zT|I&y@pCy={*Fd4rt6h$=yX?3Nc=KN2{q9*EPWOzJKdX$kGVcVb?V;B}rf)?nB@LM}5q%%; z!PuBz9)Whfe5WbHTNrx^MQ}>0)p%luTxxk@C}o}-iXz89(cHLQnK)x_rHQ?BjQd>Q z7f00GiHg&6)Wyy_ct}7^^t{&`gN*XnL)`RkzIb|3D4La;qc)tw5>OLe-Imlzd9`6b zeBqlphMoay@L}0zWWBMqpzvr&zf~@e(^JMiw8wkb8DJO#{h0Mc?pa&je6by#Kgfu& z0cn<4?0A~*cybvwDLf#;-T=0Fw$;A9^ToFILZ*PXMi-_n{o5FMj7FVdp@oq z!9K&aUl4lSse{n@sh^4^c8;#6u|8&rhuE4*(RcmO%A+-e^}|C|i>quz7dF=rw%UcN zAgxfezOmQ((FSY$*wI9SG0+~=MDM(B_%_QYz9n|UqoiKefvEbJd%VNGD8>d$1bwsB zbp72D-}^mMYS_vTwR>=%kHb+aNV9~~72e7)>kT?&7y6v$F04z7rp)S zsmAc_N2Dm2CBYa-h%J556T4*o&7(b(=n(xi>v2XRN;|n!dOaWj#Wi&1zgowsAl+b; z4{~x`#^>)oNC`oC*Sfml36!qqEyIW=d!t_*p{erxu8*rOZ^3UG#1c^IakBt4^g$cGcuYJcwjMRmz8f?r_E?sx z(Y_}cM|E|x3qTvjE#`Z@I;es)JvFE8d?(Aicf<~bVRzOQ`ym;AKH2JHjUv#e{pQNb=1q+x35{evqF@HuC* z%=^#i>|IJA3JChf2Pwl;kYGk}(^+RXqbS_fvDmfK?(1BnRtAavoIv9N8h7bP5K z8sOu$%`I1awZ||95`t+k8j@=&X!^QR;*N7g4L1G6*5KLEA*jY1Bpg^eTE!ARa}97) zUvu>>nh&V=PvRz2kYOiS8k?vfP47_nYeS#ffKreSsJ;bhI*k+pLmJRjt)4^6>W5{< z?vM6(()37FoBEZ_q-*><`>p8nEP933%OWMD>DjoH*k5qOVkae_E+_?Qdfw7J1H3Bt zPyZ9|?QuWPP_*Z;t;_;X@z2e zs{xMh)xfg*TYGFcEez#%YA)EAH`71@YNERbX!{UnPs}W$?W5a|Fw~iT{Vr~rt${R4 z+@^JYXXy%yowUx|><>p9Uq0gV;@a|%W{Gx!0e0|-vwD1j&Bq&61UeO)!tXP47CdHOcQne$r>hWAwd~?ksP_p^{BG>d)7wsN`_t%{l7J2gYf`fAZUqTQvL+VXh-| zF)|^CfBmI(niPte^zKYqTE0(MzQs|#1G4h{jO^`>^ae>SA>Zg(ndnMs`9??fcE>xa z4JQl7wKtRVbNKj0D@erBTeJd-=4yYJ^Q`;xlQLW7 zqE)VHZA^I8OmxWmjW*0%<)PnQk}47MdH_gVK64Ib{W+(V(l6yvji)aw5pt@a6q$Aw zHPpNIKZpePecE?(ndsB<3~Dyuo>pptb2dtN{zw~6?sN)SAAI^hY(V1TAQ63-{9G#q z?dft|F>?nAs29@z5^}0w49qQSqv0?Ut>0EID@eeSW^KT7hf)c1&ZBx<)c?pil!Eoo z5_Z2I_pNfes@6*&0lfs$|E5aLN0V*zwEDFlwbr4(LQM+AmdW-YeQR^$OrnhXkVL@~ zHCcs8PUKhNlVu=^zSE!Fckf5Pf83a4BsMOXi_bQ@j+(fKpy$;(6A$D>vO9*Lm(_ca z!+0`T(lr7N9c)P6ww^=@yV7D37I_ynsqTU^-J?;g<2~UrJ%fZVsG@NQtI+5?LST zi&xJ*#?QJv14)HLiCLF=B$M7?|M~7f;=1#@urJCPwQoI?glw>;MC}io#nEXEF}Yxi zecKWAdG%f)Fm5<$wS*v}w*JD-z2nJZ@g&Nfs20qFr%@trVH5F7uhlp*eg?XIkxKP` zDyZ}7ldT_9QTrFKgwJV~q+^qGwCnI2q1EC}lnA)nNc33fjgLDODF<&kg_ zE}>vOBf-vm65(rV5O;2kP?9^7DFynKtjtDiRk#pe>wFZcoe7Gwx+QFG*O}yBIfk|z zeJQlC7{ZhSorn8gle<^wi@m!ovF_a~g`5A=k|bX7C!NQh;#{U%(>iEM^t~@~K3$Zg zAi68fN1qH^;#rb`PUbDaFo&&Dj8NHeed6D78yR=x2WMPhMEu9>phUS!K}NZ56kgo& z#r@o9?p<^ELEXd1-Ai3jOP@1p51(y}S1J@<3!bV{`mM!50rSz$f+)`NSU)1%2qt9? z?YTblOvxI<5OOEG8kaNJj4bq#?@>&jUyqyA$O?Bj+y{RgoTGXYWlYrdx06$=ZB#?| z8?huuWsQYt9r4LG0*Y1fLeFI!<4bv_sYvv^Cd4S=A^hnOY&Xkznb_mxX%@?n2 z+ugbbH=5jhWlVZcSwU}b*-YBc>Oe9|R+5^bTS%cp2jZo@`Q1N!I@htcFYal+lq

zO0aS5PTsv=$E51htj#1iwHOn3b2y}^2Zp6sUKYj8H8mwCY_^i`KccwqAw7sRb33)+cIX0c=HSZ>^Yz6a>7DnT z5?YdkrxB#*coWX!SRJx2ot_P_)Rud;yd`l^$-Pf%JvUYRu18Teomqo1bJ`WE&KR{I z<8vd3o#K}2*3Z@?^F%l$#w2@cE|=Zl?(g=&V@e;YhDO&T_YdwQKNBCQvQ{=GADnhF z_UKVCC*BM9?|dXb>iOW1!VPG`+g|*$nwyE^?m$%Q!6kJ<{Y@m}=PFbbc1FEu_GW6M zo7s8cLG2td?$<)RWyekwXI`H-_6;Fp=_&6=*6C$7&e%vc?+-;Y!#eW2H*TWDGt{)gF~8WOPAre|#Bo*^dbWlD={J{b1lP^#1PeaLXvOn&nsxo_`(;S^~e;jG$o z%LhX#_{?C5-{04fGrmP6>4P_hDS>%{n&>XN?WM$M@O$N^=|1>Rodf8rkj3{r7D(U| z?!0&am4#g7mra%1;I!SZNU#l3eYf$!Z`K|}H#ZdWW>o?Sl!7$fA9eB*nOYjET4Tr( zP^!+zI3)Bh<2OgjyXbDL`b5;@x2j^>uuo2(m+{EAlfAIGgFj)3A)hyrme&)MTbKCa za<6b?-aAM*_9TSK2b=Q+3ysM0+vm8*7#|Fu;gEj%Jp>t)>=i~_lIwh}ZGC#`-ZAA! zx-0%BiASRkf96Yu`4b#^2o3o1fzNvHPhbk^Nrhh;i4UhFDD~-62NFA@U=k+fvcFYPo8AJrA;La0>F8ZLX=)Q@)$S z@`083^ZHC>P015OsgLvqk4}X->T6y6DiKqPyNGQ!*HqQq=!I*vJc8=f%Hr1_Tt^aJ z4kOza7x@+~){|L-Qc$%9hC*~Z*~UhfI#S<_OE}G)iP&%bDHM1)jK5ZGGTD%N8i}ex zewwj8$vScxWjZCRw{;ywiA#wAV!ip-RZnWI#;ZmWG-zrRzpRZjSt)3c;q$ZVX1x}W zv**>QTLxXf|7Hm#T5U=dcMKShhO1ne=OCmDSM%t4nYmDUP9B%st6xQWaHuT~`)Pnb z_@6@FE{B9xDl5|Q_-WLj{t014FZ$F!a|SsZ?hy7Z=|zb=)KQxJxCd@FHXA(=&my!t zQ82&Pl9UQ((bV3jgjav`h;K>`%D0LU8phYA#8Jyb;{2FNctVE<=suCqj!D@=XhGZBuv=uMa_EyZC6G}aF;d*b6qlhKrGfK{20%G{zk_P=GNl* zRlIVP#uIm;yFiU*x8b+UW_=g>G+nXPR*xKv+b_;Iw+zGn74}`Q*QV#1hCkzeZw{^EqK%o6~PQRoc)h&trBo~tJ29y^k8 zn>-YyefuGlZQ06MlVq5o>%uvg0dAKuroo(4ugm=avl`i%;zPARL{s z#DzZdrE=E*!u3lxAwUrKtE=EchJ=Nl0^;7)d|1J5KwAA)imcW&#$U` znZ8FI|1d{fT+L0$_Fju&uMa&R`j|q|^|*=HcBSC8-V zll2nVuRxEX?*;*#1&epjt=CfmdIOY#-b24G*<2I)Jm#zxykP4bdIqe2g`(D_B4N6J zXjbquU#x%V4_Ex6A^ANxjHzc>oAjI409)b0;jYRz-`P5cZ})I~P4_E}o+&k&bz9Z@ z$2SD)0QNpbPI>6)izDh<=B;V_xbWCTB7LrKrtfbt#12|(5eHuILoF`~Yz=NciKSK! zPTZ)b-Ebs*Blal1!n<}t}q-e32tm&~!DHVnQviiZmfRgH~2 zm^z2`40|Pdeo4LV;;Dm2$L?1>;v_cXi@B+Y#!)bZLPTz+Q-N{ss{ zoV*##%oN~0HmLNX5sBO$Ld)vegIc72kHwbr=sP;}64J;N-Ov-Ba<9nHI(kCJGu zp|H9_ykD-6)j1!<(cPdb#T&szZp~xb35m|xv<+s>zaakUpRbyJ$CVkwJ&mAak>EJ> zG@Ho;K7Hu(BiUGNI)8{NJH`vcvElsWB-AwMKHq0c<#D3hw>Dz#bCs&bOD_ziHl0XB zjaIzm*L2=cX@op0v!nR)aENO05ibnu8Pc$36^fe*eexo{KOb|A9qGe&99T~ZMc9ul zeu0lKvMycCyrshT&(cP_IN_cV>3ds#=PZ9>#t(Z?rb+z6_M&hmjctP;*VR{E+w#ro z7A2q*d}C#aA!*a4q97A)eEmO68-y)&vQHkGwBi!qd3{Tos>g?&q>1BuqWtR*5NxTi z&BOXvDAojwliHO}=a&CzgrVMu)ErcoT;w}1>Pc7|N4D8Wzx7veOMZ93ux-OO4{7>7 zShus(vdRW-WY>Whz7Ifx?HR0_b(E~nPUP+t561AV0n#jCy1JSaJ+ef#>HQSOcOeb^ zSfOxVQ6OG8Q=faQ?~36#3VJw8csjNapLyL>PO@bC66m|^yIP+veMw)>Ht12B7xVmp zt#&=X4DI>xT$nUYeuJFzc#n{wQT;yN%vcoGAgm`kG6(s~7@Gv2(9g z_Dxq+m3)x4+Di0cKig{IEH`ZPbR|b`57Eh@CenMol6hl+^$hD@ zp?G4QFZQd_4*klW$Mg)aokM#H#f&z|q7scn-NF}QIG+FsXpf%joX?3)0ku$bZY?v) zfTI`q?4nPcs@~%Ja1I&yEXPn6Buam!BfjxC!7yww_1&h1Lqy+aL(t{ntC*Zaf4yIN z6kWw@gif|=DS?|b5Zf&YL6IfP@o=+4DClK`po&~iptr*>TXe_az!oBLoQT|gR%0jy zX=snu`3pjM@#yg7;Cc-E!?+)X;F}7+sB_zLrLoKKzeuZDhz!T`VxEtpfeNA zyhsaGD!P>5hT%KFk)vBt?^VUZ9m9=;C1&r*BvWxmY=3(Yo-t+_y-B+znNi=Ls6S0Y zcLKT+%@BHLFy8YZ2mGWme^ z-mgmG9)$EH)7#5mu>4)y3Nsg!qc;tm85^+Ou>`-cIUjgH4`1s#4LkI3dj8eLH+#Z3L(X92x}vEO>fD@|2ZOlO_)&zoRx>P zLNTd6mI`icMkl(rW(X(+$0!QL)K49xhXW!}_gNMg_8D+g!;WNHo@+0Se;t9Iob1mK zP>LOwyfm#TwK9rFbD!E_*hfJrc9gMgcDlHVhF>|k=xxSRvxn;hA=pJ<)jV_!3XZ79sJHgW3hMW8)}VtCa~;xF3H7p`?;R_{O?>?lKZIhU;1t44#97Gv0RLMhlE z)3c*{-z1;scflq%F@`Cb5#)u$%$B76wRPm)S}&CSpgnne)r02T$1{?=ws?s$qMR5T zun%U}6nWnABvo%5M?-lx=4k-?bC_CstJU!slI8vejaWLH>D!?cd`i$SChL9*7WEop zpRNuV_Q)czf*V?^5zh8g!IFGy6bFa1bUVAvh z-h13guD`;46rK&h4B69HZteP#v^y3A!?23<_Fg-#)#CSRI4Ah( zWnQ>6ZcILTnmn4~c7R(EZe6gmk!?4rSNUABZ}51EqZ-q=bwTgbbCHxY@fN8%Z6w9{ zVuF7Y=NkNxjsNq6T%S6I;`qU_i|ZfOv9$fh3Z7J^BbyB12;92(7Imyr2CFioDs5mn zfQu^}?N~S5M=dch=THoLbWUT^JLvm24ztOmY^d%l(Z zZc~k}|Jk4O1Gfo04}!8fGn5S~s!R98^`v-?gWCtz2k$0cgtH?Rs?vn=139ZO%@dDW zZxI7*)U_(%AzT~8?GDe*;j5R*4dfXU zi^%dTEx2gM5spVVi1t3eq|DFdY2s{0j=p4_O0@96n=!XG9? zOJ$$eroFm1?WwH0fcU8O^QVg<>h(J_@?;Cng~m#q4?h(C=>i<{(v_ zZAN=d=uR(H-a-Cky%v);2Qb_o`Dovj)IpjTWJy=*I#HY#CU8!$JIuPe(!yjbI_OeI zZp6VO15Xt0mRQw<>hxE1KWw|Z9?HpK&OEcsD9e)P@*&p)57I!iu3 zj}^<_cm!iqVqzEh(8>2?al`8bf8&9rFb&^}n$(dW?DwV(`i~$>4`h=j`A0;jPH#l~ zwTJ}I&Ze8?iJi=@fQ~(hj4yf+Meq4T`H`uLG2m0bKD+PsxN;mC8J~qdasNNHzS)`XET|js=z)C zpT_t$xbAOFsd5K_-kNGn?Z&Sl!(Y^8mZJk0CioVWq%LBn>0Rl@^$qB*Q9KzQg86oQd^!Gu1P9YL;uy5m>5HT4xeF)RhGeRKCo# z?X;G83T^4ZJ1$(S#Zs77sUGA{V(GOAU2(4!N9_LFkW_5u&enHY!Y~bcSq$mQPK|J) z6^S!P;NAe!Z~}3iRca#>7rNt9JFaKIEtUWJ({X$+d9lTPa{ki=f?E-uC*rmVYxOg| z<*R}v^T}T^REAO-8Ut3f7riyEWxJ}@;0;^^F7P6ib zy3nYBjVQJROJRK~)szk9qOOxbKMu2__(=+$Iq|cl?omE+@5|L`0vpCX{lHPej|LqI zjO7E*2$hCi;lAs`bQk9%#Xk0X(iH=Ru1Y>6j0FWm3q zbqMg4o{h15V=N7A`yON2=0mANJ0ptM-QYVfd`AZN=dU)iw3Go<)1oTHy*|G4;)%%6a8~`z z5cfMaWSE9^ES(3jmZT>=Jf$AR;{+zKZn$GHJuD{d97yHQRX75V zIAP9jgumV0Sw~N0-Nei?QR3B{o^+yfJ&L7p&%hJIW@^@!X3OmmE&_+YeDPARl2|U6<-)>9f#?5W1re}3w$;R{K;+^rLCO$~S zuNBhE@W|I4cVRYG-?*y-w!!(XimFlsNO1fEh0_{@k2EpS5 zUU$b6xl$*Vl{Ja(Id+BM$e3%~mJI3Lk&W{UC>2+^<;$}BS)*t}yKe-?)#VXpWT`o2 zYfQo!&I!KR-tt|{i62WpvFDr)OkjOb=L>g>?Jh%$$}*x@3hU$Js*dQY?(k1vx~@|# zZj5s5c}N)C#f43DUe0h-!uN>@hdlj_Mo}{QC&77PDNL(W_sy&YW7qaI4a>wS@#yg<90*nk$UARmcntYD(tUqy0tkI-zslqd{^`ru2=qt+Qoe! z6;^f(YhuOl$)8*rhuJX_O_{v1A>)H<3?em~KP zJL6;#OJN$mXIS%C8Yv8;PiibCn_*SL54$_!v+qURy&4|1;eK$PnVj0ho94agPw-tF z)`w>Uu*X)-x6is zNpK1#_*q8gFtxPe$TZq{@D6S@AYKQ_6MlyTsn--gdUxY-Vl;O>c`i0$d2f9f?ip~8 z0pBxtb(PYnKTU8r!1X?u#`<6SaP$d+Q*i%L?Y$@Q z_v_5=|5m;!s%GoO4pyH*9j%XY1eU_9XyLo1*6HeuCgZ4InP&u#MYwI_)s8Ba(X%`? ztuTp_mp2HO!s{S;;$2-c!L9XpDvxEo{iypFb^QyR&zek)d*P>u0%b+1MT>BF*_G(Kzv!O>7{&3@7-(1=N+ORvaH z{Mt==>*Ys3*3fVS9@TJE!b-h6UQ*G~0BW~-97mYnT1S@oHf5HrJ2I>f*0EgllJ++Z zpdW8c<>Cqx*jkk;%dMG|y(fUqdKttKIQlRRD?n?#WBaPkrBk1WawDfx%OGOeg0MH^ zy%?t9?92cYNheLCiyOmfX=q(L9(Q@d?%XPN;qN?J@A+(kS6kzC+k7Ne?A4a_>>oe_ z+%|FqmcntYQuVd%FW!7IlZH>OqQ z#q0QNanaMJ%q$xIE|GM7_Ea!Fqh`0NEoN8;9#K`Q4o^OL#>fG*QLPOGOJN%8gSYzY zJE(o<%%oOuJ|`Z9F~RG|u^lSZI5LAy>XF2)mc^}zU-diNWHt*}8A^o}H$9fvr4gz7 zTT$5~;prPjw&y<=zikT=@v3iF)tGsLRk%%$0d*@Z2(vP2kbnyO~1h-DSS{l=^KSN4;>HCiP zw4Cod0ZZX__xwi;`E#iy+xOZD{8-kZgH$zeKFv7&O~6u^#=2n@cBO{WhK}v-9b-5A_L_!Zg+mZ}soqWhz+3x_fhFN_?*S=oCbE209Sjp547$k>!?Mn9rLD4AXGtOSufO<=utU=dClrDY);# zIl=BW%g^YV{|cl5f2IeVwk5E=G@2g@VOk{KEo_di4OW~0k z_bc%BHNjSBS2Uk4vL8zD>V8b~#J4v6g-e5G)8F~qI08%IRsV2i#*m3Z*-;BAGjb<* z-9O%Q0P9w%4!vwFRh_Yr-fMnEz^xPa27HTJeDfdn$uESe`<@o?{vJ3I`MA3G?UwrV zvrt<9^$ZUjCAikAKW{)zp6|r2HyjV8yXnbCbtPC4@7E(;z$uvEYw-2dnnKcuP-<%x zDBzTJyNZODHUisSw2#PC5w( zxji5-jdjCL2wRlt2f2El*3QDB-U0s@?6 z_i0Wv*5 zzOUaS*4`c@Vj6n5@4!QAWt;f8YJTTHduFe zysX^9d^lYcZmY)kfLIFC@W#D)rc|!;RQhIXdo{l2#QHD|ck~k%NY7jXY2lq_YJ7Kx z37iw$J0EK#udeA$k6)~!#@^ymz}CXPaF#~$vrfZkhbl#$*xso-vdO^eObm+)5_w{N zorbdeux|9??4_Pq3hU#ErN`v&)oLev3Q_WN2D zu5IJ?2>V$MEGxZu5lr_k$nn7CgXeR2&ItQu^bce+!SgjIY(4NS49^oW4Z9RXWU@2& zLg<|Mi5__7g=c*@Cm3H9N`)=<C)Jnp5SlJ)g%h?0(e}wz< z56K6G>fhbise;NtSWI0bUWE13lTG5%aWptK_8}u@c(b94j2RzSm5Y|?JpaIXcTuN3 z@u-FgoD;l>Tjip5_!&w~6SwIwVbr1>xjUjO3#?s@VOphnJL87>28^7iv_YH>Tnd<0 zsaoxMtA6@z83UYTVp$>$E%`qdrop4ZH7Bli}73`}#arxkKgYRBV-mzwD1L>qy1G&=0(Z>_# zD(>@~wO}k&-FzY86ijqU^dJe-y0CT=mD97uW?Hon6-<48R+g|7j!K@$=-FM}bX*AC zc=Hj%DVV?!3VZfnJfhx|97+$YYAfIr9EpLQs*%<^z1ZAX6R;{_QhnjRLnxg#Hd?@u zc;@dV;k;I0*|jP$Ov7^qpPEvwQNeW2$yJ_shKzUq!hJBT0Bu=c7~d|G_Ilj6`%I5(9IIzwC)zK;Z1`=9Nee=R|mG_kZGnE6yHFv<5-d?HtDA9jHeJ& zmp9ZZS2!=_`iyCHantt#{VA2EoioLv-C3YR@nh+evj19zb-WyRR8*O}>vcGX?hzaQ z>`<&@_#ydUV$6~lF=(BSUJ83|g-@5K52v*JmnhL*+Nz#8vUu{Ww%GH1X3qcm;kK;2 zXx8?c-u4nHOdC8`{wse<%J<^)wv}tY;xoOK>oqOA=;pTY0zVYb4@}DVw{)=%VfA<2 zeXH}FJ_9kmY^Q(ya40^(T*);IEty)^y*O_XR? zh%S}Q#H5=e^z~n2t&)2f?cFWu-_pf#g(JTtjt!-Yttx2;iVhqxCA2|@?_}S9%c`Vx zDgPr+8B{><&s>jCi|DNKC+aM-Naxz$jb>RLA6D2M9e+e9Ym@bKY z199r^3s>bz@vtNslxy4uOL8(060PxXSz!Xlm3PK{-S+b%i|eC$R?)w4g^6X*w%4_` z)R$XH`#0!N{wsfqB^jUKd`{>AN?VvwEnC}mhoVF284U6UqC~r%E|$VHoT0F@Kpe35 zWNPfwP&(Jng>{N;&Q8A$XQr`!>gdHwbRW6~vor7&etp=H_#~`}gty2m3dHwOQEr<` z5m+h__Muz*!HSveTm;19T?L|5_-iLc$Kb<$>Mo!|f_$+KtQ$^h+Fzh=?Q4Nh^4(d` zK(8I=i}k@i^nVJ(PUV_sECeF@)J|pr_CC70nAKRVW7TfdVh(E}SONUr>8m-bb4~H1 zeqw>>G3TK+1_&&LXoF%Y848_=`G8;2LsXb<3nck z^`R~$VF|M0*K)!Ye>t4Z0&E*QK#@Rv&@urEz*{- zOW&R{;mRhRE?XhewiSpG={sB%Kc;Ma!Jg398I^7=VVIu3;W_hbIapWrvO;(@Ef6ox z+LLy)lppolRF{@^yDrxCie&BMs!A8z+!Y(OR(9F!*7B)nVicHB2)lAc4XYvbvdj^E z|A}OC$Cygu(R?wfeiHt^xlw5yLgPX)W5@LLz*2r-0@sa7RdsiP7`^eiR*79)inx4mxv5k`cNB(RYPhO?pr#}bad{slK!U}hPyH_h?-pQ^TfxwZ7Oz+=9N|2XFuYJSUOV1>G7z}s zV45eE?JW?EPwvt8aJX)7ME+q{3xA2z$CYk_nh6EsQP*7UPSAm+aEW5wDpk&b0`bI- zZO%$xf(hSquUPOvV>a?x>H6q>q(IDA?dq}y2%Ik_ruyDxU2-b1k#m$f|F9l(71r_+_#^{trC!t0&W zjcNq-fut}ERzcr>{bF@D#dDjndCcR`5#60yOBkkk!Ve;`Lm7KFB@!`#rB0{ivO2;_ zow|Zz)fUk4$1f~RA*#+j&w4v|*Nyob!LSsj;fzBdGUn{i_tdYY9F~8~NH^+71j95> z1VF3pmNHy#6(+FMq^1+p(f#jhU-b?Kt2EmS#OFtfT$QqV**AwRk!EE~{u;qB%@bds z-+i%eK$=3}6kpFAHm*mu_VkwshI4}VoKHgKUk#gxv!btx&0pgAnm!7NJ_F(n+V%7@cPe0^4USe(feaSA4ORM^GLVSHS(LU~jD8VF_1 z@MUp$%$q^ zl1p^hi3{~9tu}oVu~b=j)~lS~kTYHf#JjS6^g0r*CZ^Vd6dOo+xapOMX`Z0ZQ?5vRGuR0n z_PUR5t+(p(xsIt=`yY5h+Zd!w3M-c?E8iZrdP0d5YzZcCPAb*8mgn>YD<9t$TZIX1 zA?$u(oTDd_)BH8K2JyIrXJ;za$y9@m-xa4iVJS?XTfIs@8=R}(@qOgfM*sSOqXApU z6K{P+>51_#+PYx^`+;fL6?kx(p6F(|C>0YpUu>aLrvKfmVM4jS^tP$~B%+dQL+t+l z5hZ6Al@Q7~M(~WxJ5zLARmtuBYj{ou`6^N~Zk-a{PwZm5p%rPIMbQ?nm7d`yT*KN7 zZHSz_<~$o_?H~@hnZUGX8?nq|l{|L*OkfS)HelALY&_SWO<>*XH)coYor9A}mD7_< zts*mWYi5dA>U-ucX6o3Ob)K+i4fH9e?V zSJez_xXw#`C#p8wb}RWkb45cq#kJ(lE9&_CG$mz-dA4>mq+lsb8+25!vP6H%5l&Hv zr9i9B-qGtQ$qCl#uX>w&e~OO=tdk4xQmI_x3sH66AccuJ31A`ou2Kbj+2~lXyYK%H z3jMV1e>zHNgH_6Z6fJ>H6ICN39OHQy%9g5NV#hU89^HZ`9sHomz?e7Agnbfn8V-OVivfw&BQ1cXj@ehS2Be_!cG?|khf z%V5#Fx36^HXJv+6)nGmS&@@}y1ZdbD|A(>Q?i`i&1_&kJk`%IMkaVP_~e6L{vsE=~9JhI@8sGB9_85oIpIwSa4oj&7<8t z=!KB>C$YVy$WtqHg{t`?&Ixwe>|rb<)phjfT8d~fx{tK|<0hTI|9lbCu%fE2iI5dH zSyKpBDLM|lDbGGZOT`4%tx}Cq8w;B7?`i!&hyA3!lHG(|x~$Lh|A#2a305LO4JP!c zef$~dzy#KZ>mNqvJI2DujeFfxpaZ8g^yw$%rta2NnYuv4Il-FhswTph?o|62bYKF< z7^dO-E3nGls@`!WcCjTmc5zN{GSDCsA+w+8&VYys7%0{J8?H;L9mK_}LX^ZC+zJ0O z7WURn)VwZb6_(jy{xJ_WI7FF?;tQUOEsP{r?A0g#T zgmXoowTcd$f(hInVR!s*#=@_RMQ(3_z`YE%1X~DSSpX3?O6#h$THKc?I!by5TsN?n z1$gfN^?izB70wHn0?tXL%7Avhb>c!7rJdsxOkjQR#vOXNmYQ4oK2hmKOL|W12lfwk zb?j!QfiYcf=VhrG6Km)bR}a`O=3Lz-&4zxkad3jz@0#IyTXqtZZj;$w`f=7Mc)JTG zdK@BZnINu(#SKVgly`eaUZwRc5+aofgi9{MZmNc}T_(*fsFuvBS!9ptp; zSwl5^VS2TK;x%o*_C%^el%!zdo8=U}?r&Qyz^atDHNfjIx~tJlXG~zJLjNiHoV@c} z={+};m-7E^wjo8;s*T={5`8?;&a9n2u6qC7;e>TyS}DV5@I$Qn2Xw@_|94+oTB@W( zc>;Wpj|Me4e(u-S)G+Wo3i8Uk-B7Ju3sthUyJt02E4oX@F1-)3-+(4AHrKc6%c>+r zkt*riaZW0gQ^O`s%AL`;pY|F>>UsHWZLfI^)sB9?QX1%}=kBP#epDx0>s>z>+PSZJ z6TRny&e>}esge|I3C>BSnwB0ctE?)JMKK3FUm5q5T%S}(yF1%c?Fe(zn66E=^$O-Y94A#^MrS-n(nk}P5n(~>c-q2 zB(=6_qf<#R7#IyK7I_BVG5esFvcEwZ*HQ8Tu9VB#dq zud}|L)z7an4et#ml%p3@hS6D>exBm1{?aZMr*rDMP{fvCpJ3f~?R4S*>mXlDO4Z?% zpd0<9m`aJd56;eNoD;lvJU2ktzbBO5&im|XTD7m#VC62|v(xiMEQM+K&azKa>6kW% z4(fSRhg0l(_K`XkY|_1X@2bW*!M8Z|jOELRhSFzuwtM=`>?LhnHcDqSDNw{xn1*vR z=G2j+Z}g@k=HzBz0!!gofZY~0{UawCeITzFrF!6Kz%)+;3^l~=#hvz=7P0N5$`;vL z>n?jem7a6A<$u@z^`bxP8Hm;`9P|W*d-90XL26|tTXN5tY1dQAfLY(7Zl2IznOPYK zZH_(6_W!$=QKXFEsX=YYaHm&7!vU=@Bc0T!0%!`8y86v03QOmWcQUcWS5 z;vclZvW9kkuD8MSfAdB9uum{=uWHcow5o#!dx)j5Pw;M{zJYl4xRu`X5)V16K;M7Q zGUS;y;)E9eq=vysG`YG3;vD3w{BB}p$NItV zur3wOysv5XAT0&Xyzi70OjdR(&+asNuWt1xm_%-<#_GAfEk&5Y3HGNQ16;-x>nO=f z@uNfs&Iz8}bvLKEHC>&H%J-yLs>Ji_U=>d+8)Z)KOdXNl^P3OFmQ0EXA^Vce*hcwf zDXX%;s#yyy+#i1Mp;$^46-qj6YQ&^6Pf8Kx$C=aiJGZ30|Kvll)Yg$Z?wRzCZF zDWVMM=vqF~Jpeq%Qd_Er6W@FG>}crqQpAFZ=JZ>G3u(i^DlGN!O*l!b?!x+3$t^`B zfmK^Nhq=xLtFY9ddyB~6W@?uIII|S76^Onq%DF890@p1j+N3WgnltTLySU>}=kK7- zr_FV9D+6_o2`p7Z8$k+PJG1WW01z!9uI@*;xzz<7IOTiJ65?;sjZL~1SIVkaGtKE) z$MWuxFMKGLvb(U91Xc23)|qQd5y`{N={m>y=~I6AP%QQAK_rnPd$HyhBT5mPG3NA7 zK&tjlDL*h#`)3rH;Ma$p?K2(x=mef0?HQw8REoe-XZ)6v%4Yr8&lf&Gcug{=$=^S@ zWxeOi3QN^DSxLU+^kXs8S^zO>v^jkdW1fEKs}IE~TjE!doTz@R)5E`>xYXghaL{pk zMQ8UbpaV-)ofb_(fA?Yj+Wn=75UBI8LGjuRrRp3Lz9Tl0iqOv6`(D<;4jbV4=8=C~ z8iMD8A?0tQE-Y=(WgV8nw9<=|{DsNllwD+$%2j^~xW$Ng(srhs{<_M@IO26m&|kxS zl(rR|2plA*1RqWB0XiPQ$5Y|FZ;1ui!uVYK+%}zB|EY&Dw#g#6qO}+-(kk6V+=U3`$5U1ce z#}NakL1m>mlUkAR79fn`xWY6~_=Z)bcKrv+J!{n$A9p)Tnp?lquUIcwl}#3=lwodA zH;b!flg6*g=_4P$@w#}8T-r2AuGqby8cSV&eu{WbHbg#8T-tMblF$^+k0+`Z==%ux<#J?_Q;5%=7mdOb~%hT7JUI)aB2+zyNW&R4m7 zmvzk}?N?ZdXUi#jdB;kAbZ>r+mY`R#8=d+t9? z$Ch9ztPgsg)01dTmkZLNtB)DhflC4FgVp516xt>8th8aTBS)M8KN43Yi;g=oOO@5K zv?=uU{8Lh8IRQR!_)iMg4PUx3Yy7Cm*j#Dz!SW3IfoW_l_z~bo`$n9QzFexrMG5wU z*HLzPD1EW%A9gC{r051w(ri|oXzKh^#8$lmYqL}KibYqSK$KKZ@TV82rbtWtEF?_e zsKhkv<((8t$F8r+JVw@K@sL;W`6$tKWM#GzuKUFVhzDp*HWGAymt)2J6Uyo{(+X2* zK>MB2rVWER9aswMgLijTr&9IF9a5XbArh9tt&1m$!luwSca})cHm;YjC9MncNFQCQ z)~MMl5z}yg{(T~y9$Y8Qn(HBM2GGnw3o|LVNUo-;T7}-7fy{3%kD8_f57wl z`#X!O#THyCz`feyDYWvJHB!x-<(wbbLS9Gkz{&K>=-Co`c~HXnVhb^?QhnPtiAIj{ zl6>qW>DI{$q_a($c6`^0oK@ezT5+b8xYVo>)JLb+<7k?xgA{!B3P)faSU2pB54({z zXv;Bb7>zKFVj-W($e6Ho%_YNI$XcmgLxyQs0Xk+BeU`P3z3Tau z(}DY7Ov5~Jb$@EH**9Zr3sV`VVB$1*?)Db$omV$kdg`WzJNgD=95kjd!ku`Otv&Fp z8LRX=hg5($%EL;nS!2I5#PdP6Hc4y&#OfDT`uW1&+x8kPHQOnNbOmB`vU4fI8FVO5 zAm?3i(Cm78nrwl*s&sJSq%aMA;z)y4-PhW4#663%Bo=fO%HFK&hAeU%a@sUVSy!~9 zvO&k5g)m zc?>ZSRqNVoCOI_NM6D9{o}dN!!504Antsy*K`QTC425>Yi|$O$PqXvcqUWFP*!snwdSm9+MSU< z1yBk-#xm#TGC2x5b{`r6emt`_=+Id^a5|<1LIS4w`jxK6wD18@WyvG0hWI8yJXV2YCWZeaO!zNl+qLyX~Q@ zZWlj2CuJQp%1roEI-GwF+VQLy)6g>%d)_juwFajwPJ{XY+xtwutmAc@Y-F(N-hF$H zz&bDuPn}H-^|5ZLgC<1CAbam;Yp=WdG0(^hVh7Q8>H@6!sG}veP$C)aXFz?#7DuAo z-d;1JAexLmmaVlM7o!U=zkzg3HC$tT@V@qt!K(Yd5G8-oNd?Gv>HEcO)%bMs1M1o1 z&Jy&qb&OijE+3QQUI{3$ z&hvTX5m+Tocq`&~<)gh{H3K1ScHoEu&{k#w-Q{F?hG}@aW_PfT<(_;KCAkt6V!!H-c@<{O9;%k8-l2ahFq^no3LDjKY6mf^tlyST5#BLnPp zpKPd)8rvN-xO{NAWx&&x;}D?-eg%T(y5jz79=y%KeF>&{!mEYBj~T-qG&m)tlSuAB zi<&YpjNzPM))!+S0@Cd@xR1h8n1(NFDjEFn+-%47KDb}OIjK}#R$A$!LY}8nFNio6S>pY0heIuxg3gUV~FUR69zfTQGm<5LBv%3x{z~c`ET~l>lB={-e!oxYfDyq`g)Ux*fO^-|UwxYe+xQ%}gAKIR={EH$=eIp2 zDZ3bzPE@a9hSO77%`xQYFshAng0tew$)Vab(s81f=$E;SRoA4EJQxigr!HfdhOh4T z*wS-z^4P~#Y8j_seb`!+s;k*h8gy-uj+&Zqgr}TFhQD7ZdW9`xST~%Au&ygj{GO`w z?%S9naK2COrIE8iTf`TxN)2WY8b%Lvug-!sc{B} zQe-+(96nKpKebg>PM-F-Nb1iiFCC7bDC2U+p7X@(H%8Pr-%OmFHB=@i zGsug?Gg|xpi?|x(>%+*;hdwz`TMVveA>%s0Qn=LNJeKf_q^bKx&kg1MWNbUO3hM^X z_gGWYeJ3P~;1+VLwdv%h@j=mX^ddGK-Y#qQ?-SFGMX+B!>16PZ9pZUQB}%H-SxfBl z$H>8NbkfDcTGH>(QL$ySOO$oTwM1ibYG71L0WZ5|N!DW&33L z{r1CTGJKUaZT)JtZ^}_JCofC<;|H4RE5F4dC7-H#$Tt703bk<}rG z#lx{mlnhF8qKX@lNqV52e*EZ7_S%r1rc!T=*`i^+mXeHYPz2xrK(uw5~h^zBq3=`N|Xy+Gt(ewMW zB^TRAlHct#662L9R=mHIVb5_K!}p@5J?ZF*=Ox?Ck0qRf30#KIi~eXxE6+J7xlM8A z+6T4@TMKWIL(<8$5p$)JOD4#j4`h%K?OyRir7(u2ct2LHy+j(h?~|%L9U`BakwNUk z4~v-zp&Ws8QmH0BaHCzF%F75OP#=WFd*L_ARt@tZ-t1fVnhzUM+O+Q~I)AMqqTc-Uu z0(*{WIL+frJ!;*njl8=kPr|liOZfh(>Z@~PV1=*Jcvo*3=Y@65S(iqRC7%&B^_4a_ zbHH-q?Yu(TGRt3X@0L#L{yZTrj}B#63e(V+sEf!{4-a|NGGiI{=h&(XPFnKkd8RnA zw$djKdUu)hi~KCD8{9?4`C=(-Ej*3tc%GE)VlTUFYQXt{39JvE;+*|U2Ji1DZ(F~d z8*y;?U~A!yrS3K|pjE7NW#%L~?46dpu*nqz;=)+X_s2={jeJ<@6wZ|byzQGBMP~IG zFZXviF1`PmN>&XK#TxaaxRH$4@gQ;sS&^_)DjPRm#`y}@QpvyrSHyRPi%RKeWE)Ku zR1T1zpM1^=YiY@+G0Ebgu$2stqWs9Y$Y(oo3Z(Lsk!CWs3R{B94c?!RiY4b4*~%9j z9OTOGsU#~sTU_~P3Byvjo?vxp-9w~9<+AdX{O%lqrLa%1J7w?Hq@BuJu2ZKvXBF0g zb;BFpIhD!AkU8?w#1P54e<~Rpk}S3s)^Mf3dp;sBQ=GjqRNn2@Pr!tIrQ@X0^JH<^ zC!U6#3j41Ymd#!u$Ik7->A?A3r>Vr!B30a3T{%4>#aAGaum6!FN8gih3MO!=!~4OS z%Sf+&)#SPX-MF&Cq({Z@h@bZ+jo@RMl_SLy;us< zFe9_OOMZm?7Mi^qC*#>Y_TzG`V7F-kCH*E z!{Yv2rPU6bRGyq*Inu=)lVqHN39K8Q)|zApQAa;ByHVcvB#}d>~Wo=r0lIj;)ScL z*f5tP#KrEA_}gYR_~F~V7aJWND&Ls(S&dUJ57LmFfMa5_QPB+N1a)4cD;qpLRK7LX zUBD@rxa*xvZYCTNhd3xYSm%js!mki{*x{AJ)5SZ9`Neqg+0~7VX*Lo6w_C-LuG<)< zRjNvlJlOjoq4LexQEbDc!NksFia6tljx`7gBfnloiI%q#S=~*&$n?IG#e;T7K*#mB zZfst;P~&%Wx#>9}@cQ%OA zXYF8E3e&Jcy8cM^Ph6ETd$zOBsZzyz*M zc-9x#msQ^xDqD|Oqs|H6Pljag6Hi*jFkJt9oev%|l=Y4em8AjqVP}K?A_MCvKRJOM zSi48u)#)&Jz9oDp+YdS#uTqIv3j4$ps%O2}6lfn=kA|uL!Wf=bGetc8aSa!VJfV#o z$c9IS%9*#mtFcv>=KZj?o5Xgn3YCpkMyhdM*s4+Qj*_OS$>RK~I`E^y_`Yl=__4Ic zYOW39a^rOzSU#FPS{5p6P0p%uUf3$E8_LS&H8bnBK%Ty|oix~QFsb0?C-#CCW%k#H z#Lbv2u4s0Mz3AP8Y^ygx+(VW2VXxgHeTy0(AGrQj!YQv}x)Jv+!^Fb_4zUl{d`b4| z@nY~&288p^qtext9pzuos>nD66Kz}hl67Q&cRV{aEU2__8gk+so7$6}0O6)3ddGm+oaNA8l1f&CAx#%-PFwgRZOR zchA-)9@_{+Pcy?)=df+?gdXX@`BwLj780W1ZC2xhK%6dq&-vsmtWX%4CA41)@8}jJ zF)W2?cotr~<|m@iUh~Pc3~9R+-gC`9#Qd+E6Kbu_);_(sj!kT1LOeHRYvuLI>DjyB zjfwIs{K;o~&4-s=$u20x3IT_hb0a%)D*@gKcV5FjeeOxT4`*w8?o!4m>*6=n8NRJG z-}Y=Ld6%-a4cqZjGhWUjyP=*=ZCB>ItBc>OP0DDkxnjGDq@B*zzEv-0nC6L<@V-{D ziXE}lG>nTT0T;8i)HZ{~2)^VT5WovWtQW-80cybqPAWUD{X#)JCNmY$PLu76xNu(zS5LC1b8H_j@oqw=q4k`4ND z^EIGj;0Hrl**D|;z?NVd_8qKgcuOYywAJ9eu;;i$RH`z?Z?Nhfu;*$J`@s{*#ceRJ zlQS3XxDuMehUB6K z`q@jwnKIj$<+wQV6mq)LZ7UE-mked~=B=G3ux=b# z4Jmy_Zef__iRV+A>2+AhEi~KTZX>;cSQWgPBXCae^{10T$H~uKG&y&-kp@6C*tv-# za89tsS#9vVYLYeQ2c~f;zd9d3`Xrn5~=GuAFjeE##_`XE2(n1ZMD(>OFN84*~UPHPklXg$CwLYgL#uNF) z?;t~K+iS3tRpmtT2fp|C-9Riw$i;o)xuI<|SPIjzLlQ|H_=;c&^mZ_Qv^4lZovbxD z1rxWQ9wTmG;V&O$bY?3JM3TRYW@^AOQX5ikHao#|R>#Qm$JyHF!%i@s*jM}=z}QQ! zoDM97Y3O~5tunWF;K~Y@^uSHK$*0>;y2q6}mOjOVQ(|k5z*1K$?>rbjDJcR;jeb-(_5XV$aP0aKFpX88#NL&g?zRL4)TXm`EDXnsnWt zt(|{anZqqCuJb`ZT5IrJ1QR$X*y(oGe!b^cCdIeIWrgQjxZL3Wyu|ZKyj9qe3T^8W zuU*hS&L~#Jw=vZD)i3<~3R}Vxi;K&uFO0Q#4u@xCc%}wVAd6#nbR!21mcleY>oYT} ztzTvF@=&-Nj)vOf?yGC8%+|Izuz{P&!Y-T7#%PsDymKwp4NGBqz>Qn##xRo&tEtRh zr?j;as^rx6aJ>*Je;Tk=?X*8Uqe(75-;Fq>Rc{E));dP)1>$som5@SX-D{L0u#{8A zMs-S7Bi-z43UOgz6X8McrfG|ELuC>2y1n+X7`J#Y!%~=rzGSwguq-Aby;XjwjHNJb z?Hr?~Vg9;{4;3A+mNpSK<}Yy_2Rd*HCiZ!+RR7a1R(J2cLhSruC3Nqcdt54IRnmkd z>Kj*+bUn-MV?0qWqp1)QdCzUf`A`{4VIAJ}=Bfkia&&ha>;oNBw=@yH3@YzBsFaSK z@k7)@sz1?H>bQ^b#IlKvgm$M7qz}o1rxQpD>&Rc}sm^WjT{nHAq9ZJ`nebLV<^Cln zRK_WoP&t~ZKVK>@p9(d2bmtS#=A@h$b_!CE6i2J7M_3B(4y!WE zp+1hj-0S&T`&akl`96kep4joaiLj^)&1eXoKY8fD?m(T7x{$;&tp|F3obyiSUSmJQ zIjK|!_gV=ybz@!L0fAF+zBng14|2Pe&^vLY_Dd-p?Uyr;A&$3nJ6-m3`rz(vd1K*j zzlt8az;iCI+kMizu1M244&Ki&4SSFsv=TmsMQh%a(xK2j#${_qgHI|%!<}$VE8*L> zwHaQ;I!dH6x5Q^G`npwDe%k(0#Lz`nLRXU^=@oz|+*VHKJRnqO69Tp)g43ruKg~*L z(oUCNyOfT?Ks(*A2_1BvEA}&-lS&nS$4clpZiUAg@S|{VXWhY|N;+K(NFjpPabTO3 zki0rS?JE$f_@TPpJr-s7Z3Y6-JW+0=m5^<+KmBKMS(SKRXf#R}Gb3C3bqjcoa)K40 zYCC!Ky7$L_j}zoV=oubBlsG^yvktB$r`D`8T$?VlP~V5&&-aXm*gfWKC;Kezkv4sb zAm>)!pbk3X!}4$M;0Pn{9qO5tyRmK`}B8H zq^PUDaA(aE5;+>4w?AklTU4{qg={A>wgeM_)efs4+P7yjd+z}q6(j8A=620JYBdvN zobszrqIzLSXVzwALMa`MjP2yZldUr%HwrSg7wf|`?0MGRPA(I-%ze#Z-t(gymZ^`~ z_FP|yY|K93J^F26Kkr^Q;)yek4?V389eVr z?PSx!#oFXCf*iKhS3Pj{0QQq?;A)L0zJrdd$^NP7pu>6v>?!hk0CRgE!x1?}kBwh-q8d(dqyQ1`w0kFu9H=SNzUh5E;l0W1&bz=p+EmWrM5n7vJItc$N#n)qjCfqH#X4LyOS5*8M*#hJc3bx+R_neRD^^9b0=3cU+U_e$5m>6gxsa_~kfa;^Nx83;w->0p z+`EthdoIhkOgyTU)A!mhx3A?&8s-df1?rO@2fAzk0!w8C3}Lr5UD&7G7`B%zW#h|s zWCKHELC3YH1?mn5pSmqBMZBJNgV{-$y0^#Iv$1Wiv5WULI?ug|RWA|>)UCvI8rboj z(=mD874}}cN9Vb9JyUeI9hI2gw2ee?b^13rG3*`x9YlxEdL3>>kt8faA5*$4$Rb43E*vN5ut8o0hKewA* z3io992dv{PgeOJdN58Lolyd>(=7UeMX*HbK!d8YlDDeZ+a0dy*Z+1hYScRhxTY__f z@2~b3s1r=4D?8V71eQ8|`vH5CV#_Z7RZ15Q`cxY?+3CClhzB;e*_{WcbtXCM8P>-W zw{I7yo37TTMwTM5)Ni{ltOJ}2Qem~y&ih@suYUiakK0KgaEj7PC{iP!kHWfP7QUoF z-TZS0Eu1~TS%ry~-S4s8{<7{tf#S!&k%j8hbEl>G0fD7(|G^V;{wYu|TX7Org@wvk z3e(E#xNhCrh=t7D%m&vhCk1b;$$Y9PTfMY^!PH4Htobo z%`}GPujwmIuahGVShtqBY1&KHH|~iMSxSH9>eHO8nP(-h?cGtHb=O_meQdFA#ginq zZGBxScI2G2W7YStZHF65hhL7@t#RH3#E;Gbkw4kUEyCSpoPvp@88xI|KaJ8Xe<*X& zWnJzG%|j>489_M`){&b&RGPIrPFJy^jy1gKCH49-T9;~(3WRmFCd4Xtu)O1Y8Tjt* zKT9yp6My?n6YjqlBx|}?k~_f;X7{!i>QZzE*?_xl(&&9<#LZE=*oKw;r85825TiYm z+3Sn3l}XcvQ)SiH6v^>r8)?;iqu^f8soZS&y>EQS4p@%-vlp~IxU^1N%NTzzaB>n<%0 zWV*HCds%kJ0n*yWM|CsTEAKzb+*<7E0^dx`Kev{3&z&X(Ur*9Ko}0#ARG%*O_?n_Xqq@ zQuZ~8kS#?jw0GxTTZnAg_pK5YA(hgmWUVYoDI|Ng;^wA1=bTU>`}(yeWXZno%X4OK zx9{il{XNff|6pFt=Y2lg+2+j5nWHuN7O`W=xr*9MK41=X*3QMNw-u{DFV3NU1dhm6 zn};kW$B7q)XJENdAIGiTY$mtt-Hd#Ra%XBHtbO+5YvW^9S5!~4w^AK0yF3M-iT>op z0fMat&c&y^f2sRf?n6)?w2*$y!zM`fu~#pm_t%_20!puf>IGg{-ZpYN-e$8SNbRgK@j5(<7yBHavXkl{_{;$W{< zLcoVi1og2x?9wt_EOa^&hs1sao>?Gx;JmiJLiYii5iE(moAIav@>=am&PBCnbU-5W zo02+eCK4z$ zYNQ9wn!i>!Mz4@q9bfhOqONbv$iAb!36%P=+aIU7MhGugR42%J8E^4rCjL5jG5HbH z65H%-FTAO}8Tp0kV%e%?YTM15QN1fh_?6vU;a!Hf)>pIXMPaztN!$+m5m+wN=lx~` zp7Z^HuxgArZ-4WC0gC=vAe$8$NtX0)i*@hr76$qxBV}F}-1q_#wpeXM-)i^3*UU?V z)EVOF-1)u(D&MpMm3F0jt50;om&>jTZb=)Mz83bu9M>k>6$KjYL62|ICy`&L5-eaQ3>`V_;3eBq|lP zZ*GA7*SZP(qZEdwPqCh_jV8HRq4;f)1eOJLK$_zgj zd>D?}5X!VD7}4}_JAA2syl_8GoatM%ley?+>5{nBY+nMUU<;;uP2LLRPsFalTXPmM z{VwboV2{CZ?;lNe+uv3Y|A7_+jsQ@K?GwWqM)EiA zw%+`+=G4Bguh=F;F_C5m<+<20kcW>lR44Vd7SMDT;9Z=z%wvw zFzOul=kZn-ZdE9r?hwM{17;1@eEOWs=I8v(y2UuN{~RXgkbvVZz2~J0;AMU9V_}Ln zGpa!;NYk$sbZ94^a7v%7?K_&laT^kF9!%dD$vVgLM)k-WGKxScn17ad7;GlIKX?pH z{u;q}4!vdjs|&5#ppy7WNGE_DqaXp>Bb_ZZudAMY!~hS>4JWWoz@7-w9Cyri9zSB# zE$p*;785HNA2x$;JDlM!*KAAp1_PLy2%`XNK7BW1fS$Z*4;Qj+PFDi!D2xw`8{NxW zrX!y?W;pp{-k6yoLjsmWpJLq|fqH(nBFVPSr1_RjIJd?u;Z@T_biC{^UVX_%INB*5 z>8;y<*Dm9Qu+ieR^Qwq8XmQ6$UNy*6=;fG+8ot?=db$XOW{KW+w?R9^|3mh^*M~Lo9@KhBIlFey*A-* zgLVsXidhq6W^KY@?bZkz zPOd_bw%T|YCx>kmz8n|d!P?$>7uvh~Iu8Cki@>s=6r}0b3i=I2v3-VtHU!%zit(HwPiM*u70ZiyCW634^6@~ZoN}?G08+M(dbcs zbvwfd;@kQM@}889Uk_2MLziwxyLM;eB2kx4v-MGImW0!pz~ z{mGgu_-qX&Z$=EqQ0iXNT7>RzqrT_CPPeoa`javsStS7I0+ zC~h_*W3LkyPFoRGZTX#Rb zU5kzkP~)rX{0WRGtQp6a(iwSRy0C1lxM~n(?2e+p_9AN3nZQ~N+X`$29Jg`*d?cUP zo_I}gCD2~z2TOS7#-ST@&Bx7eCV|?aRj?J%_4X~-gqzXxNbeDBbYVnU&qtp*==$oZ>P6r+6VL;Mug*HGgqPYTNdJVbwilw z!g>sSqVIp~i$mAQ$uI^qPbZGxPQe<4by z7&98ch_X783umDA=iEryV-u#fLknR`qfef7dLnqXT|lz3c3~J3=q-!_$0e245|;6i zB=AH!f;A3C8upL$Tc&o&$nsHLGB9a0f%ZZ_U_Vd4Iz24}uYB2-eAT53cum##NwW^Z zp}xz|7H5QGof``|qhirMD*^W@DpzlQzk)`0e$TFWZLj+{_}&asJR9M2Bj*UV+!Azl z2*QVM$b?pRqfoss`S`)6p+fSiXi6mh9*MIvx)SeM_Kc43KKVFohK{hM;VN{|FAwX_ z>nZH;6Em3ew^B7 z8+FY|>8xB_5Ns@%)QLx%d*|X4wG~2U#qw%8e!S7a`XP16Hj7c@N27r;O#|8ySXStj!#KEZUqRTl3PIiU z{ir@i(dL|nq~0M9V!G)tp69k!_!bzAppH=GVf^~^9AO20@0MP3>O?3G?R&$2oY)h2 z8)xH?1;5qnmL#J&L$a}Jd7*k^@HW)fDI330+*Ys37oXp~^w1HX{8@nOtoI?oj|nb+ zIa08(3qz9?1b<8HB6RK(#pItpdA4;8Zuh$>Ie)Ytali3tXC~A?8du&I1*E=h1a{B#Ir42gs0O&sg5gC#^J{v{y55TA^FdTQ+Ago%n z7=@fZg)1(Xs~tZtL9ir_`xUF6)f(a6nrHePy96pM=kXuTx20W)7?p}t{H`3 zxv(U9<+b%Ky3xNSs@E`r7#0-crlCL8841A%mV2qr8SHngtzcO*i0X)MKMpUQ@&~!w zhA_n4&&9a4VGDIfE)=mkf>P7*qH6=OP4ryS*rEvE^FEnxyD$<#3n5Kowf+w3{;@f# zm=r16CLRq!VsM(`b8ZTrWvsW zlsdEe91f2@t@<%dB)*5)qj4kWl54Av;|3);*ys2UwP3`yLD)9wE(KplqT<05$ezY} z1fJRT?l4}aY%2tuO+>IHx|iM~x}(jq2YA9ZFA^Ag7`J-1UuecJL644S<0ZQLg;z(z z5bQDNoVtDxdb7ZqsLwhP*yF(d1NJNQ`NWzv_$?D6$)Mp&(LFj>AK<%F{pQ#~6c&+< z3-)HIFS_kPFX!dp1>9lvzNb5>=iN_+qfucK$&kxB1lkMzfIT0*y4$%N-H+}=!Zvhb z`b0=TYv~$5V=uHbAe3yG;f|ptu!m!!yRPB9s*ot1-oe>tZP?X`vJQEAS^AO~ z>P=wQ;26bbuyNC)XzqcA#P$d~8bE^0pz}k5zF)N<7wXHIoI@#g#Cdr^i3W7Oh2MN( ztqSaO1lLpS6M|lZRvXp&EV4rt@e!n1R1p(h=7`&OYe-YP0jv*nYRM zWu`ZQ5#5=36yF=QM~E9(J-VG|pGU){%_g@xp2s>ZmAL$#bl!w$DPk*i~S zF`h$j;p~j#yw8@Qo#(>H!{bdD9k5)(7$yGwYLD6?EQ8jPrZw8&+ou+g!GGg1l!BhK z#KZCe)HmohZWirLU_=w$bMc%>JB3$?i>udNoiC`hVl0U^)h93}FjjEJNxwK%*Z^<- zB_rq)I~Ron>$%f(2W(*mCGP7@E{3u}o`K(@#VSFIL>e%0^1J>z2lRWghkLURw!`)WCQJ213 zN2gu?>VOfUds%FA#NPvkktCr36Dt@WSQ5t#dsqv9oo+@9wHyJ=ILS@9bgx z0u2n(BfZ1N5!gFJ9jxbPr%l4?27YAo*_{}c3-iJ1NZD`(RgAiXmmg>Sh@Y5;S9)#{ z43>rZ@x3D8_WNbpb5B6vB0WD##)js}k#5WfWBdrfLATYNu=P$mfaH}?rgcrW6 zspn5UdSlNaJ;@Y%8v@Tjg4NMtWDFkBbv~IeW-`uybPON37p#7@dk2E~XFYFFV+=;k z{D@`RZVcm7I!1-t<{wpC(I=f)V!M1Eo^fO%nOExtLohx8n(psomVvb~)Mh#pE9h;z=PG=$Nt`-*gm_oKMpOcJ>E}rn(pNyB6ts#Z zULJakOvYe5`MocJ-ok5jwq9M9>Em@@bjbrej=(dJfOU*sN4?sH7kks)PBum3NBVg< z&~&8wt63(3`Dd-_Gq43zY0KmTMjDnxznpdE4LaN~8#^zbOJIE9>K7ZUEvK8}AA>*P2d~)mD@ed7 z(6_dB60F`eomhu%z}*s#;~QCq>f56;5R3xrxv6O$8hLUzR=*EmtU70p@a#|VLWBFk z2`P(N`^LaYwk_Iq&D2{-a^lOBNtj1QzaZXNH6 zTNgGW!`z23YkkmLxKc>>-+i$SuUj~XepsRwvG!8q!@mxwkJIN`V7X8qo%LPViktRx zB!hmpA@B^$AS{XF_AC+bvQ{(5le{D*y3pHCZ}Rb!bR)Gz7x4*GRi9J1K$q^FXnqGn zDQFc-6y_!1t6l6#rn1 zt={D)a`R5bO8W%_dJ9(s+1md3Svy?+(S2;wekQX{4G9#w@9PP6k+2Yp$MSYob6A#QBZh77>g3;}Bfr0Jeczx;97j<>j^?*wMO9p(eB zi_`DikFALljHB_;rHcrRC|ogT>+aH|4md6>2ZwL(LohdNbc35Hae3P|WJ42MrnbX-1+3?1guU2oUoCPZcOZdMFjj0$ytgh6 z$DO*0^*pCCv4Xb4I}jY_JXW7PS<;)dx=@5u8zJ0rm9J`MUplG!nxNZr~Tfl}Y{ z5RUwNUG>#-BVvhX_GP$5QwtK;$%G+bL|^V9cvxBubzZ)>m+;+b7baJu1C=FSf!;Jp|6-M)Wnk_+Fu5sQMF z1bPdjurC+m0`mmbkYMq>yZW_X;U=gpaa~T|od9hc+RhTUt)8OBd?0@OE{MRaJyaFq zxIV*$fk&!maL{-qUNET?*OZN7Y9h4#`jZ0sMeynByBEc~edCUv#@pXCAYKbx2s{I= zf{~_A-7l$$56^eR4KfxJXbHTV#nvl}1=iTgEE)Ga6F}e@NU-_n*8C|V?$`LDhBXZzCX9CL_ajpQj zf0(73dvFzky6KZ=mXC4ICckmbsR{z6APr+kpQoOG9X+V+iho^XV-;Lcg!eV>CFF+& zAs7YvE?IaX4*GN%;|8Oce83DAT{(eEM|4md)fY3E+4CmOU(b=pLT|<@XbDTSd0rde zJgtWt1cni43A}g5T9rNdFix?%jyK#IOW-|0ST3}X?%4an0gp%x#82D z(P!|u-%4C7bUdSD@wAh8Oxs`izoTOj)JNY}>r;jopZtdHw)ZAb3g(6-JbN5LJ^>B! z<%lJW=W}is5n~uEdBLy-P9!n+79oy!bsEc zqnAB)&vnEfcLo!92HqKE{TTY<6Xt54$0tV(B*yf5=aBvh6&W3ipzY8ndR4UcG%jzp z9j{(DnehYK4ojlX`?TMJJ0G5dUo2+tJ3~v@yRW{gyC}wVFxq1qL7=yJuj#tOz~AbV z`xY^Gd+AqVQZ8XT|5W^@*<{8KXccpJnQNU`ieJ_X!0%J1khcAb@PfN%R3}G7A!s{G zv^7b=`28$=JIJ58Qw?p0CDC{F4eueoUpq8oL*O?)Afa=*I~|w0m>}ftENrmtc?YYt(O=EMo3+ z(>X(8AU4WLMK-sCnY-bzTxcO3&y!2hvzblMUg|k47v2qLi5iXVRN`)kHZ9B@Pwd7x z@=cLytI2rOOaB~RbGu0Ol-^~3p>q*?TAfvmOZO1R+RB}c-rlxSe!iW9^FI}-g3S6N zNQ=kYUTOYL?`>D^x3nDMAv@|GzK&2eiwy|EMb5E3ff9jjZS`>aT{VEV#p zR*jUq*o%HN9@kI>324;>-4aYHic|%H_;kYh%Ds?`#&uIdsYcFc@t7AysL~qoCX`D0R)p)lE>gYojzBDtdrG6D*ush-5^oh^ zLz@3nEu#^n>6^v$OPFGGZ`ILcP@6SKK;1Nhm0!r~-=v#z+qqM?)!QN!-y;S=0_LCA z-C-IX<8XJWmS}a%tT>6ecSWkOPRkH1i9Q2aQ$y_YwPc95O;6&7l&G*>jv!5U9r~^D zJRp(v!`$HnzVe>xh+c^xP2bn9+|SaV?gI&>pzSUvQ}8o=y7S-0*)$(I^!tNi-EFYV zN~t%p0AKr1qAk7ltx*E@0>sl!%t-<&Q zZG-hp)+0!>#E(`QBFn0~5}vUrM402A8F8Xb-44zc~$uf;JY#j3f6mk^{`VmsZb zP>gQ=RBMK4HgyYbY*?%s^zkY~)B89vf26wmsgtg% zR-LhT%=<$Lx&4FVP-@wk19)3`k*c)&4<-uqz0@|Q()jUUHO_-Ef#pJ)&Z&nuNyO0n zh`i|Whj7G}B2~vBUzl=X)ag6!n`5PXY)_7MganK<)JNB;E5E6?_nnop);v#qsa>(E ziD4L;;M*Q2$m!SprtL?tzR{;YJ8Ej;keO^vJfgD*8(7h{ee*Fgn7ITGu%zFwl|Q4= ztzWtKr|)Z)fb|vXruPS}G`k48Kbv9;ZHKiT)=E0R>c3Q~yUvB2RNEh$7OO@*eb3nL zoV^Bb=~%34(CQtv>OtjLd&I_C3C}=pm(tbmkDZEDmYv^HLi>f)Yra-Wcm@)G^q1p; z&h)FwOI}mLw6foom9lNHmt!pEE$FVvXI~VDjBz%~4^xcr>t6IbllONbC_@bQuwTzwHD_!S+@eph%4&Khf+f+f@P%oJ zi7RcCPzshia8i9dv~RKMos0Oq&!4v%KZLmM%FVqDa7sV=4anhJ5tL&0elEMn3sDKK(yX{>&_H45yZO?wPV3B@X3&PG$?v;cnE&fCuZ|=tlA7niwsmQZ|Lh%(R>3HM2cp+rnoc}=_ z!jpti+Z2+N))KKKEiINDMZ|x_Uv)p$o3#@%iJL@geG=uOh`K`~I)-QnDD}nDMCdb0 zb8Wy9Hij*$VzsG96XD%#dqLEvQg#U!z0(SNw@*#u*0*88MyJ z;<4_lF~XU-HKgPEs$qhGaw7d^adkhSB@2|r>TmakNq%UrUj9o!DM$}_q$8Z^JEStY zYxgwF6Is!cqVX}psO~EzKPH{tAgrl~maNLHHCr&9KEKkcv*t&uVx`qC(okPmP@+0> z(TGYNUl%9PYpMV0Fv{B@n1=0_bZGU7a%=|EY8a^Vk~|o1MSZM}MJ*auS!JzG6h7pn zNq+3VoFf=qyDRC?>Z8v(|D|8k>EEu(bC@;#cw1q`=7AEe&CP$Ux_bc&j`BMH(V^A- zUjq8kjm~{;(yL!7|CQID|0T4U5~W}UwKY^jO#Rt`&So^xg>3@16>V$&uMS9P+nuQI z|K6gYRM*=X!Y{#7@BYT2huF@$RfGQD(xAuT<_WUg@MZ)BwAaN#wzh&@mF2y z!R|6)=#y^$A3|G}NJFAH=%Fy9d*@0&G#WHIAfc5K>9W5&1j`TuN{B5A5{y*fL*dic z?NVF$mk{&u`(;X%=izlSgf3SLC8>5buL+IL4U&$pOiUGGj~@OXed5kbcLbCD3neK? z_s@DD+ff~2bh~eBS5>c|)H1^<>h#kl68$exy%&X2kdB;qH-F%?mj5GG zOK%jZk~~^US{Jy{f()maCN#2`w%997R44xmGoDLIOrXJECel zZ?WNhRV{%%wN^^hq3yLbIvy8=RuS4h97>7D>{#1&TVYjn;pnWD5(#!3Z2f7dqo_?h zqf4LIc~>x88f75O5~8&D6AA5jSDj`F&lyQovC@uSA^}J0e@7g#mfXu~T4j~?j7Y$m zsI8%*E$mpUZ8;*LZ4=^gS!E0UZ~K5!hx_jkvKrlzYRtccsN=C$MO8kuXT)+Lfots) zvObspkD91GBUw_}b zyo2i4R(XA%a<8`XUa>DWs!gvNEV{dt`T1fQJ??e6i_13?U+hbd-=(#5p;s)G-{1*J z>mjXjYIVSJ#p8ighp3x=Ype2m6M7S@m3QW+;kMt3RJUSQGL}FK#hnl|^Y)>E*2;)S zDfk0jTk7?>p|E1=UfhtbG~asQ;xd{n#qYUdRg38E)T+nUZKNxf6z|^3sPZ{DgW79j zQNsoL#QHJ2(hsuElJOkUtPamgtGJ`xl+cn1)DqjjMXGV=XEm#yR9;8Te%y`mLyW@6 z&;Rv_?rXs-meTR=b;9DdCxNTCdc!k9s!?B#IyNlc7XuVQb=Ho@GB}2fP2x;m^ z?EVsmR~zgU8a?Vp{RlbPNakzx*m>;lNX6l4%$y6EcOMB(b@EbNhPE8Ou}D@4ZS z;c$9fXTCU|JNq8zcl5a7bo)bu0($s_)~gd#YEtM*VZTQjRWHOQan_=aDHl_nXMMfk^pUOuh(ruMv(`94fHX_Q z7j=`h8RF&g;%B4++6$$iKDttrxJ!Lir@*BywF;gIzLAL!delY{M-!MR&>d+0RtSoR z9fY3`BNb2zdJf}8-?bF1P}BP%`9lj?0>%f@bXOI}wPp zIrU~G;ptTBUYn?D8N4u8g$#YVxJ>^Rp@3yU9gwCu?@|jt7!&IfRT9qVa5h?t72g}9 zUz7Y8eblP6E%8p1e(K!~!WA_ZCEy9vl2@H(GE$JHyLi;asbuw$WlNoWwDQWgi|M5;SGe+wO>rsd8dZUJR3^S#f@lWqlKvz)ppDkj4PN_i?4 z;mMH=kmrmTN_^-RL|jgs&2O=AjT}mi=^cmzw%0_@pWbj;r5A`>E&nShJ>F5m=~OT= z_ED>oFGR_k9A1dysrFySO=OTRzqJr&e*Pe22iBC)cV&7lA^IvWXOj#oc~tg7y!g>S z!rsPTg%y#I5Rq6xh!!qEQHLOW-64L1j(Tkw2Jj( zbml@b&VQ3fOWW!RqiiyB~jYzwWZR^L(ZaLK=>6v<*gVz@GhfsvmV+ z#OQ!yA4{w)S%K?D)sUqe4pPA00FI)NX6Nl<-JMTs`>L@`Wa4pJn}38Aa?Nq*!BfIg z>!!5sJ~1pkD$VwFE*~{*kML4TOq*^j+zc$n(e&70W{~>M*vjJ;9cf?EV7ix5Bo-Zi zV+%(zNbCO6jE^R*#F5kGp}Rzg_CYC;7DrLPmW>&GH0O_oO2nhuHCP$af(+H8B1&k z>L3wA=Q-xWGvi)p=v$vQyTFp@{A#a;5TomnvPde|al`}{NWhZl*90Rp#D{_xc94Kl zY;=eBHJ7XsbwDZTIZGH{9wiZrXWX-cS%XB@h)~JeGYguj>HATCMoWa%dzV}&H8fK* zUR^JXQnN&={RoLznH_HniH;_bQn{DuZrPBg?`^yHukr&*LE7P2ltkMY-l0}?Yv~{n zHcyw@!84HX+rCsHTKI`$Eg%0$B4*w5%k7yRD~-a_+87H^3evQetWJ>Hpw+xac94Kl zPb+801r_29nYKS^=X&wTud=1yniQlKk5`rM7CPp}NXKFe7LVy0xz{5V3!7#fpS!FX z58Lx}O34507EDo$I&5As9(o{02r1h|iQ|;0`^wyzztD__Qjpf_*627wiGkUvd6th^ z9kASge2VedjY!B#y+(DcqJ&+>CRNRjhWwf-#n^+K6D(WR7oZN7NT-D8wRJ5+#*gas z(|Xqg1F64ye6g9daw$*}mMb1>rP|S+FIj$HaHKsS-J9xsGgPxSvd7g3C3-J9o3OpNgVjqj3J=Zuga^85-YJ6eM|}e@rUyU ztZv3bsjP+w+irR(Bt0J|u!M>dFN~GJ!CC2yU730SEOwS{BsNit1|+r}?{BKd4QW1eAg_Yt@I>k&2pezIjIO1u}yL z`}kqAEYYjT;j#%oviOTH98p1Oy0CuMKK}H@&S=@9Db$Z|l$enF$El@h0VAcCxR3X; zwMB<+S;(3e?BfG3IU>`ND=u{BVM-iIPgb2CTp)u|P{-VeeSAkx8)W%TL3OO4M7u9P zj#tb+$q<*e?&Alnw?|7$n^n^>ixTI!1^H3GPRgKEy94`ppJxuJSx?<+#9K-<-+m?U z$xY5RomT0sPI3r5~C~T>Y=}g9>Eu3?#aY+sCIZZiO6PEvO`N&O7AIr8)w}?BiQgOA>o6l0hj* z(>=*$1;XHE3v)kFU0>SIm(O_F2if+I6n@a-PLwvM$D21zmoLibhbAN}6*#W>zye`p z>&Nz@bx`U}`A~V6Pp-(Paa=VbkP`PV={ktHheX~_JNX*-{>YiE5+F@?eD7NzbbUMS zm>6Y9sI5)qdG4;r{+|Q^(sZWZuRz!ysBBr4$n9y`jKo@!k<4XLxmqw1t`TvcerbTkc76`SN8)- zL7F~cN(r%+h&rH@czmC>L9t#z-BKGQGwZlIwK6YYvbJ?xfZU@|8??D7URE+9K;DsN zv(ArXnN+XHz^MIs$ut5`3VNPCGe92aWQNAhh@b@bCXyVw7wWX`3t@EF_yx%K#dk$} z+-AvG;^yl}QrGXF<6UpFRwXS8kk9tFLD!T+Wsv4LL#kui%mYq!mk|L+`l*7Rd6ahRMgpD$sTRFySdZ7Whig79Odd<0SxToh1JW$fhFUe!&QP+d#>!-QXR$6( z?NExfO6)Aq^jvfi%r&TAC0Ig)t{N_B3rN^U?S z9oXSaHR9sNC~<}?^(Rp3=d~3Q(ec)^YQ&Aq!4fh5s$dVL5_>O~2)}N6GS>52U))J? z{Q#$=8ODk_K1<~{`|6`n!xzh*b&rvs{?G*3#l_1eJ&KW!8K{r;^-8C;-Qll0d9|Ug zgWDKm#Vksk+Rz#~Ok)XH(!UujH@m8A79Jt#Aj>jkP--&OA?hCND(VRIG$xat#vD)o zL)XAB~L|$f?*YUGE z`Bj`Kzh-KQgzNEYSo8nTHkiDlJ*p?Q!G*Jo$+%&%ycr+d$>fP^wKdzAq<354sPo>PK->G2E|;f&b{F2&eC^V>bcMXEnz^_>>h+yMMEU$CFUG$#mvBrd{*y;NUrjxCUajM_hI$Tlz_^7T z3YR}Vr-K?y+(QZT8OCIE+)Br>G?S1RbR$gO+Tyve(D#VUba0q_>AE|@yWP2zI8Jrc zBWoS!RMP>=^`g5>I@MNkH?QjL9yewoVtmu~xxy^*oo!Z@8Kxog3XL(Px@5X=FOq;pA7A z@H-tN|7+6$Dd&%qHKnbd-JE&eF zY^8)h)$vp}*|D7JfGuaaDpCI6QET;?*Q?a9rE%OMO7xjm*Rix3F)B7u-e`osy559n zHKgg+ZoG|21^VIWTa7U9m?%%N-=lWSpQ45|$E8xD&m3DP-D<>|{R#5k>Z|IEwC-w1 z(_PF*8G{^m>eTi3AR^H-w?gaKY zkbt`BF3nSo$)!gp9VgJbJM8dk`O0(~!RG8OXV`bKL=+{uK0N3+iV`{ntK{yyOfY@v z>H=w&XhGXxmkIZC%V`^g?GDl`(V5nE*F*dACebzsiQ+>m<MfH8Hta8quIDU+1T2ZR4{Fti)rrT%F$%UpNV7yF)#2yV z_qdo3CLr(I`D3Vt=BH?HQI%HzsF>zE)kOM10pM zd5@P5)$a2)$shqs;<#iw4&F3==HN=lK}bL;wl66iZ%kJ98kV>67i(3}(Qx_4E6?){ zWqV|>C!$}$@G&NTVlLVZp(7_Ow?rK(w@9b&`P4WrYp^U_-tW%`)!h+$X@Av*j^`y6 zJyl!icn;4%9k3*h8&X&EWR2?y`nHorZ@I9lST*_4ZfOlsyY83$#7@pFFIFYp$)Y;u zx@m~uG1f|W2CfK-$8%$}Li8D<4CBy9nF6~hvPI>eJhC>jk_vgxsYaw3x*mU z|8$Wlo2&|#U)WNtI?;14Q|_SGvGSwaHGk*0k`J19WnO&js)S`ht5{+qr_pi$9%~hh z8?;ayYoZi~A9a?VPjscVVaR|6D5*iFOgw(}s0C{KWwUhL(Eg@iVJ*(#M8c!{?p&*e zTWn!&MM5R-j$Ypnl!z`D9g)#7v0jOU_^-{eQ?{bi_y(3}3yP7Xv;-_kL)_5sbnNuT zClYZk+zdsuT_X`%`oBbvnaic8SVbKd^mS2&&2EW+K2?N$5H7XQ`XOo(eSK_MxVAM4I%!!H`Li465_Ee!W11}utBQ% zTKZpNc9Xgiq4m7F4lS)AZgo$|&3;v$E0zlhZQF*lhS-{*N8hof*9nw>Qbn{U>O*@X zmbke5R?p7h-h}r42W<1OB>Jq{wbMO(zqXX_W@ztCi1$2JgxkqSUU00sdlKm6i2jj! zAJLkgG2JCXELW=omMi)2Jsg~pbkhwee|1Q!xDRRm{ug+hlEnFT$X64 zw@vDOL@hcOx5&-uENt)POaacRZd}m(U7Ve9+|RPh67j^!!`3Y~5w)O%O+~rO=m81H zm>%zR%NOF??Lz3iA;&UWhYP_J6$ZQ z2w3i$sATEh#J7^IRkT<)m$$J`3 zmi~TcB?n;+IdW|4C%aW=c}E zCq0!l_P;C9PI2XwKql>~2v`=>5$HNyqOJ8mQ6hVeSru_FxpN1r4rFHXRKq$wNH{%R-P3@%$I4R>zLe)>d^c&wIt=aD=*rf z_<<54huT|TIS z-ohxrk~nVn7#GR&A2X7V!I;44LYnpb+);Nay65KT@izU3OUI3a^!SO_4@k!*om&IX z_on(CgHmT#?O%|pC${Feo|4)@LW@Q`Bw$J6H@$0A)e?Bd<7N3Tvd^TjsktJ8s>_NA@V?##{F@Gyq-xg~c^J6BD4eGHZh^}&|LaSB7tQ(>_^ zm3Ht9B-s9HvbnWnRfBmUj!--74Mz5Gll&NZtS0q?j~yrxHU6I^pTE7CD-6#KSuBT+}F&;#C&9XXnM{yHV>Gd z6Y8eBUj)l@wK<16lKcdjn457|%Veqdcu8OE>u4s-yK7FQ1M2BJLDPfe;RU($G>8aXEPD@1ZhdHt??KNY@f$&1v^tR(AB0C0C;&Ttf zDjkr}y>~&PeLYnS&2bky7)eC;<#7%TGEPWR7iS!lL7LUE!&t9MM@acTiKu6}UG}M+ zQab*-cbDu>*=WhCFU!@`s!g#CB%=Inssof-Y^#n(h&QsphnAblpgEUL%+%}eCH8-Ke4%SgvcenhxBSm46 z_XU~{%`b}VN;S2II(F{#lJq4VSkLIAD@9Qn9cSO^tDp{8?p!a;+~@Gv8&rpIM$@7` zmDhEEXCM*!K{NOHvF9o!+B|zBjRq!MnM0w%TCyb2CqV|SN^+= zT3&i8NI?s{j7=Bp>`xW|pOs-O@SGfmG9P&E4NPhgyy(tUrU6&W>lDCg!;Y~EX z&%H1)9~*Q-C1QW16Jr&$q{Y?g(tKs{;pLRb15e7XUOrIL(N|nhZ7y zk2uzG?mekC+^>0C276SPC;FUaT8^P?S%6|@RkOUFT*Q&MzAZ7_uL;!{!g7-JQ*_FrPP|M;Gefc1*4yN^EXvekMHr6A4L#5aFWiPwYVzyMo& zD3x-{To7l=)?;F1EHU)pzgI;UPtTJ4DD%#iK?0UUOMkhes;9o#bAd#}WZ#v^gXT%c z@B7}9y|>$oT2pqbVOF?ry$>&5h&wq41E9qE-HXeh1Y_1h5(ZjwUlfjbyttH|S zv}$t6dJXYxz6@GOdr{A8RdpAZ3-#H53YO^e7jvlRwIg3v5p~=&5#99RpbSbu`d_O) zHf~}MErAvm_t4aZ#XH34#;H10)e@)!mdg^c+as&2f>KZ)OLTPAmGWU%U(bHsiO*7v zbN?GJg9I#zz76=oThj5|cJ(nxc==zI=$#eb4E?X?;*rsU7m}3zfSEE#z>+xbEV)_b z2Rvg{r#3dBZQ{FnjtrJWcjoT+NvgY|j`~A>N;+ z?7$3~56w^0w?nCmgX&09mmbcL{g=>=wNMJurlaaf^yop;sg7lQf#i7y{c}uhFCM3< z?XF`k$@0HxYT})6ab8k!`hSm6a2$l=bI}uRbYWRgN9j6EPqekW9=M`E5N2p!>aOW=%sao8LHd6aqAo@X(6HC$xailZ zRdpBYfPS#Vh;F2cfO&?5*(Qy(FAUDmSdD$8sU@OSu;+wQkfyWO!H1;`_N+5d1?O-b z!ZaD&pLd^`&vD#rn}6#StUqv0#m;vRx6Q5c1J2dps1N799Je?@vkqrJXr~fhXTTXb zye^?vkUsyeS;937xaI&?Lg-Vha=of{4%af^3Ibf8qch9aU#j{NxTXiCAT4G={AqfI zKesb9?ZCJ_vqtj2*Oo*M>VW0KlIT9ER+{zQKX*80Edvs8eTKd_F}6=tKH!Q6T#bOM z6!h7s*nL$5Y(;R*0n(!N;;(YP3)&i_S;D}>QObwmK0gPzW&sJdFKIOOkVN?F7Tdz! z$IDAocOO13m%*NhKI@!wuqx-UhC>3DMBmkq@w65F7}R{63Z8+MKnv+TVc{-cW4o6; z=S#3c*wh#Y$Cn9vI>n*v=?(G1r8k6w{g_h+W3U-b0OoM_;vXcmbv_$9?|logFy@dbwHZF+qZNlza!}j z|8hvUV*R|v*iCj;*gJ!@q@}VE)-R=xXpa`HDmdxK*K6}2fAsoDg>uk*Tw#$Y6!r^Y zY!BTKj4N8uooTYgud)|EIKeOVe%dojziFP)~bZ3*}P%LL5h;t zR*I&&r_m|;rgy#Du_#mC7hfOuQ5dvfJ}P+WfLHFWfwE)$sg47D4j-FZS5Xl#TH%%b z4H-7oL-%4S;T?c&y^yf?<9yWXYZx9d{ERRqX*MM$&za7*NRL!J-nPnRX`wxS@w_%_ z5;g{nH~NGwEjL1$o^4U?-wZTqv?0P~eCsWkJUJ&#s zu_oLI33pBjd%EpFLrhIk;ig#v?Gsxa;CE!6lJ`mRC9|)dK)TmH3(1F?$u`|eM8`(e zM)bJ^*)p?FXnx6O!S?Y3dPnj5ggoA?mw{q%)K~(g{tPt49a29F<$YsZSfahPivQbc zn4)!FGh%yRffJ_x74kxC)t=M4;?-Up;ua|#qfK|Bj_Zt2Gn_|t*azhE8}sZGi!Ssa zWz)K1=c3QT+63%eqa+b6FKvVlRMeM2ntn0;YaYMpdoM-CRx<+6454>PV-FaiSB6hq zSRG3gxA^Vr`Y1}wI}!mo`d*2D%yD~>ev&7}JQ~WE-{)()gri@ik2c+qB=Fk)TNu^xztdRv{)j%D4+~F;~ z+bX}{2>qk0&gbIz%)kgm&O!QBbF*~ZrTY!x-s??5(&H#>d-zzh(p3-I+-|kg}qUMBH1kXTX$f0z+t=kPDw&^xX{Ma1L&-98^H2HR0fM+0a<9a$i z+3|*87QKTK`;r6rIdyBgWqY3iJrZ~y?{4y@2g4L6s3mTtX2N=-$xOcsY5K*&AzS!P z+!}d{MT-~$PhE{K)<_k`T=!*YjvHLQn*W^ELOx>U5{7`~!YI%;c(2MeixJ@+gUtkOo)4F1YL%pb_Q zDOXILrGVu^DON{LpM$)IB3I7MpUV(1Zjh#Xh3(zVhh9?4fARi|AFy0FN^snSQ;+zq zCruPFUIUrF{q(qx$o`uSYGxdVSYlYeqx_D-MvB?*M=&D})B#5cdjBIhk3W;8uV`30 zRsp4;?d?83&>5a7?7nI*-le-wm};2nXZ} zXfKq4H0^h{6!2^H9TY7mb!P}zW1a`D!t1+V64JxQQL8>1pW$=d-4tWGnlM&D&siNa znjn5`XD3BcPiqCV1X{@IhzwHksju7>A99TpaHNMcOI%)F#5WFeQ*8d#N&(M6KW@|7 zK4IW~;mcW``mw`!KR?26l%jRt`ivh?AIuZI$8t57pYU{oBE49L(XoE=8eIGMZDCN& zAxt*uGZTY$@)fPT6gs(O@``^l(Cw+M(Wx;}2$sv{eA=u7e1~9f#gij<Q1udjI zQ{)JIpFtB8_jl+rRzYuJNp#ntCHeg8L?6Y*vdeNPb%)01ZKHfaKB^mHiEwo`Z*p|5 z;_CjRj8%}h&Bxdk^BPqA9NN|KXS1%obNyyT1(#KvCJHIY9} zuRj8Ow&g=9c+J5Qd-}!j(|SiLoGZ)`)DEp;XO?=C;`!9Kixt~`j=;@n)*OfEA%oMo z>g@(Q(XWLjD8+i73$&KjlGu%W|8>EN)yl;fN4Ups%41NHifzwb&^M>Y@n?H&D-o#>jq{~%ipF0&D) zbW`r^|0dhrcDMQS_p&4tmT8LJN~i{g`Lp{B<~xcI+TZ<5DvBntQrh3y?2VzW4!P_+ zs6{lsSnxX&^dH3Uy8b^jgi|+u=jr{=FMRK*?*0EDet-E3u{)BTKmQkDc4BR>|6i;A zwB%1sz5lmW+S1y8f4*p2rTvZj@xL7TU6THC)ZWXew59&k+j&(l#h~SXz199UVm$nh z#-Khmd)o_6zY+M$A9~tSxF#)$|9U>Wc}QQ3z%;rt8ub{Bh21^>X9Tsl4u+w9wO`(_ zw`+ua4-uEbXhCSxeVZ~Ou#G%o*aDUD>Yvbp)fK!qR&2WNCyf7P07fHYMfd(+Kx^3u zXrQ&~uWvs=IULfXWX7Wq75;(|OP>FPHGS&C=Gw6gF=4frvTx?n{t*VDs`KLnML1~) za?nz)-hX3$f&H+C;2W)t2He`%Te;FLvd=PI9)Cbm1+S#6x4qui|70q9<(j3Z%-(4XkK1a!qdROGtqhQ^ zl*ltfRrt%nM*50(VOyvZ=+Cu~Wh0s1MX^}1OtWcuxN5swT}4>l4r+%^=1O5S^Jr}B zr5u>}vHvE+P!;Ao9!-7(cSboYxjP5-KXX4+6}j2#KMPj-?;@5MjAqf9&d$nJ*U#4B zk3v@Ea#fneBXCXZ)wi1U(_fA+;~^(VU5iR0&n7zkOBKUFj@MQAbIgSt;jX-K5R7^MC)nr`nt$ z1~@e$=e!Tt8cd5&;ZhiVCoWs+%Fw!>+cHGxM{9CyUYaHa!Z;c;#uogp*QB1Y#3L$u zhm-D2Lv44o4pz-QC`+cSu5ATPxKbF+@@!|NlF;*eH06T>Rja=o{e45_U$U!9c97!9wtbvOjBiS65+pOPG#Rho)TJ}T?WmA^ewJ~#R)Vl6B4h<;%{B)A4>CsD)IipeGDM%QBYhu!F)=~BEvW~Wia|Uq;Tq@tbO6taH8Y(&^&L0?A~IaZOJ>e3fJp9^PJd$wf$9NO9@M;AmmO@hC?B7nv@AF zk`9$}vg!0&j{RDi{)K2AyBA3B@wTRVEKeLNh0%h^OWXF0UgY{NOcD=y>np8p)GPg- z6QL?zKUQwbzL>RZEnzf|uzq5oY$!fc>bjOkL^;ftwcZ;ojau<&L5l9D>@5kluFuXO zmFAjP;C}V=(+wI->K;btGB;b7B^-Mcei^4OC!2N z*Ihp1=DU?Jc}y>8p6JKMJos0>c+N4dbnF{7#a~_+17tnu2hCT_5OGZ`Z`9Lm;>jpl z8u3<5J1)8?2kdYLCnZX3es1{h@o;m969=U9fPi6+khnIC(eTyVEyh3bu(|$PP4DRR zwcQiv23@zsaERc`=Io895wLpr5{B@ee@$F!zSySu6E(&429p(HN}bX0XlA^)VZtZT z`=>kf?WtWkbN+oPt{mG>bLXC#z8-7yd;TDuk~tbY;)MP$F*M^|i4DsoG{)FUG6PS5 zMJq&%<`Kpgouy%Uhitx_;AvoV#~lHZY57>N(Mw~kYB8j*l+ngrQ>rjtp)X~dVt=>r zY+O1=PY^~#%$MG4Vr&DJ^N4G1>5_LFwmM|46ET`u0jg3Y^TR#BVqw&Ad7W(#(rkt6n{wM!p)&)f^bYBXFq?F6V#qYFVRFhVV{LCg+!Qw!K~w zNbwhpxMgxd(u?&3(MiJ)vv=hY@9O3@c^32Om5G&7PuU$xo>CE`c|^OwQZhUtRr77e z9F7J?m-=4+-Kz4zTJMC=gNMmeTmRCk@>z6_*Hy`V`Y4FMa74tVFq*x0XM3G=K0eUa z=e$4N<8WP?GSv;X&pyr}a7`@l$7usqWcmc#y#XE+*Nf3teXFF63tix<*D2Pj@mG4N zPIcO-nclHKEq!+5cYC|kxyaFYHQ`Ur1rI#*>eYlDrGUXg;oymG9TEQSq&@IhBZ z+*;--J2zbQ{bH`>tEHKOOF7Q1{@tg6wzvL5EOZZ7*;wRj9%q;ia?y4rwY*>%>BOwWZXv$1+|;oD8h&OOz?_a8o& zuX8kb#CJ1qRlBHlwkJ2%RAEFHtN(T{O6gM$EeLmxj8L7Qf3n2uwUG*!I%)Rb?xpee zzY(2vsJP!<-?k3RMTgf9y!zm^gx%a7+Aj8N+q%@~uT>4NOSmR>XQ|#HcG;xU|1(=T z@fT@w%yj@flGY_r+SS=< zIUKyN0=vr#M2x^SF|V-2yTox3iN){PT8qDwT-^#A97Xu}agK; zzn9HR$D7o*`NllfF#?xr;v^{lzU&Gst+ifygXXo?LufUiCYI$003^uO)LdB*)Vxks)xYiedUn?Q!j)^wAWN zM-)l}rJs>58p{J}ic4YiG)v>?GPqv0{8$xh+pzm8CA@yN>|0Cg2LRI&A=SHub+;L6mDLPSrMND8oyXcrj6ChH zJgLRruMIL0bH;iq%R9_2O>wqjG~AcS@HMzO9W-Q^YOjHyY-?x=P1;WpM?R~i?D)|E zEX$^diJ5)btA8!vxurQn{FAT?R++PxvTw~&SzpOF9wJg z1zjaEp(U8M4rhq;*YPkf`MdR~*(@Kjfu}Oo;&bWOOe?M>i&zVx(;~U;Q4@y99g+xd z^0wGaX8piz$EEmwO!Q5F>mMC#JZGs@xYXWl9?H4a-8J5gdWe{|AcVyy!2M$rZ0axs zE``zFEj*MvX5%$NUJur)eJc~-hpV5>hneieg1%tH?uG73O`~Yd_K7_iBBn3_w%m%a z+0PKT)Qriam4Y|vnl}l(L>`fFI{}QIq}ez!M6CBHCD3GxrpdP6B1Yhv*n9N8j8~_x z*tBN6!e8cujAU41TIxG%|+4J zF4Gv6^k=*}$!Pf8^S4>VXy7jxA#50-tUEnbbNrAsLmXsMvQzG2GlS8C^$D@YF8TX0#Uk#0ei(Xl_b>^v6z1eFHH)?0g^;a8m z2HRU(O7DcKRnytc=3bq;uzz^0I6dVj7&E!5=M~GL1>r{P1X$F^9Paky$0LZ{Y|dpj zn-1(|6W7GNeJ#`AP`ka*+bdFqOW~O)j@@#Ob#4fKBel1jIV2t0KdY^bt`Wh_R|>l$ z-Fw0iM0Q8YBZ7?A!D^$yic3f+htOsBq8~Rk1@FVrB1Q|sXtPWRzPChKzibhQc$!;N ziJROUvZqIh7%d1#>gPi8{7j{3p9Lyh3ipGbMQ>-wpkG?8Og}zV)%W2-4GI&6)Ru0vc{$b4Aabq=o5{U1FieQsZC4avGoik zrdB&RvRC`QbJGjiFyVwR9scuQg6o=1?!nf2{lG$S5X&v@!KDro+&|rf(XeZJ5f+rV z(T8&z(w;hJmCl}LyqLyUpcg(+lDG3rBKmog|mfEr5r%PGm;=A+r9=0){XeH3srC)pVXtPkHg96i_}p zK*K6;`Cb1w2+$t_uSa$e$pby5OP)1kT#l64dj4xD^y;{fmh|34T&?TLtH!&)_sk`t z?vg}#KDa>7+q1-|mE*))(?&s;&Dxkax67xX^-hgqc3~C`w=Gp_y~Et6joSICJPDxRLUP8_z^9fB=_{%X~SIV)l9@#(bI+%x2OJy2HtdM-Dd zI8koE-X6#bz9|bGTgcTl&nlApB{?c>DC_xfVK2NW3#DV~+mOK{7AqN_*b7kB4>VWy zM=KYOv$v#L>&k7FASK{!bI6=PHG;6H(RvtV8bO<1s7VfQU!cGfV+bZgxKi<@OO-_5 zrZ8wz3q~XJ@CJx8i=fNRYLXSPJ(N)gEy3!0nFiO3YZ8QEeOf@`#xQ#8SbrjS(Ua&T z57=Fi#P!_pgq_sOZVYrSOlITpF>foZY8*&id#)hYSP#Wk|H>Xm(qzm9zUPjWS@3dg zTUzAmpwfP!uZm@>J|8sE>{W`@YZbZS#><-L?CYJwU!Ual zDN!V&@A8;8+49FHMaokDukv&DHp370PQ%L?@8z1EwC^-LITb7T3=RezkiMWQ?cXEKYyRBjS zq;&-B2f$KY?He0gUbTdImm+A;rJqn;RxOR2F&Q3pSPPf!hDko{JYi7%O>n?kAWug4 zz^sKE7$V=ofixhuP@|51CzjVSw5MvtTuR^iGdf_GKo-B6WTsZWr)!6ZHfQ+ zaN4cGY&m~!I+Xt=5x8&+t$>>iJ0JZIClrSuz*8ERO-bW!=f9R&(Hk@pACk)Rnw@ zIs;rbt!6ZK9iK#cyq%?V*s_3DCFhfSRVU=m$5#O6Tb0KyBCRZu-}YM05K*}U$k(@$ z(*EosiaE+5P)%%S*~(wi@eiTbvL-5e>CPms?F@MOWhK{J+*(0MyLVI!44*?E9Vk&Q z?&w8k9rT49;|+k(d_OLhpOT8Y1t>5gh>l#~Lr!*W22pMDpt3_4@rbAc-(TcHW{og% zZGUHYH#VE~BY9PCa%ZFtZPU<`;<0^ax`k|=*$DP^TmiiTLTf^J|n;7DIP9V|C zUq}ap4^$SdKSc&=?iT6o=>%6DkCS;bGKvnmIzn;q334QQW`B=rQOn(Z0-PI|u9#*7 z(5$p0(!aU{Oorz}hkg~((i%fy^^%?7^LdUGc~b>pVLKS2hiRppb5l)^7;P3YjdJH> zB)*aR!H3&NaP-)T-n+A{vTv299XqA^ee6YkG_e4yCWWxNstMU~uR92~g?~wj#q7^w zi|l%|qNO_>(cO?ZJoJE57P&C)K_gPWcnGBC%s1R8wj-O{LDhKTK-&D!X*iyKig=COF9)>REtAIOm{jXNFU^mR^E7mDj zelFx%)i<#h8FYCd46L2U@r~v8F|i{R)PowFuSwsTN0CFzTp+7PD%@CSQPQ>*B^qcHvT2M{lDgkRr}g&yxE-$ zo((ecoXNAH9biuL0>HAs{6**9BlqM3Fps?_hCML&rQ@kZG)WmlirV#nPG5Ea9uL0f zt+K3T>t$<{kI?}XOE{J*EN?9D-13WLR*1i5%h>6hl-M^cCr=+b%1yrd0d6hZ$!xwz zq#t86G49hTE_LTS`M^otXv8jvnhk+f3vxIvFn@-Tok*YTa5|yY8XG&7(fD->2QX(j^YFUM zueEd5D$>CY-RO^dB5e`vOg0;hhaXcn0;ciW-G>ai;R)Xkt!1t1>N`|AlUK9)^mu41y7x*Zp{?41EyO|Ll=UR0bq_fEbO{t*V!8Fd^ng)*X^h5| z!Br&WkcrZ;lP||z&ErxM9-A(E-j4#FSH}Aj$<~^Bbn}@J+^QOdIjFWTUADLHv)i|jHY3NQ^kHq5(eT%lw&=%KQCy$}6L zd`P>F_HgjYR*qL#LRp55Z8p-1-Hz0xybZ;x8s-n?I@|A7Rfy@g)%4)ets-6_@je0X zyI53oyK0jET&3)3K85PDxo>xyDEZb0AHaR$`{8DAl?aa#m6iL((~(n3$gg2#a%6-W zFxs5elyxsvzOOr(@k(R*k`z7urs(>L91V=F^QDCBYFsS09H?f9#w*rK(I(-vc@N|Th+hHSEYL1J4M^xU)A^Jj#-1iqD49BSo z+khbk4v7*EXW7*%!f}haBu^471tq7b{0GADZTnz|gC*_sH8z#xlfazc{jh zK2zSj7{kfcsdIbDlU=81MA)OvHA`+pSe6)9X-+(be1t;!zvUMz(9?*K+MlZ7hJdT_ad^ zN=;2?tr72?V0)jvvtVhw1?=hFlB8NshjfF!+}@XE@;uuJ);oq#e-}IQwIWHnwrw0Z zK3XH+IVg6O_+OUP)?0c7&@nQ-;+bW!#+AfI0NfdA4>;(4o9WNqkl zNMJc91mRI-eHcF=l5PQW#^-J6nFNw&I|gPMYiwt-IsbG!2lzbh zB0F>1YdT8BQ|8mNgLZH);*N#<@VN-m_jFB@T zVD&Fs+$zikLC}rVAv@-V(v=506LZ}#vL(hBeCuB4dj95n60x{767Edu!uoM>Ml*6O zIF$O`YfLbIFyDAYd3Ftw^B|B0Z;Bwg=R-*2Mw8(CC^r$8y5OBiYBU)MZ~Kj4GJSMH_H;(O&_lT{AQmM3y7mT}{ zC(d>IAf4(l0czeaWUZ=OP#`z>HiUldVXVSmaI2nWoROMe8v`j_wB8BfofXN^+Maq# zomI0eV@Nk$M{qFRCYnE4LN1iB6>j`~5#L6$Sj!EeVzXggXoALG6;s-P#O-l|Uj=8l ze!RS+A{Ac4A#AcX%guw#JgLc??(|VFYt@$<(d0-g5x%}J6EPPsJ@&%iDOd4jR2`c1 z#FL|e>-Fp0irjkW0Nw^wjK+$HZ=!Rba%D{XEY*Z}K4eveExdKTD%yBWCw(4whSn_~ ziA!1yBrh6?kagxZL!?e}lUtgZ(qqPUs;A{wq%F@!f&0aBZUndAxh7TIb%UNOjxogY z$RMfYY#rL%%2PG6!D3=^!xD}!xguhEZqFB!l-hm4Vzf5rTGOjXJFD3ZCe3;3V9B@T^KlZ@0h0RKGX`o!)_Qb)>uAD<{QcloGBf4Cv_ zyypaYmoAD|9d1a0?}kD4hO;7;1@;Qx=a1r++;nAeQh>@RHIj@kG=jJAj2jP3kNG-( zOc9@(KZkjCk*e<@>=;*;l$#;Dx|a?ibfHg<2+D*Oc_wE6UVFzd-Mr^gH- ze>^4U-I7Z4p0P-w>D5x1nGF~}W;xGLDQot3t*>g_uj>pE6E{hI5H_gv5^EK%7q?LR zoR;&_F7&aa%L+5iSSE~I&LHW6I!(UZF+m%Uz)&^lYht0-HYbsB;DnGmX9 zb3C`!VlW5Ec#M`79Ce45L>yM|J`kz=_%14i@ryB=jVNz$VT z>iKARDc;@Tbr;`wvb|`~a(UomHSOMHhltNI_|6iaeV9hoc_F1aMAFc1`!x8}fOnSo zPL_G^?CwK~$1J4vf}$0C_u`q7PDalg3>%jF0^XxCudsqBo|IG8M#wQiCrD21+p-WFF3)8<_;MZD zVKF6h?lpmis*9RayGqFDHmzaIVC~LwpxN|W89N+k}}xVfpW z{ZZ~F72lrDW71=|c#llBRIu@g6S}D^>-DFj=pY4u!H8UjsIfLrcG^|V5EVUQKSlsugt&m7z~8 zxSI)l<8hU>DmS!Dli8^wJ3%(Ma+~D8`J{yF4B+k=l1huoY@%xKDx*xvGFP+VW0mRPI9Y7kt~Y z@O2RhFg-2XY>Z;OI@kOn85Dn1nGipU;}xdC-u*Ts1-Azt- zy;@oRxgmr$StIi{;V*L*fL$cBmaz8=tZM4`{%+5GZcSB)xIK4Ej0m0Vkb^RlhrtOVj+WTdi*c)mkw4M?450u#~dUDGJ z7_oLZy+6Q+zB!nn?3+;wN*Ad)9|r8(z<6~y1>&!aqj76>IKK?66Ii>L5B<0Oa51kF zm9E>XuywjgV1;6-pDjm?U-XxyI_1t9ae()7P5bw}P5Ay}N8-HXQjuX|0p~x#?#RwM zmB!y0DAiy-khm1KROT&wFQw-lD~kQ?WwD6tg9po7(mU6NQa?pk5%zb2Sy$3v#)saD zL!Of^uKpPnG zVe()8CCiMGAX|!{x>t0`k)-vCr%pXMQjj2=>jQlb8U6M2P!QNHiD>c7Pib99#a6OJ8RQ+lRfF2<((9duqH5n&nk`v z&)tF3%HXYVP#M)|4m}VnD=mkl$ji0_0rpPeJyPthwjX*S6Jdw_6wR-VYI?DUj*{eK01xJ^h3)osiphqXvh#&h*gdPi z62I?~yrys!L$uxC1x^7Q`ok6$SJcT^X&;j%U&~2{*Kds!x9h30mD?J?HL-i@sBtjA z`z7nbEH%}?*+9uNjgS`^W^ko2n%%=0jD>-5U2Gn2RnzESwUj$chR7`*@d#WK+b8z& z1jp}oHX+;ieqeNcD;>p4r?Y&`Uu!XOaGwP4`{!#k8`Ko{7PtMptAkQea!+p5N$YFS zztI$E^0bZoEkjMOv1m}^tB>T^)hhv)!f0k`sJ9AEh|86(lLKjFp{)`-Ob2#cPlb7P zbrhP~1Ol&T0G0)IQ*r|s zRzS)ePvzl&2eMc96u`9Edt?{NV7S`_<@w}k6wA*?<{P69NS8O*P6I>cy>&Qwl5ANy zkM;cic?w5*JywQ1VAc%e19drni()bRn*8%}IAAn;6KU*IupfL)Y0=$}8rCmU=Cz8J z=S&C!EXTMemLc}#LRdZLBv=fMq)%B(b`EGJ=S*1$?)t}-%A7Xx1pP&TYhp1bu~VUm zi@A-?S~YFA;J9+Lek0lBZXjTEb&V5B@{Nz0{LDbs51$27VWvkzn`R7wzhFdh`U&N6 zPKBoCcrD`BfT?h0M76a&L-e#cseJynO!L$*5O67sW|<=|`U34AXPwIs*Y2HETuYm1 z=2Qd#M)QbkF23M;qqVikIyKjGZK)5Bju!Qvyby3r?1j}4zVJSywYBm8ApVp}OFE^T z8-BaUEG*zJL|LRS%7(^N{)b)L#xs?dmBD-h^`_h$RD~+3H-H3kJ`f zsHe(U1-gg8&AcBtJeV%xeInjJvYWf;i_mp~JFWFYUxjB&Jd2i@1uC~2)rSBU9n3O+ zRquf>vK`%^(?w^hur?+G6dOyy``+RX2Dei1Yu(1$*A>!s2JJ%!WM60%u7XQ7v zR!6pPe>x!p=JpJxMs??M{&0BjgMH)Js%EzeepZLmpeywV_GrWFpy9^?Wo>gEIG>ix zXf&&tz}D*s+V8?Y1h0^fJX4jX%^Ja^8;j&!&sHmy>l#2`63q}*-;?3^)1ZSYFlT5SSj`;V}Eh7Eh=i8baqKO(EDv6nld5{-VB3%^~ns2sKU}N3gdl z_B_Pil!D;lqrkE(XWDE;3l-KoEbUm1Srnb$c39H30S)UtN`<{6@m{pn4vo_G+E%$? z+pA1=y}p;g+~wwUXud6{QML3wLF@c((6P%DPP_Ccv%HUkFBNO&m9L&La@SXmY!|LGxd_6Ax^zc#cMgF|@vRCRqQL4VooHO& z0V>>E+$tP(!)(I#S#WrrwestAD5tfROjD(x?^6qbSS*t$iAB1B^ z(v`yWg`DsCt-TAC#KX7b6(tQt>@Uu|sUizt|G%TDO>AAxCl!0H@_G*Ia^%<=w~80M zRjcq#GrmtQWH->2>^;~IBeeI_N8TiWL!EQB)zj4~9HTUnMl0zo&gWWpAWRww|!v(vp7St-ZsP+807q*p`AzVKkfJx(=2D6TOwr zUqU!uVLJ|ws4UEp&&HU+x)R>Tf;q|~&UJ4oeI8SxG&?_&vrS+d6mG2`Ofz$n$4q*n ze7o$!*&uPNuq}-FuuLt1{dKM?Kh6AAID!L5(c!TXgpSY0NKy8$l!?zLbCx)4QN)%; z7AM>(Q2uCRNgKx6s<3qu+aq{OocW7aqSxpzib?Q9uIJb$$XgT(s-xwnCHi!%F>igv z*1qqgO1gZ~1*YFR$z}%sj~cKuGNeI|UAdm)xDp(1!tOHMPeNi~4Vvob#YMgdeFK!0 z2D;$-`MNDeGyRBF%NeQ6zp^|?g=b4Vx8pgVS=_TrVC1nIO4qu690HfZyC}9>nz}|h zu%#V!-!z!B(POJMZ{Zz&EmRU`HKS`U4CfHI6dp~s_u05r{yumR&2#9e8gucy6qxS` z!EZ`AyL0-9OHvCH54cl{GVbnkA1lSXv7F8w25=*YM-5w=*y+wUR^C6a6|FnoS%pUm zOAIe1NB1j`yQ3projgE=`HojOepQQVtU#LCJtfG>mm71uF5#M3BU5B}m5DTaD%; z#UJA=>FXJ`oF@n752nX5e>E$VJL$X8O$Cir*qZ{E!XwLGmg{j4+&`&k?aD6PZV8_U zFsIr6D)}0G^I#rfUCmVZWP<@nGp z`S&>ME4H}u<1ykMuej&E!E2)AFWwyA54S)1ewyVscxJM6m+J1R< zCR~_4mma^nm*A5Lj;OGv|ox4fZ z>m00nvug^%laVDn;=-}-l2d~a+R4F*U{5gYEr31JSX5*6R%yWMQ0jZbj?*aY>Bb|v zq)yU&E?!7ewr$`n?pXS;R5H)yTk~vv&O}htEB_E|i^pDb*kg}*K!hYf(8*Amu*;s~ z6&@RWPGr$%Wr2_|c>y)NyM>coJO)^f*_&a-<}4p(7_C@k&y65HbK;XFvtaGt4wuAW z+Gzbuu2pypa0^*qXM~X>m5#^8|aO@H$vndzDn}p{C@R zpA8;cjOGzh?R&%OGBvdy_pt=~#$az69J|Q&qNlB4X_1;XrbA`(wrk{i^IhSrQwA4V zj3bU2chCQlvso;F&0}8;M&LUctX(XE=XMupeq2pA*3Qx3FL(@aP3(rgEDtR0!)eUR zW~8%Em{RLkQ?Sw-qQO>6p1WhKGoa14FnZ-!2M&Qt;js~fORpQklPio@si`)YdfmWs z@$5PeSXO;p#(iRYp9ZgGV42>oulQtxIf_eRG@EygW8i&&nx5Yhtif`HB@s&~%Mowo zMUGprX!2ThDE48&ek<4mhI#z9?@D4~!>MK2_);8QgT1b?jIqe#g(*^nx0){fy4f1b z71`%QjtrRzKRX(6(V&80-l-1Q-B8o~i#nxvZpSi)echQ=|7H`&tyI&>>zOuK;xON0 zzHO9hRe8gum%k%;n)QQlP}9?P2Q`~At-xZNGnk+L%1I?Ji3vK1@WL{JZmQBFCu=4v z_r@8*9Vb5--`4W?qWO=~AZbxJ?K-nL!Lu5k2l4#KJbp*@0ZP?$(W<->+z;Ga%mqOh zGxenS>zSI0vu71yKQhc+%ymH+TYO5?FvPG5r5Jy~D<`grc}-?Ll21NR)4jt=t+B*m zj$%%;b?{pZ9GDqF_ooXSuP}eG*8;O`ABcx#x z4VG8z`-44_n0`Fp0{X|s(Lp{szi$WsMDgS3e*Sha&YZo+xG$2X>1~v-&jfA>z9VN= zfQR)}|Ge9;Log!A}wM1S2pH*$HxIcQUVcIKAF@Ln)44#k|7aTg=lbrKKvua2Op}oW~(> z94yb>e|of)Z+&O+=l@(P!92kdj(NzEU%NSjJ_1ZAiog5!7-2 zD_dMIrpLER{h%q-Wb^Kf(bsI+>XmC^=Z}O~vlO_N)KW~MqhajuWWX~9yZ1>a@U&P> zA3l9niq}ERU0jnO1e*3xSsR&Av#1mWw|yV;XzQAnC8z9tBlG>3F|sasI6i{b8`4$6 z?Zw=^v^t;ktZxpV8*2UfIy7zsRcv)$cgLUW2W~rVExQ-3szYWcgi$hFhvP1mW6VPq z)6lpL88$nd1`iFCFm+rCx0Y#b%O0u*o@VsP>SV6x4_QR+EvuT~+QtGf7g!Ec9e*fT z!`8t*zSdYqu?}LHW;?Qai@_;^WyQN6tih$Q24nvswiiuY58iexR=+}D#!~&3*>1X- z{wtsE*c}Wu6e_hdbiin#HeRi2|0HrMIfQCPwvljeQ>}_g%df^z`{!dBODOYhtKWu< zJ{C^1hQ1RquP_4F#Imu^?5FznvN26t$8TS^qo$vYSh1=jbi_<^5VudyCE#?C657%quYB=norq(l0XfO?o z!1M%R?!8CS+WvubPO~^}%rSp37g#2Q#6GHFb&aX?e2;>Ai@AU$Mi4%4Yr&$TSq2)n zZ#I~_SU<2=Im@ND=au}D?M3%`_bkP$KGqMc^MY{nNH4g`&IaGyt!$d4zL9C45zsAS zC1BmgIxh$jo8m~5f<<(ZVkBWb$Gx>{UQDKEnLv)j-f9r`tPn}!>fG;H;J z1@GZ7-*6Te=AXFPn&o6+X9HbFYoifrIN8z(vhE}R<{Qtew@sUs*lQbQcL>oVhN{Fc*enKmYq`1ilnp-r8TW< zaPiJ~Jb3PYw%kq*#m=X7+V_>R+1MUy&<6TVtpm7T+*J$$29tKK5XCI+eH^dLPSaIPc0;;~D%HT3%B<+`3ic7!dX+y|vrsmfZunQ+ zw$H)sM439D&hIfm>eix|>|NQ0?dckGyyAPl&2t2q&tgU|#yfEcTna~$u>3x;Yo+BX zHO;b%5;1@99RSZO>1k79-!p=?^jXWrJL4!AKBoHW(Hi9C%Luyu=}KE%FD`}AY=(=f z14DMtqw`Vmb%(yjx~IUZ>Jv;QleR zi*7BdzyjEvItW5cSHbDWwUllzdqdKXL@4oH4-?l);A5!G&#*DF3F-C8i@I8VQ}B4; zIT*_^^NlL8RxL@ZO$*lEQgC!Po~ijr@4iPxRfYLEm zz%(#_a0C~-zZw`$XxtIS3#&RL*WajlSJ>mD53-6@kx37XGq16bg~_greYn$y2)M* zEhEsUejxQXPgSr!XH52Fd9g-AcK>vU3Je#Q&l(B6=dNRtsJ_<}`m!Cs=$eE>;I$T` znZ^BKZMYJsrk!v304{}hFFd0Cs=2U(`Ko>FPh9FlSd7palx%9mR+1@1nUaR_}*(7x!kQK)qGY_oM{HfwD6Kx z)p#Mviwvgix3%Q-1M39V0_NjYb(t6)@}-3lUAcT2xP=>-ro|s>4T4&G{#c}QTzah= zNnick0Bt(1ArJ1@!_c7l@O()=84=$bHcc4BX&O5f&09dOeF>sR-mT@nU<9Veym4Jx zkRYod+V;d)1=GN7$J!+bHb2^t;-Wxm<~UoyQJ8ogJklhL%>FPQe8S^dKR$bPCbM5I zqWV`xE4VHk+lgtjH>CTUlWFT%1n8k93a$$yFl}~o*MF*X61)*Vs#_&X8>&KFs{Az$Q z{PDBTAb)RYp_)WX=6+D{oH52WMKoVL0-Rztak&)P`#2rvfaT=~dc5KVVBN-=ig)B} zUt-H%t2Pawv{Sl*zhDI3KQN6l*MMu{eWmwZA9|AQ6_sy0<=qFvxHuo|X29AZ0@M7=}xAiv{;za()`Oeb==!iQd6UZvnHawhTl_D>+HT2;5qB%XvGRT&TFD*zTK1akekKhT~l(d;ffFAM&!* zczPuL4Mzh@B5o~v`TgV^@*r`U5^!M-#W`0WneAq4_+k0qy-C1l*(^)#P8?fLpsAl; za?*}h8JvTXd2$q4lcAO4>A%fhD!3)M6yK^&F9kBNz>5~%{K>7HcwNG|$=GTjq)4eT z-Kfe+qByr5&I!n`ob?iQh||__w1zjeOzdXc@r*97$dN5vc1p1V=!;bM`e5M ziQGDf*H=C!E@qpC+$?8#Id9oftamtWn_qE?{cKeej>jr1ZnWic>0!h=cB8Xun}Phi zM?1C}n8vRpEzh~rU-jN7md}4^7-o!+WuNoF4rVR@HDdPrI6hogK5+VLyiV6h0%i0(?vxtejGye zZt^rRg4d|nWEF7^AT+|dBgJ2^wBvjr+6cFPWXX;Gw4hEmE>j3b;9P+$XU(^Ign7R(M3;wsYiyfrIJTHXS$`c&)|swEOmH(CxuM zy2z{}#dYCzH^6LzSleePP-%Ij=iof72=6vo1)8v&T$gdNf;ogVhQW(ukyUF4C#Li@= z^6LI?&l>^aI^!x{Ekrk1tWO$L^_SGYCC)&}nxPcVcg=z44 zIrTf$lPjI;Q@hinDbDzfvk>!nIk&bim%e11(#@uX%PEUjIJ}Co{3Ux_pljcoO3i3L zYWFZtlyBREK6^{Uy!Br3XKxY02j+0v#e7)S_&|869xUIiC-p`RQC3Kd1-o5Y>-E;I)=tId3H> zP(G;>-TmI4TL*D210G@b>?kZh%JNK18%puohY?sG*%{~BStuXTfkw<9$Z0J`^N44y z&cU!9P3f%0BPfnc#|W(d?B;H&s4{<-tfUth|32OQ$+L@BORWDa4l>W^zF{-FRi-SG5oc*|7Opo2e zUF$_A`qrY8Qbu!g3D#hobDd?Ievlv)bh9WOI8#jnqNb3E7NPQXNB$)N{K5dU_Px*} zkK+Y;>+CpAYjNIlOpnDIL<|JKyGxWl4T5OzF$cw?C4IonGM9S`0BbPIpnU$j7;&L4 z{WqJ>vyE40Jg=}@wSWflyx9wV%86$pe)hSY-@mUn{1iRpmn5}f^n-FSuW0MD^& zl}n=*a%(NVHL5psxl*{`g#5Ug-9rg+?G8b@@?6=lZ!)Ln_zno8ncvb|8&&*USLNfQ z&YVVJE#h-JO^ljL=F10_Ycc*@CTP44VhaS*!QGw6gAYX-@6F*9zdnNBP^e|Kg&2;^ zl3UGLqusq~29u&e`O40BGdUXgwF-=8zUM2tl62it#pKWoE(1T#x{uL<;Ae16GEKXn z7}S`?$u3?8u^hAU7&!#Yk6u;=J5J-I1j{S`rbXK5o$#=Kh4QcAOp51PymP`UgCOh( zJ_s+HT~?;&`g3EB(fkM=SYH4?t`4Qgx3{Fz*j>Y`o(JU1V;2LK3?6Ygudix);{tf1 z-;-*+=8P5()m)2buX(WFfAWLjykYEaDYPpwzPnu+`i0#uq1RwAclq%cai=l4^ut}5 zye^31w-RtEjAju$i@!;W-Y!%IXDyl`LoyMTepVn>zAQ=dL%brEj?5uUi)PUWEnqqF)P`t9(! z5ROM@!AQq7%C3@yTs|3X%*UUsGlnQ@4D(^>yNjH&G?PA#m`Aa8;t_lpkV#sHWy>vM zGMLu-JgP-1*KP!h&*9wrIC%Vd#Iet-Y|9D&wmpdC#sj~0g2#rfIJ?wfn5w7jb%@}4 zjUXPo6mTu{vms{74r1%R)V7>`Lf^{RX8?p`V2+TJF zy{LmF152eKEcg`y)%N+&Wn(1AE8KI;H$gaY>9pkE;+Ezid;c6$$2y2x%d!rgJ|>OJ z$}JszERy0d0?ai$_ORYH}EN z@#}~9)i<8I-=8*==hcd^eaF1XF-I|{dBiH+rZCR6^vD){{<%w4`8>}4{_eAa*e`;))KmgUpd{+`crmK<>Y@3%J3_L{1l zERJ4_2)&zlK>JHuN{Fi{N@HLCptYqiT3b#KOa!Oi4EZ}p${$3lEHg4^$$#jU?6(!7 z!K}Q$9DgJ5m%nNJsYy%W|N8O&tJh3-y@+f2KSa%`uKl%$m`07E_qR3wTj~!&ifGB~ zx~u-D=YD?rML*L2vDPBSf2j-Io2?VIzuWoNfYjmtM?;JLKN<&`9qNY>e_Em~g=zmE zLi|PT90>o1Gd+xgr@`O$SqULOsbm7AX z`Qp1s){j0fS;qI+9SS|lJPu9miQo0-a?kBKVp&lr+0md#e*3dnTy9V8R_}< zgFI7T`|`OY5J8u*R?R-OMxI}gBU;L#gvNNvFK-r$uB;!IqSEC)e%gNY zetuBAqv>a}?G;<2P^tQ?)P+y(@)ZC5q8|Hu*Sd}6y7!A2qTj#vQsvzi%7QcD6o0{p znT+|l#y22l<_KxeQBt=sqrh#5w(c@9yR6oY5PSUu|zhK+WS?D zw>A8jS2r^veK*$wp<#+>S)C?%XE%e41q&DrJvl=f5p!RD-koJCM5Qo)%$bb!e*8f$ zbASs=x|NwnqD9dW-WA`+7#r3jp8Eqd;UQK@EWj{A@o-) z6>q#VBJSNH=y3MsT0>*V9I!?-mm`Q@YaJN$B1iOQHMs;CL3ZRuhR6=^g?}y0RfX)m zl>f)rS;tk;e2@QHh=quWiY+Q22F;z_RZ&#L!fpivu>b{;5G-s#R7AxV6%(Ynckf<| zN5yW%PHcJX#P69|fwMe*ey<<@Ft0o3ea_U*&YX#j805?M8QVbQH^dOFmoNWyk-1nl zER;M3qK82%(Wou0^BP=B(QmAsuzQrPGze_?pK=uYF7qH|LwxyNm2E^_51vduHje-F z%t=hOY!AffDY@$Mb3%mWTLpgTMqhsAU{2h%?xwn>X&rugCMV`LYQcyB!Mqq)y($n9 zn_7ya+Kv>AI+m3>9v{bRd%KEBBc5e110t-si#ReXSsi!Qmp}8di|A{e3pbcG`Pxj3 zz1dSZ*3?Y$2B~%6txdi5O8q3;m#@is~!oarL^{q;_g22QBzyqCCZYo5BT?8#zvYle$^2tTy$XFTd{JF5=i7ui-v2 z@lUFJ%N?+!-VQuoI-3H_F2x4)0&6P5X6L39VRZ;^y6pccM%V4AFTcPCsppp zra`LI*Q;>-zIX`z^~OR`dTB~<3Y9ieAXSHEo> z5IhI2;<5F&&HQ+?$6dtMuHo7Wr-t*hCv+2cKV1N+I%wl1)`PMNK5^U$ryUbm6WlKf zUxb;pa)7WvRgw={?wH0U0w>&>w&HvsAGtjeoD6R5;~XA2ikUHyinQZA!KlwOpM1U% zE_C0uSBqoHT(IQzj_}RuJu9@aKi_f*-krqOVX=^pcWDAQXndHkIk}P!$6$L{6MWIr zcpR4)A1;Ki_0V+rzK=70=O`N8kJn-XYl5Dke|=K#SGYjmY`CV1YLk|NGUo@O29qG? zjV8n^T03sxSQGenEj-2Ykg7dT3!KW{^X2bTr6o6sF-uIn(Og+L_~p8Y7paJr^cLHO1RKo^GebBunn9-xU2ZgclEPJ;X>ViUum%vE(IkK`0*ww+h?jU zAm}(xQ{}e3tGI3XOhupQjrvMhH<-6bJY7Ci7*n;C4yPT{^Y{AlVcj~3?l~*rKAHSB zwX*NogbFP(+v#wsuwGmuaJyKPF(*|C72a)Vr^CG(Ca@;h$#MIe_Ev$b;Q6MBxC1{O-dk#P(pp+x5fZ1N{l(Nl*M2~I~&IcxNp5TPS=*F7P&qIVC!|i$erpHp4hEsHh zmx@b2^by{r)RxSltfXnSV&UQb+>bEfO0O>>9$DZK z2i64VwnN@%pPMunY;C$pSTB~U0OOToL3X0cy>SF?%nFz#hNL?SE#_EDc)WvYI`%ox z*jjX$=?jGYKDBuA(k#K`!Wtdcg{3eJ>mQ!0wC8*(2{!MCD8^TKOyv%#>hPeIIC1te zu<=<~s_pTurC@rei-e_`gVeN+?M0(?K}1QU7+H(DI(puq+B6A|?v_1Vz`NR26ze?S zL@Im0XlZX}P5qJ3g}Vaz~Bg^lrHbNS)p zD~h=_cM@z5?t2Z{r|}$9R`{pyNQDhNF2$*Z6S)my#GWtm`R);3QoiE?-g32xSlMC~ z@mU+pUx9J-gH6$;@-bmg6#;|o_2<}+W5!iblHhv!iYxAIZR-w z!lPjOiKVFTxDtq}Ck%DxQ^SO~`*)l$fu-j54&jeY62z~by|u7XZDp*R(JxHsno^#_ zQZ*OE@)nPqiF?hxwMt^rViR3}*(9OLo(no0gNecGWB4}itwoj5RIs7yT2p83Geamy zOwf7QFXdlPu@$>s^;hUs5@QyA5T97i6;cm2(PAQUPzc|^PY@$Ic`9h|!|nPcek}|W z$Ydiidu#~bVV58t@D0&o0&9YA%f6_h>)9k!C^tM$#5IM>?dknheCMW6v&pBOR4S)C zm34f%5TV7Q8akh@t9Wf=sM~s{oUs(9;mZ#F40Jm$1PS}9_t4>(0}q4w+RN19EZ3dt zQ86p|SkMIDwS>1?-5G|u z1)Aa$PeVS&JT4UbyqhZcnq??bWqvZ4S9i7*mu)d4N+NpcJ+WCxC!y{fbLpq|eBN%U znRwcJ4l!-Ekk4P(Lah6&FBzBs<>t{soU0CizGVA{lj2mdx1e^dBVj3QLrHk-`Y4X+ z>L(0&yj6#-VVtuG<~S6U=_(9G`A4*8Z;)Dz?$GZ&XjjzZ|6b6)}YD~j=_1tn&7Dog|*c4=7QU; zP7=-`?yqn^2IH&R8RFdnb74p_~rx zn!p71mth)ask^htyx(p4$98br6!I-$&lL6=!CKM$4DxBaN%nH^Mq%&JOHDAZ@r&1( z-p?%Mjr#p*2v_!8FU{gz;Zm-C9N#r{vLu&{`lXiK9k=1S zb@{hdmEGwU^>}@+R+Gz7E#XgZ50tQ!NBhzIj+Ro!#NZU7B=)SnOxm@v z=Ry+U{vFWO%+){?K8tTToUk;YA6fP?zF|~>#mp|TCcTN+c@Z4b<*AuMQ zetApQxwhrEb_`Y2Aodh0eSJ5-58~=o_~q;c-a*_lu#~cu9Pc)STVXgL+Z(=Jg9+@} z#6DTrJGgNjX`*uEZE{1TLTHJhV`H=(z!!?8Fb#g6BeS^7v7Bx~BPD_TyO>s~x(^mf zozDK6DsRITK4eT_+bUIhBQI|BB@?L(>96ovQa`2P#j2ud&5gu&a3W{6yRI13iM|b- zuXN&0af`U2R?24(KdDNubBBrzxv#AU^EJ$aC9DhEcn|g#y4Mmv-HQbqNvmgbhr+6H zs&U~G_LyPoWJ<|Tw7;;Sz(shNJS5ado`uE_Hd#tSGL_UQDXra&{)N^7fOvBfQ z>XhX&jQ`9YdN!m@nI0^!8psUW`iQwq0&2w)U9*1;#H+Ku)wd+hpyTWY=w;uTF z^s#p2#>2V7-RB~Qy|UP+tMqbi>Cq@F@NS4OqPK$%OJPr{l9>0vQ}hClaK0`<;SnzK z4pJ{C_F2Q1Prw67{i5G2uh`*KVZBPfXkbKLE{}{5{H~W1um=)*9kJI?rP{aLOHAAd zU%+@$PJ{i1*bk@l^^F2=ZCyxJsNUEf>%umap1b4Sjk%OfvxTQeBXrp7g#BgMO9i)6 zIxQ1p;${k?H*U~jPZ9QbVXqPF-bvo7Y2F|}cqy&XVXqVRq+#2z&+^A-k~43L(4y%n z1%Xqd^ewfjyh0p3bhx0OTVBFm9PBB=9wb;LJN-f9S1?96Q2nb8w^8hwQrb8_e6wcf z**wzF0|=lI#i zPcW=E_qs@8JnePSmi`(OKd6EpISPIkFHmqQE z*ORUHEK;d0tZVI5ElbJJ%MS<*w*VW1APl$MbOYjvB_psDrm=0fV+(S8x6wA6fnD_q zT{yS66j;uMl$~o+dI5o@a7wUk=o6uI=~@)6kGB!ATw@pye$CyY9n^i5XbRz7J+oOj z&Bu|2VYLs4Z=RVQDM6)*V%`9)0VzsjO)8bo+i<}*_Dg1qQzGemE=u$oR$Vl4F(JJ_ zM~Nvw)Jy9@?(3t(`&=#YyjK}0s~w>Gy6Km!t@$}jsu7f8ZIIghI7*!3rV{hEwj*nv zMTzwH{vT|BIQ1@Eur5e&cKnv6kfJt<=n8pJ;#Ffq(c*D)Aew>=!{kY6UTcmkQi7#0 z4eQR3kDSJ%vikdL6!|Dk6y*stRpTxZH3_!(Ed=EM6b$ zjZ z8|q2p#+?~~bzz!@Q=vAygC_6}wrDN9T6J4(YS>wNQEnlNIW=Jj3BR?F*_(5G02$;l zkA+(ep9;kG8$0-0R}O35r}#_L*2uaB&gr2buqL>zd+D>j^D2& zuqJqOwikrozp85|Ia^5BdYOF@EQRLt1BlYb?Z{ce@R9Y&)sXc%Oz@ZIGJA1(s|cpy zOEhEW2>I*mH7`9U>2M4t41UjL_T2B#{;Cjaa6*&c9mc5i}Gw{g?E?eVsFW1vT^JQf(fiir5aJsOd4X;Ts^+2n}o~f`-pKY z?Z(!G*$gUESp20v(pZw9>{Kc)ojC?zde!Mz8e`9xXP8_Vdq# zXtJ@^7-p~U{$ngm+f^S3!?&G);5z&|vKR;~g=re5&-p3P1m5$)CpsTZp1SMj@lu`J zeVC0U3p|K(`you~#?W!3(TE}JcbkP?Kv-?rqT8GmqKz9fQ^Hc1ezdqJqdk}R1;VcC z4l(ybqIy?{aOwS`o=jK$%l!zJ!ZhT=x1V%tAg^AxrIysiZ4@I0Pnxet3APRU8Q{zH z&NY%WIU6f02rSiX*(jE(CleMzs`7S(O3v|V&JAa_)Zv)9i{$c|F+Q4L+py==F;v>@ zvDC@drJW8-4WB31&D;MFzo0(6E`GC3Fwtw5J@w;SK~0UYxyN{<9hP=lk4q*l|nsaGByDEV}c|{3 z3#4|=Tu7=WhjOjq_ubjy&s3ez(!anOWo>uF`Civ6?+_m_2Sg3RIl6p~{@>*6t z(~g9b9)HT`>V&zZ=bv)B1Yx)tkB;^pk7NXv!n6};qNVE#n%KBRO0*keZwaIEh}&zq z4+(X}-eYGHJcd&e_aQZ5!SQx6`;-Kh!uH?`t3cfK-(uhPlajzvp0HQ7#^+Dk@(*W0 zs%Vb$%%0d;!3Yzl3Xdjn3RSADuwIaEGeCRjbf{>MBX@4%ufjp7qqGV=j=F zv0m({owHg4HU__&AzicRMxrJk(P6^VdLpBzkG!g&;XUZ(z^%5u>fBKmF2%;pVp5*z zdBkYH{1)9^{Wh`xIEC5UufGj8dY(2F7TE036zp-A+^)=#-x=pGDG00yPIEj67v_Ap zpiYeaqHT69gb|V;5)YFQX0MI)ITAcr4mXaW`IxTc-R9(kCp)&;>Gq+$8BTmE~CZFBC8PR0eVIYjl zt=IjYl;a#8KTE(;n7)2v2BUYUQ5zbKo3yi%h34OW4F#+V)5`jI{BxAF`i>c?_qmYA zQn+rE#P{d~-eBgFjK{pcfUVymy@avYOYS)JVL@!n8qz1#_eKbso@(Pb5tp6?_muD9OHgt9Mijb$0dR_sZ_OE4U=B)7@|2C zQ&C|96Du2eGTXD3Ux8HJNr3N?H_dU5Zqt$<7vUwx1Uw;F3e&JA{4z{hdo4vh%(X0! z>lxEZf*AX9jmo5`N0lmFT%t>odayigfs%&1!iMDX8+yiT+*?l(=32V2RPh#if~7DG z_juJ&38TM7s_X6^B^Y(?EbD50OhI5xu*1}q2-EX7Yv#{ttFYlRmN0v-UYsXb6P!Qq z+gBL-@RWL8yE+1v`sJx+_IyTMDMjSN7p-sGUDd<}xbc{{-PxJ7M3>i(38rCvaCEq^ zvDa<&$Fflzmhy>pW;Sfvzbr-cc^N1y9&|?IY`$2Br7&G3oiKZ4Z-0W)9TMv;G_HC^ zJ>$_e1%ah11o6yXYm*;9bp2u{SU-EA`DJ9Qc%rZrrr~Ca$t?tTV-NKvr>+uyIx&Ht zW;iq2K3mtmV2~y!Xu5=Z1N@xhCm43O@eg!6^Ioc(HJhmDOE7^o!49FSfzp}tUp0On zD|NW-;vNULW0k5;a%DdDYKo@8&M+yyem~|Z=R$Cth+lf!-&2 z)O7x6aBJ{x21!_|(rca(W`4${2ou#uKB`I|t$(F)5|*mk-ihhuXH_jlyo+fmOsdwA z)N*!_#!j_idSj9dI80zoDwWpBMHo=2qju1mmI`9kjCRb%k&h|`4SR$Q#|c&y`;h8o zKkDAEY0GTfzW9Y;0^5cYBRl5^-@7_#En+-%j+ZT2Ss7M)q#&>+*c)XFJM=uNtAFLy zQ4m<_;zvtndv#?x$5}MRT<37=hPwOuQ0a2mNEXw0eho!^;Cg~@-e2<2`7CRuxxE1H zyGI0;>e^r=OKsuw8c>6$PgIij*NoP5I5tGWG25n1WK!B2l{u^lMi~}$C3}amq-|Uu zg$+#HKjh8&m7rKduwgRPO`87bn&#t$h7y)4D451(bYEMR;grP6oFP&}(ibV^t>=t+y8Y(TDumIs*bgWFk&%b zp}NHy8(nP(9}gHp!UkLx8$vi}O(h_{j_G6j`!}or4C`+{VX2n0gqSghf`|k&2s&e} zJarbqGYha`SdrQIeYtsB?=^*@DM-Z*i6l5BN*izD`ZF6eAC6aFa8^KAXy%dpsdt#Y z4R3Cd?`ej-HT*u=a4Dqf&F?wP#&%Y#pa6H@qR=4mA0!i-A;K&bPGSjT zr_M;jslqA2wqYK1zA4N3*@6IDtheaoBt7-3v@zh#SC%STR@esCyQNVhT|G#Z_u1~S z6L9|I`Yh+A2`p8lseLy+ob&4MV_i((n!@?OH4CFY%bJYX-078Vc>lMoUA1ntmhg76 z_cZeIQZlDw1oNs1+vrTVWkNfa^J$SOsaO|o$GFA7N}RrJajJT?ls(utn)?z=W81LW z*V>p7brx1j!zsa1)u-%Ytv%QJBBbiP`#-D(X<5}zmp#I3AD>d>LrG-&)cJd=(E0~X zA>7`2)sYcRH)h+vZjhjD1~s*!!&tKW&@kpNYq@0_@%JCe!UIlIKZAXI$KvOs*>u@w zRnuk_!E~Q@vbW7=?_wb2zX+jbP(ypXmKM#MvtBf!U<-Mqy!Or)O*){*|&ZLH4s>#i&nn{{Np7a)N zIp-r4Il5~3z`h;WIMaG)v5o!{<}qUFa|`Y!7tP)!XFOYRSQDIgK05md?R{EZ?v}RE zpeGwy_*}H+Zs^Cc@ad?wr3stm#jPC^I3+(%wPmTAG>@k0pZooaTO!trQ>aW;#Cp?W z8#o5%qgLZhEKi;dT7Zq)zqpPxAG8J&_js_J|Jqwqk@iwVqmnwu1eUu0F@bp|Yd2~F zHkS6zD(*!wfu-(lNn(Wa;08d%Y)>gBEbWG}R8?JX!eLrTI31Du#MzfyJK)xUTM5<# zE4;VmXE3~*Z#ve6X(cf%RJK9O3b#buc9pGt$84dvUE!w)ODUhIwyO?^Bs#8(E3IOxK$8?+K~RbxK0C@IrBV0%g%d;FU-8?+^28#TRWXYm zvi@q=j2&rM3XgrOv&2RA3DG~fhcjMm#`=;~=awn<-zeYC zo1Zo*wt)${*QDr;jNkLHKe2)(BPRX+Y=g_>5Zo<8Z=Gp6jqEd@fFPtCW^xJZV~0^wc2iZgiHyX4}N`JRtoJ8&1d^(it#VoEySvn}hx2WEX#?9#$}m|&!@EtyT=)~9!>p`jz0iH9Z= zJVpiY`Knv&iHaQ9-VW>9u|@WNyjrZ{uxnyZkW7Od2 z3h*{qU$5?832Xz?uvR3Qu^#U5_LJ#NUf8popC442Yth7ph2J(Z;Lal3Dpi5E{0x4t zv^{;!05y}!e^5>F9>niQct_dEv($q6!&C7HInPucA-iA5CwR0BBi4o;iu0kryWP1d z zQ+j=2BeMB=zcf5z#Uoj)2}T)jEbQov-n5Fw0p}b`DMvD)H@~sAd#=K#G@K8dc4d8x zZFZ=*tZ+T!`d7C0wZ~r+kC1VHg$dmA!Q7y;8?)j6*(hDFie+zrh&8?hKZE$$RH-K1 zmizYOqYk9wStFijDrb-_KYV4W(i`4S!!~eF{qvIv>w_mx4~0Il@6Zp$`M^?`R;J2+ zgaNB_o!OR*y-kdmt|mDFWJjIKEL>)UKfyGditk*e`1!!rF|8y{Ewy6Av)&amaL!H2 zR21pc_0@QYV&)AafUAQT@#=+9I+i*#doY`mKS~%^iU^xMtTJ#x-~zS>Gl46iC`a)(nhzHC2yQYbG=wu)u@@L@Rvl+ zAIE-Q{^csz82z!tQ`E@}y$ODfU(?pYwG-CB7xxMsZuhH49&g zt=*vbjf0;k+}f4>?)p6+$RTd0QyKVn_{RAa#C8_Hv}v|O$n}>7;_0;ST8GL*h|!30 zVt()6T7$qL(01PpNafr^v$BSwN z5iY65c6FfhrRY^t2qu&^?!?sLvYxczb6rCvETt0Fq}sD8BLD9+;=8cCmU~rA+^}OT z>fM(-9N# zo-i3~Y}xe6P1>Kk%#8;!+f&HczfF%`JiFKUQce)M)2pXuXB z_Nha)j{JXH`X;A*BiNVs)-h_+0MsP&nz0S_ZCvrHu}gE|OKSYJY!c zxFR1o?FxIUwyg(}v#k$u7pp@)P>Eu_N+O2n$tk|+-=BjC- zc0t`T;@XSKJi$nR4V>brTHy2u2rTt;(tE9bV_EUw$f1f-P^pAr68W|yF1se2+s0BW zteqkx2TT{tRc>dpP;BscpJFt ziNS8yblOU=E=)Y=SDvlizqF*!pcB||IseO!+Q3rv9#19{p#NA)CKDy`%}Gz%d>D{H z^MR#0ecVedYSk3C9-LB&SknXc4`t3ur!5gnsXE^y0Z&ZCq1Mw&5o#bt>*le1V5w9{ z`&m;HQG&E9Q&s0^WCuC|m@#5tD&DQy5j;0^2ksK^+~8faaB8diDmG@IZ)tpjhrYv$ z&JwlDT*96eb9igZZ}XzD&*y^!SPK6<{1+iq)sD75 zA2*yyd3N?E*H+GB;SmF-kUc^2DVRLR;6DVNrPew1EFBYAYPvX*(UCb3h@iHxRF@6% zIhH|#7LorFG#|?kuC>QfkKW2V?MH84{1<|zirT?#3_}IuNM$)cdA&u^jVZVR;Ku7xWUxe_o zR$@l_Hu>C5-he#fF?>3cN_4qHVqVIcV#iVMc@aVX`vgp7QrpWsA+ATgS@_WUhYI=+ z@F(Y37q)@v5+d7vtOF+UD$2PnXmE?*)Rqu>wL=D$I(l-FoT@k1{|7-?Tt1kaM5 z1PvXHm(Ry|Oq-y12Jw?76STEAxt^VliLKIn)+)C}jaAS}8@LC+1nx1E1dhQ3wyh)< zc}KF8lpoMX(c|ErNJ(^Y@5P8}xBC%H|DA|Gt;)oGA11ISXiKLoS-(rI;TYVbVok8i zVw}7-aeV!pR4g^|XhpVzYTIpJ#fb>GQEs(su`dJLzy#I=zP@OaVj{ar9i}&<+&ofm zg?zdubI2l+G_^YWy-M@h@SLw}!!yEg@OIl;-c4D|F2@*>bW}cRvugJy5>YmSy-OC= zU-PGDDC!eGhPyK2`#de_u-=V@-9BUyZPPX^>}*c=>C1m|pLnTR9~RT1l2QuO&|Zyx z7U$!9KP&d$emwXelIz%o(Ze%y$jf1tEWA|8KsIvH+h-h_;KGQwie z+3yZ4JZ)up@SfvTsm@Pix}pbH=IXEaVc|!O4LIw&Lst4s=+=k_H8G~ zdzz<#FZ}qTflRMkdU>vVd3ne8c^~Sb$2KD7%R9+`#+q<$#=RI(2rK-xy9{CBm-pyi z&LW~=_a>P*1{2wt{TML<_ENx{^XhN*{_rtPPoEexip5mjYs}#kDpOU%t2OK4@)o-| z;2h$7;1VfG6%Anmm(|l3!&zDV8%tNJmNI}%6rnsE-Wn7t}uaZ zV7kPH`My>eHE)k$dL7?>C0Os@3CgaV?#qZb*&hj}|4ytv*CVa{OnFc9%}O6hfswpF zwbIr1FG8?+zRwQZ=(SNktuQL}y~17zK|}w*DhWMr(CTcy!bW}z zHTzvP`VF!{iDx>wC3b!DieMYqHkG4)a(!T8EUfC&(|PVMo|9+~c{l!*$4`)r?Y&d& zaSrhlb+DVf!&tETj%skL)ebvMU@2UNa+-?z5}fna+vVNr>ij%{pMUro)STPJqgO2T zdAz)beuCk}QiT1MfsB~G`b-+ug^AzI1y%~f51vFhr|H{ru_cQc7PMK>C*r;m_M{rg zdk5<|8)x7c+;e)GHDsD9uU-N+dbBWQ{;RI()+;ufr+8;539IV28DSNX<$&KTn8tGv z*pU+Onh}1+xr!MJeyb^o7w3L6qSZi$3>+ z+hYQ!9n&QQ4dI+)0&6NE8jPy#fagoNK5)5}5Hy7A*7Jfq^EwRU2iz7)2(hrP116fS zms>_kFNt8fgrFfTr5h^G=mr*Mlpj< z8L8Kk38s~V&#y13)JDL7aD@#_k9L#WTa%9mq3w3Qw2l!pA2{Z`ja>hYcI{W#125;! zy==^|plW-2oDxh}1j;8s4;b$+^?XndebF2l(|;#^HOWfD1eVIyOl6wd?JTlU^#1VN zIhn=ed^o6>lmC~XWmT>FT!jrxclh^eyxp8MHg%g=sn2_|@R8T0=LUGZgGV*EMC5$aRJGu1 zr)&M>lUl}s6*z3ecBsH??1P=sGEtN&9E0ZxSW}4&8p3k}Ji1pBL;h`AJX*pddOXs{ z^Mn!`Egf3hY?<%PNecD_=||TuOfyp5vcI!rIH{c{`M& zyFWMG>(A<=-s`IAcr1#?pLmWd+n}Y}uj`gHtQXt+VHL#e84piDJ;UqixoLQgjP>Gq zdr3a_^*w5b=jT{2_6L*@G=%5+*xui5ylN1yuz|103|EQ5AW=AiZg3V{ds@d^P_J3)4IHE<+f0-2-vH*6P$XKwv3M z(=eS=)B9^ws`ws#d8@;1vpS^&OG`c&v%1}D7(@)}R_1DLsw$os=ucWhn4a^y+8<@K0CAX|`7jRS?S(DsfY08Ho+6`73A`UyZB8*APc*%nyf2pZm+}PIYuM$X-|z z{swEpS9w2zX}ELXQcM2T*(aJQn?ofWgHwn#!M#!YQ@P!37C8sNcX)Bkisu!$$!BVa z0fD{>dvNDjbtmqYpM(06R!PtmrN<^F;&WJC!Zhr;Guz2;xj2ek+2JqYGKmY4cP?kQ znon>F;e6Dpazgvbg0}zq5fYZ#cA^n0=`Cwklp?;Ewi5dE8BQEubXE`_54B+X;o825 zBbbIc`ItU}%dEB9dERxUxI?n1(YyaXg%qaY4v5P>LWF57u{(T5hY2hdy-hx~mH0jr z>O3tmR5ZU1^7MHdKb%fWqvf5J1)8i;VB>VFVLbn3+&#RR3{w$MK} zF2Wk5P$Y$IP`%W~(phym*@h>&qY=kYItZjFjWsbFP-5~;m__NO){CTQs)}eDhTDzd zc1lXn^;#TLWDn^Zniy4%Z+qU0hGFlcQo^q2nn*J9%Xt2@`ymK$ctWtDB1YhZE9!jRjkmVI<#r zfE4r4kJa<}9S_!7%-YC0z{GwTI+BeO@BpicVAJznKHL0F%P&ZTZsBxHt+bfpB zG~6fislDXA>yGB$4@X67U-oJ|OX2Lqi;9*HE%8mDG@!aA(fx?jVJTc6xSn8UdL&%> zzNL;f8NS}B5A);(z!P=#`a41@d9iSd!kgr1fEU*UT4nod&uB}m0r$ckYOEbIzm9~7 z>L*7rsd16N$*E%_7(LU9u1)mZc3WpY`-J*CKS>&0c_53q^tL>QiE<12b4|g9M=V{( zX=LmuKL33~GaBBUn&WPah#OXc!?coU0R3&(V~N?^wrE6?&|I{Y*csxH~O z3cA7SUIEhuho$|QRM5suQV6#W(el~!DU)1=TaIWr`zY;kXWV+KYqG>hYo{A8T-i5@ z5%td;Czw_eQ3*Yz&zTj-w-hsBCENl;b=}>0iC|hul&S0~ZHI50JnC1#<66T6)&#d7 zR1cHBT7Osnh^nt3u#~dSv&vNGn|{r6J`ffr;N0STJl*NaQfv5;&b-VF2yd9QQqv?M zL{V0_q?JU)PmKjtMmzPq``rZ`g9&AQ*uNVmEWABbGg&O)aou7mT$^xz;*-h3k(Wc% z){QUneNW0Qqgs_)ih9PHRH|6GdHDF_quFKQE^Hiw+ZEQNQgyH5DSS-UXzukZ(BYOi zpjszZ|8u(kCNFC7tW`$d{RU;_c73v7up-V`^t`CUdNHje?5bG`wF9e==CgPye^EE4 zD`|5%4ohKsa6jD90=}H9T07~*I0?t#rweO>vvy6*`ToBwNt3ux2|sIC3e)gK=xPsi z1D!Xi&D%|sa1Vf=bNmFuePm0#rCQ5+kg?US>u`(11ny&$H(I}gJE_g!`B0saZ?tX> z;RAnev|bD&CmMz|dKh2*L^oO&#n5{P=YbTZu_m||r}`@D5tb@=hNjRx1@w(v=g)p> zI?6Ci>%s0~F0u#y@1v2)lz?4fwpf=M?qzHY#8|kO(H3@y(Qptu+t-S#z{a9=uZ3s0 zwXDUS9BJ%ave3(jg%?)|B+jrRM2X)`=Rqrx|K!o@X;=ZLJwt9nHZg=1a2h^JvdAp( ziqLRb@QTRtFh6JG-RH1cOk+Zy=t)OdWvAh7RwC&Mb7van@Z6aZRPSH%fGNhH^fh3^mft+4ke<3P~RLO6v@^>)4Zp7?SzSa{{RALJrnM zq)h^QqCJ+vG`3fgs_5l9`>t#3n66=}N*whkQN7lu%KgO#t-(6yEz+@dY!7QH zu|Y$g6+1G$k#Xg@2e7|{+Nj>PjKW?C@x?GH4W|U_#hPS-=6vE6GY6~}w=3MwzD23)c%+uN- z6?RZjU6HVZ3QJ)c-fGFJVjDN5ii|j#=d0+QaUTp{)ip2i8sJn7pIo2O=8YrCbJ#gR zQ`nyE9Iz>DS!@Ga$F!1II?^PysHd(Ed&j7*B-lHKrLaAi$`3Q)qwZ3c>XMwt-6*(@FwM z;kxXOxELQe)#qCT8nr6&Vvcp*Dw zDyJ(#+Wxjm25wilE#Wp@k`FkckcL||Zte860&SJ_St%iC2tQGn{@(=M>r8cRf^!p? z{_itbROfU*H6`e?jp@G=ck8=2U;_6Nm{#TkOX29-<&mey8uqKtNhCxI+ zZM&1NIy&HbrYCY~J5Gmt^>EFqRBv5mVx4}zEtbOczQJCM-Vb}RLCdOdr{U>X z7p4oFOktXmmmYw86s%#pSf$VgUUv9xdHKBjPK17OH#?QfpY3KkU+?DIEJ{ zpCW}NsoMQdq{0SHA*R85?mCgxIc3dV3FV&=VwaKMEuuwX+<`oV6O^INzCH%9QK`TpEiNbEEdPmyC%7> z``HLNI&DNoXV~dNiT8agaF|vSa=IdT=of1e4v zHvejm%L>;TE;nU9zQXu1sG(1PfG@gZ*5C@kTIC#K025Q4- z^d-gI8PCE?h2ts0p4tjdB2i)|oOZ!_u_id%*JpHbJ}~hT&Jt1DEA_g9h8tqbEMKmh``DVt*?aL?i=l~J zvu+Kz5pVs8AABo*0jz~AVBdsEHt6FIvS3(jfXAO)=?MgXzl+iT}r*NzgO z1BqM(y#seVtt_b*pU4d|wCASosYimPMDBKiBX{<~Ww?{PFMQGS!ipi;M{IP87)&f) zk;rupwc!Q}ZJ}K~r8(DEaO$vJPg;j2a_^(tan7bL3R+3j2OE|B2Ehfbl7hf_Ql^T1 zHPmvn{S>%+0LNfLnR8lJ!thx8JMdLn9ODVK*(nQh3$=+g!QJYA_7qWDadmS!tNDaG z`+kF#(!w7CYl6|Fn_lbP%FmwG{i8cSxH#L+oVDvZZE2dWm{EIhmjT%5(|jMjJ3+v@ zzBlvZLqN*WHC&4|!I=gZy|#`+;eTvkA~oKaf1K#TRXx5MY=}UF1x{lGj=_YsT@$`m zgKivuV-*nA@Qq)a^q%(g>$+Gf^M@V(tiCJPMOvm+63ct&wRbO+qqkouh__Gr@biy$ z<9usGYB3FKsqkGjYqQ7caEph6*tC8ee{OnL&U4j#Ev8kfPDHQuS~SxRZX;0;pP{TW zv$}9yp{y`1@6_6r)x&;IXIQ-ishP=LSc&31bvotCH#^>id(dMI7K3 zt7uBF6sF5{NF=|NWk2jJQ$Kae}O|W+mQuV{pz`1Wkj=}~ehKKv|-kWW?{m!=V zoYOC18m?>Z_+x}#i(@dcY^E>oIkFwMW7hy6@`3RBrE|O!3g2o(F_?HT(U*5}Y0dSq z2>_xDks-h>)#)Pov?&`Dp#{K#M%ZsCGP#9I^0FPYMg3s5@)@fwH^ z(FdIj$0&&-8-w|U3mbAl;Y)~iZ7?4SPw<|X?Jty9>*X~(sxV&4saWRc}~*F{fo3@#s~ zjk}PlO)H)_%umxRY+&Ltw4MYHfx82(2mIfTquHF3zSC2TIex?jGw$7$;iSP13w~s& z@TnahP`U+(D3YQvMKlgmO|Yx@Yjzqxezq zd)%;<8kK5U$LYlcmTH~4lo10bTrNd?T+!AZM##d5SBLDeE=)+DmN6S+TP8t&CI88( z!ZAPXRxqin*O!#CQAE`6Ka_@TU}E#Km5kQ6wJc@h?aWmyrr_IVXH5V95hH)fw5oPB zCrp>*Bl+S&dn}dUC70-fgTdMVC1_dII5#>CORde33B!+Wn*S0-HHf7!U3I@qZ>wnp zHCXAhyChZf&5HIk6-GW5`n&5Y|;IY%bHAwP*(!1-7Y;Zr$R+hSXE9-QUY7 zosIzNj1A%QrU~2ucnx?8eU%Z_ zV0`%F!yLM{ZTh2e45U`l(9yS26-i zEqb(w|GCkDD_r|Yt0bm+zY0{dLAPxi7$}zveTP5th9!^&yWFwapSG8@+J-;+l#I%y2UsAqb!8B{lZoSs9nLj^a zm@QX6YO;uFB@qpT-K-nV)vo4f`_%B~r_^`mJ}((9x*zl7yD#d(Mb5Sm+n4p{@4V-@ zwY>&HK74>kIMiFC^UTq{zURju7}SMJ$|Pd^7e9XfFM;DlcLl9dwUuDpZd#c;8~#R% zr7*qrwIBa7urv3yb~muG3~apmU0*ZNKSyhO!H;j1-i3QIvZIIzoI;iA>ho~vxrsU1 z$F%3mjW(BHujNjHg<8G?5r$ZT%uSL8@;mkM?$P# zVFMF1Y_+}%M_Uh!sXI}hlx%C8#{}NGMpy30xu2|!aet&R4Qo)~!-xpYXLlQxCTJf_ z_1?bUpZ^Nqu=R3QLFrmSPkpt@I(v8A>~6!& zsd{aGx@}i(Qb7f<;R`+WnEh{as3N}Fc$pjE&2fXPRt6ie8Hij6K8j#5Uj{H{Z>Q z>vl6*JnMas6Z*900#B|IEgKx<-rsTL%H5p@1U=RGHL;=NjP`I2a_B+sgoQ0Pq09<} z6sDm*UWW^oXX=x>H`55#b+5}ouA_qk_igSHu|vCq+?cg+DrvwXu%U)t)M?Eq=j*XL zg$+z#P3(M^FgpIAy%p38jxm7TjyU1SRfF8({K_(87GzE)hb z*ceC^9go1%D4z) z2Q1~e>L54Sz9HAmaGm&H;<)=khnGNXi$2JOLt6@;v`)kX)+C>Wo0Q$!@n7(l#5%2K zUd|TRtBNaXZQ$CF2HZsdbz*Rx4NOzSiFJ@F+Mb3789JWtqSp>H-oSm#Y0N#-tyK_M zlWfE3Q@lecc%|A_+Q6Ou)Pl=hu|~wSlAykf={dH)k6hvA&JS^1 z=x4m+?M%J4*5x>EVmUkR&A4SErmyONcx2Bd zS}z8IdM0Rp6&tQs*ig{V;<#zEI&kZyl|bl#;IcM4-RPgAAO<5ToI>_QN#h&tPcJ)M zX#=Mnmxx@ty;GKFz`d^u8(2zNR%O>u~ZDy?DilBt|ip0N)-To2|wwb z9VH_nW^$wh*A!wf;s2r~SM{t7r>$%Zga+DEyMY<3_rX#TL%NXp<=S)4&zOixVl+G# zb|>$#J`qb{y6U$j+ITq48nL`K*tieG;RQCVziM`Tx z9TBl6ICocdD)VLJd`(EjF;!-6-9)4G;)-*WH@^SIP;#8B>+gVDU zHruI4dzGJZp3YuO1!BR&pNw$%ZD=>icPBp^^zO(`6tPr$qi9x!x#!b>Fb;jnhams!Xo1nW`V#xkOsL!ce5 zb6kVCo>Zz@7xuCmr1?+~sO{ob3E%Cz!xaDW4^m%dxY+V0FHN1#5O zD#kJ!PvWN8a}Q)2mqxA^u@t6Z7t**aM&!57PQy}|#yt`EEQcIp_3`}EcRNgADaYF@ z_%LYG76J4b9Jjn*ah>BH4ohJg_P})+SxjWrS;=(u>5;C;2d3eR&`nqKKa&~?jS7iW z>t!;(`~5C*cb6mvd`sf}tL-KG{Pd#nm}FkMd5~D`&_SwhWq;sFCtIPxV*{z;wPb$n zs6!;=j8??7lJL6SovZ6LS2(%zy!h!|5??d$2#Kz)5noSC=9gtBla60B;>Lm`-XbHJ zjC(?#k9Vq0!jbvz{EjJ2r5?kM@ZQ~bkcX#5G1&hIU+KmMQsk=OTH1izEE%p%WFU!lkPuf{rH1xuQT`Sj+xn++1c3{ z!OqJ^oKiYj#wnP<_BgH_S6``D{mi@AAKNL*mn(PDtZY?BVtXg(;Cil2C*}IY@88t~ zmclf<&i_qA@BE{&@};NtNk-oz$Oa#rJ5)o{IL1_Tuc_Er{pI4r0X(x5&I^ z)p-8VDizUr^&KL4TJYnBGaE@ow&IWmURiJU@gmlRJ;9ow%$v6qH*Pwa`FSocVkzul zcB8Z8a`{GlToX1<%y(=l4yrvoGjfWWz*4Uq^fl&z344wTA}z&hA!VIhy?7Dl&uQ-~ z#AM0`O-RR;s+eFsgIi0na?usXw_|wGDf||R^Ejiaa#tNWrePcnHsm?qqqj4v6zpYdbXsuW;l)LS@o-OKtMF3)FB_vT)`k5azk%oNR$;**=Aw ztlyA$7ez~$z?wL29^X&2Ql&QsG;yt17*beX8OQO9c&x%$JJEN;J8!uB|BImGeq-H6my5C_(U?^H~~+gGqL z$2BDF6A)O6TwG1Qgj$j6u2GVj=mYnM-_rz#B)C5?5nU;o#1E-JPMnL7Fb#JU*l<1l zGj%A$fr;A(BFOwxA2r@j!X-?@St(${zg-oFc3>m^S^!yZQlM!X5GG*)YvQ?6Kz1O#;+zPRmE* z4$9_k<4Jt_XBWG{5mNW4nPlt!wVDu%NU7Yd>10aWNX^ST3xF_B8!uL9yHr{|{;7cV zy6*ELR`ZXh2MsT2<8?tJQQ#`_`H`JfUL`M@L1vXp*6h3zqVf>dEwyzMYgwjjg^l&yQxy@rQL*h95foeIZ@n~c87m*3>*er#DlTBPbUTe~b&MXM&B9myB28uzCc z-To0)`fed~PFd26TP9`C)RNZ2%t=d&IO&!BI#Om$C8CRBGc0wR#mQ^Lud-{CL1O;3 zV`Sf$Y|Z8PRnqPk7fGFu@fxx0YN^oU0x9j9qggJl1Y+%+^Rk6=J^JieOBJy;Esq35 zL~G8BSfipj?wtHmSUe*_-oIp+*m&h_VtnqnrepQhQsZrB$oGFMlI=zbC2UN{YA-$; z%=7d`2l2{>Ya~CYP_x^7m5RWcV5i%#nWF2kIO&kpW>uNvoc3HWmK^A$OK)w>-k5|$ z28dxZY~}JspCl}Wb5vcg4lSB1w#%y~AElE7oPui!*2Hng>|2RbAC;k3ju=y1g4hPG zm9PVQr>SD&%^C8ec8vr~oURc;>}p)ld>*_&RsPUYM|Bc)k!|J6w$`eeh>6Coi%63u zMkM4AtL-PtbP<=#ZYqZw)e~_Xn80@$)RGMjA~&riJ;!&Iu~*o4zlM=y-I!~dDkoXJ z8s}^xn$_)1?KZDa5m;(uWIXA{f6zSiWkkzgEyRuIwvmA|1@W!VO7gzAItfdQl(6p~ zFK;AIw^@_4DvN>{bi7R^vFZw=ixOMDcEZb9unI#v&%L4NSxHM^9U^ z_RK&zFuuLmtle%>r&lAAVY5`io?uO|dy>XgT=}^Po%MwiaD-S&?bVzmym;%!7WwPt z8Y1=t6WAVjwbe#EH*_-JKEID!&O*IqI_vbKL+%8*(y~5>D zwaW@JX8Cu`z2c>iyDRQ)7e23?LHiy`l5kssX*KaVw3#RdRidGHj6_V}I4})wk$<%k z#~0@Dm8-ajp4y|Nt$Ra~cO_cFIeoi@j?@gTOY$;e!K=Enwh1T4Ort-i+pAhQ>`DBw ztt8&EG-(^gh@XK6_<08d>C2x@1f1gZ`3Q*~ZA^R$V^#6N)5L&}!rt1===bnyB9_9f zD2@+y9dfY|(?7Y$_P>a#mf*L35*if`mQ9@xd%kj~h~acQTv!K z>c|m|J>^INAL4?;;{Ts-e{(ih^1P-I!^drHOQAP@sgT& z_-Tc-Cb|o)eX@b7$H6hFdx&Xxm?&Re{A|}puJ=+M2d1&N zu+QBCM|o0|D=j~)p@?Qb~f4H2ZDstSzt%v=v>R@D?y99b|%)z@NAFb($yyd`5JvRcO3 z@4hX+x3+m{@ioiVtWDuh9556sZdsi~i#R};*}$fpmT zMwH4XSnAiXXlch4Ykoj_m^5{1v~;&^Lq4I;42T?7Cy4H?K4x0f&L&t2)7V4k)gFb4 z<(us!Lr?8e5lM5SrAId!@BxwYOV}8gG)x?S;-uWtFGG&-50~eCP1JP0l%%^iFkDVZ zO4fLkU$2X76)soZn5;1$w;J9XY-v+bI6mXLJY|R%#e@UwBAGIHou;e(dL4zGBZsa? z)@&}?2t@eaYr>M6p0dS&u@vjYw3=A4P$DKK9jL`id&=fAF2I~cvkAMD-6C7fU#ICa zE>*{Nty~Ge4{62Lg`Zj^k=QaF=+aku0!vu{(b;x=2_oZiC>yXW6>3<+e(u7WMgrWwlj$)dXAh^0C0%`5vr#!6}=7W;U(g(>nF+_GK&S+Z;E_*ZR+1FW3h5L=_V^-6KP>(W8!$117LuOmkdDQ+?#j zEByW(=a1UPx8*aHJqK3ao?(v(EEWCx{rRa=Y^Er++j%99;Fj_BBVm;mD?zK1;SyfG zpJWQr^q^-f{9_JwoBn$U4Cs;4_LX(h{|V-h~Ld4DgsN5 zdbdrgx~3lQxv|Ivc0+s~O5a}Ypi5eDLWff<9&M9?W?S>w)myn>+xl-a(pzXVqM*IP zDP17i;Gfp~1Bg}~c@DHXXS}Lu#6Iw~P=oEt-pb~$Gc-63HF3qK$Dg|vrx?nE<*wmc zUxFstnm;WAUV)3h%`p1ijwLI5E>||*^vA|OzxQ(X+Z?1DI%w>W+XbpaK(C;lWK(favdw+lPab|No!7;(;)w7y%N7dTD z`6!kufG<(lS0d*dt|>uyU(wqb??23b!>yIdmxV1l&r*H6rvBn^{R@2@?2f|L@pol7 z7ogo8TFhq8>ET=B|MUi|q%eVZc!alomGy5-ZteQe0qeqqy3B{pKcwVU)kSHlIIvz! zbKJASi%NN1Y(1b|%Xz_ zLH?Pbzh=KT>&@}(cNm5D>iEa2Kg6vt6&I*F28xUN-m zgIp`;3Q2grA6ij!V-vpV^KmK9fw%*s)EW6#NS);yb?ka4(6!)NO*ob@;g5PYNMkmz z6dRWs?5T-n-6n{9c9M2)##1@XORu-$+x5E1{q*)$S6i=3wF{SbfW7)t*qD0LVk#Kb zZ0o#!iZ8`dYzKDc)%EQgb*FxNJ8lCTQ%|zrB_xeA*X;g0gJLO6W83iN=hqzZ#O6|( zWvMZ8T?f4?;v6uCFxY}U77)}Yd{>`f6dW&5C0<9XzZ!7!H9lY zoiyco=-=J`CEkqZvmSrEFYnCoQV1;dxmPF60LPL<<9!RY^*ha{6E6G9%&R8d%aGlt zE-K|=C>xyXaH`RbQZ7?(&!K(x#>&hSEQRT*3yjHZx64q1U*0EaemM7`d-m6$j4-5> zv^QzZG0h`)w*M|SOV%!IwR~@3`Fbns9CTc&c2fy#89R{eKZyid{$l)&y%(o23dLwrO2v`%M?~n@*KSgD$@l z4K$7GO_i5{)I|?#&Fx2eqFm#4(5nTuohkND4{;uPZ-;=T+;4l!SwPpXQ0UV0j<-T* zbA`~hKlGR`TE}E%@jFrlEQM)o8+wD$JA_aE{+Wxr%~W}XJ$VaWRRnu$pR@(9W`ACj zd~bVyrJpLiEy`cqUMRg9>p!Bba?`ofx18ATPiyF}VJs5!rrq7C?*EgRU2Ej=Jy$cG-ec0odU7Nukzb1`E<=O=Hd)CXt2ty1^O>~+ZQJ-h0 zd7NI>hJSahqjH^9s}1a&ZLC~RsNIH#_fhwwl9`RJHi;Q!evMLeH8|BuC535ty0c!a z+#Adq)`jVeGZzW7?fa+|*f{7KqYx|e4y5nDHe0dr!=@#Vr7#U6OWQ7gY+xx&Pk5E6 z*cfTq5^Ov?=Vs3$U%4vT5lf9f9;w)C`o1}@CVI`Rso3Cyccsr?<*Dcz=GsCfg=zS5 z@BwE0}*UXbe zuHO*{DNIAlaD`Wh;@MT5KEb}%OfTE_8q;dxWOUO% zUgZ~kS8UWtsH`HeCXRcsUVrjC%Uzs;?+>hr$+16u>wxpBW^|U~VS}P-yc_HY#=K=a zf^pm+uLg=&W6Rb`!}lQ8i|s*wo?WOA5ndi?SQoZ2x7-QkJo){3X~OpZ)Hu?2hl}&{-jFyuFZ)BR>LrDY6pm2YYl5haEoIb#>U`6VCZr zaZy>T_UaJH=pFS#8VV`N+&Dr^%gY{c?X2@Ar$)V0e&1hvJP`H5k18z#%L6Qh>9xbk zD0JAKald;5R!d4BS?yTZzoL?IyYE<)4TnLd%J04pF~Mx$6l_mz!{X76Ke_8%=cD4U z=ae{=@0ezq*`NL%#Duo!tU~*kOjgkxmpF6M9~)Q-)3&u^l-x~yfcAA3CA!AZZTK`L z(T-YvnP4eQ!wU7FPYO|XN`V6=EaBvD=KI*m$4IV?{@SRt?su89`(vZ& zSykj|oAtFXg*!kBn$%V3J)MGqxSKuTPvrIQx@cJ+b$ru8l@zAo@xw)bnmLO+_msYd z|1&X}U|LO7KKxX%v8q~SM;u2n?1#TDzWB)x@2!Cpoim9QGu~_E_Cue_>*d zZE<=Q>^97#zQAt7n7}<8ykl|is^l)?mM`kAcvTfnoeiGWTe+@NDU;w_hu-;KPbH4C zr5mK+Qp0VqI*!5n9{jO^Bgc9(pLbU5W&DVP+&%iHa;l-d!k%C$Ov9dS(H;NfE{+^~ zrS1*3cI&PXNf-90M*5gm=M~E%gIBor;l3}zQa>`d7ecSTe%MOAg8i_E!_La=`U3234r@7W zx+=u0Iy)V43hoDSF2H=^#lK!*Px|=jz1p_;MhUNQ4Da7`n|ByQk^*LhAorgHS_514;CYDUUuF%Fu zbICL}{Rp6D-+Ul;x3p4500k*s(y{LzW%Y5q9ei13kK=Anucde;-C380ZD76FL)at5 z?WfY?@Sg9}Hk%$$Jh>UTl~@*UQLcCO*hp}Wz?h-8lVamYoSRdb`}&dI%SBp(X*D4` z)>a6X%bJz?@y?p9GTF8Nykf(&Uk0&js2>w;31&M-CeN&{ME;;uQW{Rd#Ee+|_|ZA| z2oU2UEB&!C$yz_U+Yup?iEXH2;~d>bnp96yuI<+CWVt&`|1_a1UF3jMa7k-^^*+;E^yy4+a*ocS^JD#86L?sqxvk+u6D8)snue^&dd_M`;Y zL|j8*1$JHKOIES{)miOue~!IU+pzB6SFuqwsK^29!s8%p`)?f9rrjNJ4aYI5ZQ#0# z=P&Tw$-65Dm6|`=sm|}`b9UEmUOCADr(hzn*LH=dm0KSXP2^aIK1NAOihrZVJeI=r z-#9wnF;2rNcuo#$f;SC`<&-`uLJaSK2|RO$Y51b5ZR0;Bi01(COaY!j;JC#Ze|rN= zU@1I-9;b0#C5~G^Uv$6(mQuG@ zkrV%p0B{N(GvbyHR!6_kk7RzmZs>@ma67Li&V?qX7}|DR!|}5deggPg=Ijd3_25=p zU3b~ub4?`$#yRtWgbs=;3$@>sQUfW4#tdk$88Ao8aqX7)`wNqXnRNljK;@@`ei zs_5RI;dj`1nw?mw-+*4xE=+HF7$==>!trMDZNSDBAd>AXx~zYCjNlYZtazgLu-k|B zKn#I3wKq=oNntyHrLSJ1oZ#X3w1>(=M*sDS5e=<7Dg@SxX?D$W!38wI4w#>YiGx;^ z)>?Emp*C5eO3JFj1!P$j`1S^*)|4Ab>fO?x)YbT3b_VExTSLT~&1-2Iw5dRiJ4Gm7 z%|Aa}C535tOZGNI+^*}JQLS5+c&;2oy+dd>`@@6T7$>E1UO#iis&pJbN zL)xneER`6hKV2pK`h6hU@2D&;^6g2I3I|dwWjQZcG6GM^BwQtGV$6@`;-nonw3Vlb zv{uhxrN+%Z^N&gj(_mx6OmSqxByC^MZSq6oFoihookK9KCiWkkE1qrJS7Uj1v5LS_ zt8eJ@YNaR3tEn~X(%xo`G#(9ls`9FM#8@S-q^VU{dsrY;dl7PWaK=$|G+d&>-!Nh zmcq2!2HOdGVA7V9&@tJ%nE`rT*tFGo$T85wac!S8q&Mr`(EjV+g_=&$pXis_&yQT)GEk|nE+2-G0E>|dvGMUdAT~B@ zMj!vUoz>H%BgIn3g@KCH7Mqg90E-2(-GVbNpVrNzLl*Z?^xhiMmtX>Gf}K21&yg*f z56)`8a6WyosE70u{H?Q0O<+whC$nri-MnHdsW~G>uJu`;S9J!)6C9H|jytdB)31Y{ zX}f-&CgYTlNPYfHo)Ay4CfL6OcHc{1_FUOf&a7VrxPwnXiL^mJ;PgiF9y;8qHWpsP8D)G_V zJjwe=ec4nh=ttCqci(JsuT-=n+r2eqdaQ171yerMY?O+?nqcOxPd54VWTCQe)a-*) zC%re}z2xC40&C*9Ju|aOm8K({UVshk38qQXQytw@n!k6)1LAlM`-<)l9GC+8jH(DM z#WbU zUsAKLS_;#!^B3gqP_stq?0bX6Iwn%i`|o6(jheukIIatPRTEv`-sL+Gx$jM++3&uQ z3l?euYvMR#l1=`}^~hvi;RrEpS*on`FGOBsK9rR?>@F6$uC=ne7|vZ>$JAwht-Kb_ z8l1103G1q5@X8;&vaURoFi&zJrj-zr*|E}+>DHg*^*CmuahN%u^u3;xwZ}CqLcS2=!XLV;$3to3p^tSN^Gowhi#-UY)x?9bwfSD3 zx=3vohEiQzj!ud;;oIIGt|G7|xTEGY=E?Q;@{S9EbkN*boe|XCp%q4vjNxT;@lf+m zK+O+3m8bEJHszO3^8v5gB-G^J7L1keM)*^lf(h4i5t>(UM@?~Oca;62Qv8xGQ{=Xd z{OQ{#eMwokJIigFtkSC{?r$7I#!tx399tZ!vN5i@DZe|pB7bG*OtKlSzd{KnjAn1* z0(!-gi(PZ1emNmDdSp3%dP8%*%jg;8VvqZzyw;L8Pn|}5z8UlFcUkb&H?Y>{Qs!oI zw#s_xxILU&fTUFPyz+eB8Z%yeJp+j84SJFfmt^geZ=qCWJ*=}MTUiqoJ5?1Ed{^@6 zE*aZyxNL3`po#a7+e?Fd4TKqDGQcJb}1pMx{GVRy0*ukt{b90<3i5W{}xtDN^n4A*vF@gvuUQP_Bpg zt!lisdPqIGxK~r9{$yO=Lh2o~R<6e_iX}hxSu1D$#BYs(^7wJkLriWRN1C~oqc~;% z+ZKvcuK!_zHNncW;WNabZliV2mhF|X)aUEAijCJBv?U1Lh7j=%m#6XVaYb_NuRks6 z-qW)L6Ic_>Q?CjYqyI_GSS3!89`tRg=)F;bz?wL&cCMxPK$orEBK4;~bX67NU*8Z_ zv^W=_|Jd?NSp08)a{TltRpgjXeq33}g$GaPLSE&ZSSGZtZ=}1}c`n5%n79si?Kik< z_rM(tYtIwv2yu~A)9FVL{n1}PHaH|rCzuXsSe`c*EAu_G**)m7LJ(?hXyH zN#oc%G*Sol7?wVR@= z(;f?caECt1^{Q`Gc>n7?l=9fJu?ozQ_4Q2@0(Gx6tt@9#oWfTY6{#8>%z3N{b{;Nm zB9@Q1tZiC%xXK150(7vuC&W=sr~o#i-d>!YXmkHnF$BRbgm5#YS4fHxi&Cu0%~2%UsOS zn(R-JaSA4~R_e>+;<-1FyG25vST2hr*E)5UO||-a`=i+df~7DGUz|CGinR)MYF(#n zlCTt}acRP;`=|GHE(!l?>OBsnzSW25%eK3^)NpCS?l1+G@`&tL+Q!3zY4oIFN}dcD zZpmX>O?)|VUXEL8M9SNFtB7e2#w+$d*;P`}u**&12U+{HxRV@=KZnVfkRQ)bY#3E~prT>MD~7W*UbC(q-3A1f!gTa+4~Kvz zI1Os%6M1^nW0$Fk6X+C&#k@7>x>qioH0}}3e}=s3cRZHtE*Gx+US>fY5Q{Tk$ecDx zvwOjKT2NyV{|TfH<}OeXSQFIUK9+L-5OZDmQNb!3Hcw*|y68|a!J6Rfv#r~u+K-85 zvu&t~=m`Y#@T6A=!8Ejqjv88>yvs68Y)x%m&Q*NhPIsw%$1y<*x5)-A~hB~mvIUvTJ4&p5H8=-frxlJm-cJ3NVi9hlCjkB zW%?4dY8XuNWywuu*tPn#qTW$BhmuEA|b9VGX_E`#5f#t!&@#JIS^fqO6Dy6Iv@jF)g;ky7P7bbQIdtDZ`kAA$3{ETVJMFQC)8 z*oj<6f1mTEKhF!woQ4lSWIy9o&;6KS*N>Lvrhi6+{yeW?E&T24dG}^-$|%;gG`NFs zILV361$$kacNB6%o%mC54Ljp)FP&nxYmGwSGs7@}HNlzpV;ir6w|| zOVwNP(~pHKQaJLzc~vs{B~gi2O722$mV}+`9y7JFz8tKme{@pdF8GKQdHRm=NGOHUMG^9Q)11War zT==4VNAh}03!!&=C%(t+0p!u#J^ZU0t@(a6dqQ44c|Jk2x879xB=U@04y<=y;lv+` z8=xYvCXPF_uO7edhMnBwQy~2SC-1$iRh55vceU!YUY}um_+ho`@*8^202?n{*XVA% zF`|}5BWUz=KOuZ%D}II1D1z-ZJuz0WBKCaIq5eSBTv1nQJwro_s)cuD)J*wts|}A`u)OBB(-l6X=7Pa zXc6~`Ty7N)Hagq1;ESK$kvet>p{(C_99Evc3jH?T0|0A+lbW_~&_03n#4GRhk+D}e z4s~AnCKr*M8)K;5=Pxo&nZ05UoC#sidz5ZWY@nRZNAY}Cy~f~GnNG_j$9W^^r}vyH z^3!li>GSzcd|GNvRW86cCg0t8o0^i~7VE2u14kK9tP(_Z*V+!QRrvn}NmH)hiuQP4>anjD? zovHVVMil4OTZne+^v=BJvRRt*yZr>uhOWHRxn)3Hj87olg8gWH4S zT!ZLH$)j@+O)IJ|;|OtHVH!^QTiBI9oZn3(q7i%>`yV{PY#ZgD<#gMxRr^7`@Bs+ZGO!11fnkU#~&rqtU{#bI*e$3 z>H-9}atWl*oeafB^0h2t?3F^Y(*uOJN7Be_qfD@IcIXg3Y<2IfHakP@K$E5z_%St#!N~9;$(U{@!>r*&4Bm`Ql8fnH4V<|rRv9*B8w)c5KP0| zQbRX>#8@k#ML`h7Dbpa@(mq{@bI#5ZHkvg1Ko*9Sr#2UcQXDPL1#8HKE5BOt$$f*s zs{r3Gq?(%<%{)9vl~=f5QWMn)0#YjzR9mywfH2@}}EQoRiJ+{DjkI-1v*z!?W;xXaBozw;TBc`tzf{6?x7qh~7$S zBV#G-q1vk(FlML;V}>OUayppS(vKNh?x?IYj2VJl9d&pt0pA~|l$9oo9Z$b*dLiQ! zOqi6JAyiuL#$U;9rQ^71uXgDwxA3JS{IlgBzx^F~!dF*Nb%roI)s5%Y4bx%U&@#NV z;p6k*M8Tyw4qa~S*DW__ z;k(pVdK z^HnymZH_x&8!ip|uA$VV6)hg?CuqEy@W!d31WT#CYWHxWbZulydM1mgh?|4`gdSaM z^S+}K6ng6w8@^ntDCj?4j&_lL&X`D#p1dQMv|*6K-ojeWxK)z%9y>aFkP}^cKSJ18 zx-4)0EQw5jvzL#wE6bm(vW<*}JlxZzI=?Yw1K9YI_EPupL__*=Hmr>r;3qViSA$>N zdW}k|JLJgY6HR%iaZ7>7-nmPA-`0q_O&dx3KuV2!b@*a&4Z%`s8@-JqiFQMEIiPj0 ziojBKx?thX3nRYnYc|RV>bq95d^U_al`^Kaz~6%N6?vc7odnxc6G!sCXp-EH%R6rP zsBB=GJ#)r&sK)0lW|5yXGUZ20V|4qkgi@S>iSA)R!XclJq-nQ9x-)E!bh}ibaA~5*bB}9e zn!u^tykY@QKJ-+gH4f{BxT0)_S+M80rU zKOLrFe+FN3d1wzPy(N|S#!;(t)bqBFc7ylg5T9vVn%H!dgR+{IERvtxySq5SQxZ-Cj_Z=vPnnP2>AuZyi@ zobnD%t)KGBmd`M<)nH8=*LrPPIcJ+c?RK++$_6GTKM4@bnh-whel#1yU4SwlFpti5 z87F%pn~-kMJT z-LX^toF5>psO-Q8)U8CY4NSv#69<1uH8nHog?q3 zXjL|_-ZLE+3Ev^6el3iFm^$K$G(2t)9oecP#k#N!93RXSjo{=8m&en3k%jWhmQlj+ zFU@)PvepDksckr2zb}oA974ZdDyOo639JcL2z}ZsRe5Sl_XHDFotg+rOKq{-h;Ov| zfHFI1XlvE2=$RU8bw%c}@|`Dh=#}t5!E90?sqdIVSi5VW)x-&L1-Y4%AkT7`L&KmA zZ{D*4pErM-$_A!kSFSy+d9Q9W`NjQ1RW>lKCN5Qbq3ig?h(=r+p|XKJybjNtudLsY zo$lUDJi4~<^uw+9B~X3 zTNi!>8)b~>S%t5WyI39>HJ9QPOjK_(T4+)AeELuSqd@#zRX_q7I!IxA;O!FVHJ@@e z{mbx7f~7DGqYUc7|9DzgnlLMrVyPp|Itsgu&ZqBdzN>^+TXv+7&vh-q zW!@0pBQVg#5@w396xNI9PB`w!jW=ZQ>X!01=O7hE56vKz<}>$dWn8bSZL zqYQNy*J+L`G;1yWQ$1TYs^qI0Q{z??k9|3AVU;*tL0UQ5VS)!`PY{ODJ$^R8<7-&u zeY_31b3cR@KaqI+jEtYp@iR5FC7bGH`riqp)p|S1I0X~xIe;alr%3%1LTMMT7OEKt z{Df_I=47)iP!oU8$=tm1xC8bIKW$@saI)N}3DSl&us+zQ62W@$Gp@k~d(wwJm%ELV zUch{bS#gpxma@O?Cv?bhD><$YrK#CBoH2o)m$7YFGtsXWoZ1;mljj+Cz`C#v_49eX55ZEE zR9GdueT!7`xz;etjqSl2ug^=QY7b}8VaM0Vc!mzo*5mnWI888Rlh(TS9BP`qLYX}` z%=~vpZ%@?E&L2vDCwIf9(%$ve?^y7xBc5A?C;G;9wXgRFQnSe#q2zp`;r$n$zl85n z?cS3!Px{eqr>amqdy4gzAeYkDhxI|-*wrTV{E=a*IRN}b zkDtQfG+KVC&bPQJjNdv^e0P?Ew$?C%fbV8lXW8c>nda$0w=Zr_@ysud3BSRFn)oJG zH)nS_+Sk`Z)s|p;xRro4cV=&N#g+2pVg094+{)lN0QIwToo}4fum_dL4D_XVSK4PKXrxROwDm zpKD9}0%C-S2zO$cRGL&Du}paVvny#g&jEVQ4S9~5s_nIMo37L7GHlB zBN7sNWEO{Pm)u&y=_E^og@GG#(~q~`O|TTEVP(HVhJA{|E~#A;HG!r2yk00A-IAMr z3^c(ynTO@I0f`Uf^f)hSTrEm)ntx7HdQ>98xuDLgvko&fBL)~z&SRvCz)~Magb5K9 zi!^afSAmT;A40URaxJKZ-vAYXr5v6|34?o=CeJ3ZIhp3S=V&S(wxJO~U!%D>qa%&o-;@sQxIhSa z-whfH+>*b=JIlJc3fo(kdJB zstCcx%!y2`F^Z^(Pi4nzgYtZ+^}6FSuGLry)9^f)+(T2|*N@J)aY#jADSY3+Tg!0^ zoyXq}p_jjBtL~_#0~QIox$fjiVrkXg#ny;GOZs~U<>bd5gx9b#E8*r|!qyQLq3dZ8 zx#=t6cRkVbH^HO~DU9Y8>7}qHM(FpsZ?S2BBVM0W2k4i#+VgJJCMxy}>zVXKQsbbs z*3;TLFsTzRt@(Sa14v0?8W()yR)S= zA7K=)lESo}2#M}&Z?M72z~Gf3T1J>f=~toY3HCqTa)lDP!3MKu$ORmqo~SzP@c*=7 zC`|*w>VlqdJLKk2_0m8GLkjb%qz!|IdV>9De~c)p*AUZx<6y-9DrdGbk7>d-IBqhm zZewL{Sd+%emPr}(stHR^`;^(g2`q(ayv7esee<#sScxBBQV2E1P-+^zP|W$lbu zZ3WZS!o)j?>E&)EXxZ5#=hJf2`wcCC_fbEFS&6lLpJn>}a2IjPyVI+LBTL*gjdw+9 zu_o9<=(d%}yVz@5C%TJ$gH{QSg>jn67yY!Dz?$HjpUpMJO=ZVuS4Q;~&z4^$yy`V_cily=g)4J0y!gpo%qmQhxTWgr#oeeg64ms#}2W;RJOl&-{ zT(J0NN0N6u1;Pi)e1g$|^v56E#mM4#VP>og@vJIpuoR{_ZuJ-|anGxEPMyBGixrFF zgx57YlV``5YcQ=Q&P}!wk9ve=jD811LaZ>Ys3*Djpg@CZH8B}-H(|HAQ&Wfo6IjX| zMo!`3?!8rH*kTZs!dM>(B-<1S(;Z12S4B|_n}4&9IuT_p7DTa|R}yclfMgUGkv{gk>9BF8D1 znD8V@sJ`EbxUOJhAHmm3O!4^TSfR*WJl-Kn=)U%v#_8Hxf~7DG`*`)W5)U*kP9IUG zw~D}0Mp==<>goG6*_+sScV4uWxUKR8r`=cG#Ze<8h03X6ni{3I5iEsiSW|S>O00Od za_W#x`n>Xh5oBMe8H1Zd3O6r0XkJ9`AZlXL$!cP+sA{BjQeUx&QKYcZ{-Mix&946t z22JptFqGh|Y_qKEP=c6XdJR&!FBS^@_{4O+KO4PTHmWJ|DY2Ow9`;tnfjz+2*(a zpkF)Mi&$#5(MrLrMj5i%C$|J~PRz<2d14R^9A&1mQEu~cVcX|+B&xJL$3w{$^>4U7>w59mYUmz5^i zo|<_6Hr6E`z8CGVNKH5mTqI~~^&uZ))HFQfoc7OJ_OTj07T8zBIf`?7!ts?t=-jKC z)1O;F&*|WD+~upSC7sn`fQVBtu_irMs2qGwV^_%mh?Fz8vo`O2C$~r*E8>*FuB(Lc z{9euOcEhz;6V&$L443Hh59ALEyi~+7$2h^*c7w+5sh1Yh@Fibfp*1M!`O+rPSGU{HOF!pe6dL5v#CRj%{ z-ikKaob1%;FBiXzlt#)9Dv? zS_Sla_NdDj_3-Z4zDh=M_*u`uiO<_fBh4K+XEf|GO zb@e8TyDt!`*f$|(+}K*qFW}X7qruMU-`(l@%HhIGu>y%b5lt}dz9n2Jom7*Ue~biT zz*sAKdF&FW&!5#co-7O#KHmPK5jw6QbKivuvzuJf^t!MPh^;`FU%H=>1q4p<;6jCw z8+T|L&)P)t!P|35x#{+$*!tZ^eXVHKo^Lb%E!~?wa}5!qmwIa&7Hv~WVH(bNo@_-c zZN28S<()efZUqaL=5;iy`|MN^SQE4iP)mNM9?s|wwIpj@u#h(|-lg5OT`B@=f_rd^ z6}1_9#X0${JH`HDn$0=o!<>_TrpRZK6x`FISp_1eXMBnHwhVUi`3QkaGvdm-`x(&vn-5IL@+m{t=np@kb7^~s?Ov~akFV*+b} zG6&*WpN5WOfY{;^CCrDBe$%>$HOB=dS~yH#P3$Z>D_T(JRC+OZg{5%&_+i3Q!5&8a9ww7DP_HIh(XCRX zqc7Bw)3cTdx0<&n^YjcfqR>W#fbj)emd>6%W*6 zg7u;wGjr1?Lodp4!{LtlH1A^OJGi5U`^50OqtQ6;ep|-C$6DK6LeCYBcELMwYHQ@(&U!H2o!R?roAX+|fgsTf!+NiNCp^hcN3O7M zCsnTXvIb(#mE%H}+P9RH$5l=Wo?9;~*WL3ZVf?h`B?wl6O>R=b_v~XO1=Iikh=6^^ zgy4aN|DpeS#cW{Tv0m&UoR-#qJ>(PnQ%8;otO@qZsQyFwBEBSn^CxBHDdC6j;S!NE zBBE}dFyCptl7e&k|0b{$rg6#YBhdd>+i)LqMtE<#Sh1%jgosP2KKad+JL;hBtT4#@ zm&OO~B1}ZAJ}W$d-OE^ggOUCSKBaZdVx?YTDNL(vbRTMQ^vRKN|EY9{tqxTNR`eip~m$Jr1Wwx$7YE%wF?pU&}#qtJj`PS!~->pef{UKXAe&i=ZZUVOcj#BqZ)A)?*YcsFK1o>~nW7NE~rZ)~@lh7BKPY;922j@McZe;TyV(Q05m$uhlebcM;;K zJR?MWaDACB?CD(|>%s)q1mC6Vg2eeFD@&s*S_`$;o)x_3U(#H>c}|Ckdn?Zh-*=ZH z>yPJwjZQ!N(X-<&$~8`160j7uhjRp0m?qT{?ZVH?=YO;jF|h%1q3`2Hgxf)NY8&~V zgT#*=zv?zNuBEbpJyb{Tl<7yioZQJX42lVA~w`G~t}C&&yES zIqIOx!T|~)3L8q<#F>F+)?Cp`k_I_P=b|yh0yoM_e$|C-xFN6m{v#r`fLEL zYE)JBnPw*7l%3$=j4H0g+u?`~dkcFuFFZz11y1vNBsr z)&lYD`Z)5oL$nUlI2SmsS-TMW-Rrb8_SIt5{eh)04Qn9x!k4m7`bxXTt}5(Q?e(RT)W6>nRhb`obyk>o zDmQ(27oAQ`M4#=+=Ou=U7W2>R@*bxNi9L>x>tc*l>20#`b^H-h(OfHqS4b0l)*K-t z-o`^MDQCJ=h;W@Pc9?4{FG@Hp80|?W-FxaJO!r7k7p%4>ld&_F0^zo{P?#7qMrY}>D}-R@t8(YB8N&IBn~3M|MewcBUs_GH zT|Pk^`cHYmzS3=#4NSW~&k(9tO(fG?Sb5AZZ7S%>2aClav8sH>wFH+xeB++zCeean zV%|Gr`X1_1j>lnA(M*y$en}Q;gzqIG*Qw+=$3yrudL(HwiGqzX_a{lG(?Z1L8hfOX zCb7cIB?+WZ)Jp%pNfz?Q9wC>_v{D^k4uj@6d&t9v5=1`=|*2a1SBBT_3Xlc(y7R;Eq~S zNjlNLwz#-YFN*UA6Y9J&`Qa)(_V*BX*DFVH3XTKE2m8=FkI}jH_Y-_B&sTYceaH4- zWlix+S@&>^P}pZCZJgjCbPsSM<_X6nxp;`sWn2$(wR^T?xxhmZb9$5Yud*R>yB<5` z{4V?Xl;$%imcsP1q9MZF`A+1RA0ukDStQTCU0(FQ?oP2TOjD1cg1OId@}>r>B@4P_ zNc{1(Vt%dz#VJ>&c?j+5Odt#GW>xg-rFc+DNI{T_7JLk^d_xSSS|6a z{Y3iLGlYKLve4yy`5@tS6_MX)Z6|$kiV|M#bmSlSb&z)J0)>g4MgIJnuh3Fkcv#Dy z&v{YXYL|s7eoFov)e4PB|!0i7= z*q6uU^hEzZ$(~)7tR*F)s8G+ncP`4lFIlpMN<>K3R#Hi2&yvU*S|rkwdS=F2WXT$e zERlWR*M4*Blkb^6pYQkg{L$;an)5#A%*p#DW!qGOLReBE;$vaw4L z^Oq@c_w&&0ct(FCQe4AVzHS(W{9Qvu@AIp0hGz`g)gn;zy|}UhVpN;Tv`~-ATbrhSQ&XoVl)dhP2XO#=$$$ z+1R;4)c8=`qS`K0XWM#VhjA!}R;jiuJ%by(=#c4u)n6WWC>D8G?NIkR7K#n?Vo{^2 zztykzhT^9OW6+gzFV(0}i9VZ8oy9l%HPE)Y;4i}x?bcY-_t|T^izh-cP{rV8s2 zQcf>Ze0ShMG;~K*$%VZqd~w~2vi)mIceh$F8Oh7ju}MK!I`oK@9Bt)=tX_4LzKrn3 zA^v00(SA0PZL_5~_463iX_T3Sd$W5kR0a+0alwf*q*t|B^573OQE=4`(x}AMIRBbC zx~<KS`8V(+`6W8Fh78rUKzk4Al0uU3DT@ATj|(+J%(^k>x;h@rI8Eg zJY}d!n}nZIP)utnbl7^_HmNm|1DZ;~#>yyTy{N*=JVM2nc>!|kIXXzc@Ql#A!v?O` zaxR&nu(&R744)uHtnSir`F;ti+YIh zb4;X9XV~o|sz1qVh&G`*E$%W%UVi2%vPfZX!i(JS@oE`p`kzH&arR`~+!Ldej39Ai z>_~>YqT$Wb)uW1844Yyv|p+^~uS;7;_!IScv7 zTP-rZlOfu8NgNeKvmNVi21_f==TqNr+tJj}Zun=oiPYrNGQ2aov)GL7oIAa36~3)q zE+*Zwl$H!uB15_yNQkqVUY%eppYD=^MmN1CrqyxeWI)+$^m^lrxVoty-F&SH`q5n% zpA9yVoVtWy{d}#~Xt#-Eba^F)ve~!Pnv;n6qzUw0=1Y`&B^fmy_)@IXtv9aUI040* zyb>n~qjB0ajI8r+ikl2gnO4W1^&t22J?P_hhd2bJiu{yZES$V?wKb8ruW=hGFsd2$@QuLX7Hy>T z#|xN@hZ`qK#ufqeiS<0`SMCYzKHCn`#}CW!XXgm~DZo&AXAn@K=DOckNOhmgp*yxG zbNvAkmj*By7g|b{*)1|E)y*oSGS^-1PbU0WD%*S;BF*{PT+-hbg{wahrLL9@r0Y92 z;Tlc0N{bdWk=8y@qEEHH&BfEPU&#JZ&T`FKTcxd;#?tpn8*!TB94S|~ofJ#gW5|hp z?K4>?&J9f>(&f3FjA5!g(e^@fDdWgSJj<{^G-0=zJ7y~~y2rK42W|D+pQMsn{&GY? z5c0U$L3mm%0&9OQL)waLQm+z@PYaW~R)z9{@26;dG&-st)XpLy0bvt37j`I%-9nrl`le0>zm zQ9-my)yA#_@8v%fk0gFB#TjRHzPvh>p z{pI2xt58Z{tT^yeIELc~ev~m(uLf!Tb&s~oK7P!QARk24t-6ReFD>Wl#CAJ<*CX%E zr)%Z)esYJXI5b}TEG(J40z(8GeX#GfVm2I9;iNysc?oklhZ#Odo;gge6Cyj4pXBEn`X@p)fG zZQI*h_Hibt#>5Mn8#SGA>WEC#V5nAb)=b9>v>9mcjdPj?on|n^m9HlyVA9OTHtFHW`F(9-=7MK1LYiHJ%|x8ZIC;`wrB)ge{iavp4s> zA8rVPns{-1p*(gH+dEV8J|s5Nd%dp=YqtI)ccZxYCnJ{@q+;<+-E z4*A0RvHi}~QpnCKeF(1YAr~ylL?4Z8#NxA4Io)3!rf9d&O6+GdhSlR7GNxl5nbStY z+5CD^7IMjp7F)*Ez)!Si(B~W~zAveSi^v&t$@YL~li!3P-0xSR?#~dlpKu+)k`@Ig zQMYrK#d<>8RC!aJ~Cw67`md(Jp`#>_PK{C>h$S^cy4w_hS+}M zGSPWohvF4>^2Ze?kgo1Nv4v=dVGgewd;%r4pD*71(w`v?tbIaeNaN|3`ax(b>$S-9 z`Qn@JkF`)9tP{%yvl@_BofgsN`zN8>7cn}L^H@B3t~NGqa13?o`&Mi}84DkKn{ zVLXSilAZje-%L9{+Zef}_;LuC86aA@qw1En-(X`b9}AE-UK+rbhHVfoJFdoXqz7{e zyMcH>O}wo0Om$2?KTd>*@nicSuT4M2SCOk(f9P$WLGS!X(;79ripH=R;d`0c8uz|e zwAeTY=^u|1sICrfW|D(ibiJ-2^(rw$m6}%M+V(cuwT*q{VOJ7Rp8Gbzp#3s@dPpL2 z+__Bncs&rGw>ym5&2J&rdhEjxQSWTYq24t!&2oHX7y%&Ff}BM3FkccT2Lv)i{&Y2| z)aPO591R~!Aeu)6H_F1%Z@Od#Ui9a(0qixH;n;0Aq>}c4NssjBzXQ0~ek5-Jx}kSo z^cWU_Vc)PZ+=JcPt3T>zKKu|M!*+)V_a83E`fHAO>fps5TQd6G50GI`!5-uhhvT1WZ$<=XoO%)dx1;}vZ1<^brZ_Y;Th-b^yHlO)7NQi)(RI1$0?sVJC;LP#cZy_f(k2~|w zdSO*(-maj%vHUUKown>L;};ula)@0FePCdQuuw0Tvr1+q-&_a{w-G}FmvFJ2vl2dk z2sXsC`lHMdB|b8=A83itj#a7|A0FV;L8^?U^VvuSyv4&&4IF*2TgIANXs6eyC7Ax= z?F!lwj2P_XuOL%x*tO>wK@0(H3ECJ$vz3|hHErB@>G+Hnyp=%9fHua~UtPGb)j7Gw zF6?Q5Ty0+oI~}sFq|Rh&k3+ydSH2tE(SI)VvAxJ<4HA#a^yT=e z*sx)HdGpCLXyu4p!Lu#GtLYgOeg36pmP-$OZD$r5{jEUrV6-K(_KWjO$oDhLGw1F0 zm0=FQYM+3nEJ+c1hgQtz8QUF+dv;sxDW|2JT|p~>HpXV7PIM-tbo*-^jeTXv7b4)e zOQp)X+?fp7)JJ=*4If1z0&-$&aTZWKG5cudpZoqY9I?U($6Ml{6DzUjD96lcvje!d z35b9rS$0;K{ta#KH)k^MJPY7*6r_UVV77De*9ttPVFu~w(riYbmuYS;ft^u+^W1)$!qO9_elcyd^^GgOQKT8pKS>n0O=M_;+@)HJr18mI&X% z*nJbiG@b~bM6MEY@!B_2_`gtPW>{^!uB z;tN9K_{$LzlWe7K;5CIu^Hju5p?X!iP*iQo(y?G85>iwkeB5J zq4O+d40mL04;s|K8_)UEPKKTXsi3E^FQa;nT>0Nd5J?lSp3rn)*Kz*OfNKO%X4wuh;YnX;<>^d+L$nvL=fzWCdW1~Tkt*#FRa*!K@dJ+kjhGZMLXsXTeheq?;kMT~15 z#Lb@b(Wgn32ITA7Y;4-jmm876I0!kh-8Jt^v?(7N61~oT+=vXe8{fJu--x))MgwAT z!&ina3Tw`{ZlS9!Ze$Tg-c4G_A>iCAM6>T7HA*t4PS`{`qa+)ZLC0#J|BG^ytq{1zi$#HEqnf+iS z_l^VKw&42?TPO4I8wq;SofN(2Jqr3Ad|P5)Opf}JCH9si!NOaHc?rHp!*^VjN_+Y+ z$?Mje%r@cQYatcygY&d%Vro=}T(w-n*%h=BD4UG{PWuvi!je=m^Ohms`@fH&8Uu%m z9X8Ca@cxmyv_DDOJcQhdUBK1jZt)?cyJV5rrtcEWTjI4bHOQ4(^U31D3+2I9`;h+1 zC{ftFocjg^bFfO)VR;=AfyWT<)J0r&hI}C>c6P#7%;rYi$lD={IRyNg#m_A@TUrHg z>|j7bf3h!F;M*4T4?a8VC9qRATg@WxuP^2h@GBWavw4Q|Q?PGd5c&LNA(zkLcM2Zi zA7Yi-U7~}AQeQjFV)jtYd=n&M}8$PmZ9J6h)9w$Z?}>jX*Xit2kQks*Y0-? zCysUtImE&iH>F*J+Dct7tj7?|*87A$(PnNLLC&xpJdhWp;$vb)=V{dNe0P#P<_D*(jsq#VWMUjlIOQ=>RTs_Gj}j zCu__QU6#ujdaz1Gx~(L)#G#~1pLsI0aA^5(28o?qubEA1wwXj)YrSM>;n0g9CpNws z*OS!y8baEcdvVqdZ5MK4qrNYFaP;92;+wEghPDJpfUy7Bjh?QHF{+zD+UCra;n)x& z4jx*KE;V={=C@F0wvT*E#WtG_>92-;{u^F8>-u#o_}E_yL`))GzOidRB9h7r~1F!OOTv{#6Lve~&G zC!68C&JT$6(Un6$z7Wm!6-|uL_I9mIAJ!eu)#HqBlH}06z4XmsJ%+N``l}%mY0DHf z>7Dl$!LcD6O+uSy?*_-m&}Z>iNXK@mXlsWY6o1uE%t$z+%>Wj@i9IJ>br9LnqRiSK zoE<~=UYtQp{J(SlQ8nNkGRPk;*1lO2L)mO!(XcVp%lLJE$H*0=j1>j8~cD<%Tb*^jXtEW6L)%cVu+yH zGR?aYL3}$j=MXR>b7<9o&uwV+UYkj0=Wa6eZ7!b!+3XaDvqtp#>nQT$Xm>6$Km_E( zc42p^MiW}c5#dQc8O98l!(nb`Bbh13$V`$=YOEi}jTzuvC?88`^lD&nej zLj)g7qD=zGyr&n)$UjrKcx8R)5PI`-hnRMK9_C}oh#Uhld&_k)^pz_YeY_UzMX4LH z=?M`+p!vAb#S%}BN>d35Y4_pTHM5+ z+}qJEH)R=0&tKw;>L(gW->xpjlUDkohM`R)qif5URhVonkghhS3>DPCh2K zOdPDWZ264Do4Lp^4#E)t9}~ZBA49{eUXZKG`W@2P zbCL{s!IdLC;-UXXZ2hO0+?zdBhV}|=iT975R^RaHVm&&)%_t55qXG10wx?Pz12>yn zo7QhJinCoPkN2qfb1^tSuMVxVY9xn%>xiILvaF^akL^1d&`k#h$o{VJ4b7S z+KaUDicWIRrPn1VD;wz?TO$E&mmg&WA6O~+{`^Bmewrx5RS$4I1ALogU)*c!(8_VG z=%QZ+GW@E?Sq88-_WfM1B|YH&m<+gX%GnjniO|N_Y3##(k&B5pAHPP=hhU#bwtp{m`8Q?B)2X%rk9%c;npqP zA8-)GG|Lrp7R|!ECBFS;NzQpSrhaY%zKq|O;kDZJ2WhfooQ;(kSHHI67!yL7a0JMXiCTivC^#~EgUVgKHuDj&K=vF-W}To$rk5Ph}kxA=ja1m?&D=-#`U4aC*PCC zt@F6m36L+8$L`0i+K46|>_@{!PDF%_gmsTz5=S(?u7%(JL*ld0zFEoQ00(7;{&rkv zdj6X(b*)`Vh8YrOPPj6Ht(x4~kXrb)qIgktF4sadjFqg<9gmV#13S=Rm(95K3~-$t zj9sjCjXVh^jj2uhK3rsgF$%^mhIrvb#_X$0b<+lM2pB*3cvbkP1^Jj_N#E#nR9*z9;;x+JQl zynC`Q>X2h8xvOSiI2MJR*qZH-BiOvR9Uaial3R@nqXc|cXE!@M-+na~{PLduUwvs$&L}ECegIQFiy1Oe(oZP=VeVJgzdoA#J z=v{2)j`>G~R7iSWIg6l;!na?3)HhbQH@%x}NGF@UlAs?XGruz!=OV_;3DH8oVS53l z_M(2NuSp&6=bV2)+l9Wu=1ctZ$-G}SG}pPF4A(@EsiZgi<_GfoDyb|{aXt$xax6t5BK=PYB+ zcHuf(|2F$jwUT#Y;3OAjiF*AcV(2W>ufvRGSOTpN+A-70t}$sH+Ltzb)10$ihzNYV z3grxHE&1>BU^069f5m4*r%}P_5x3vql!GtwxMV9il#IsErrG-4h(a9qwG(Zpwc|Vr zS~#?PcE<1U2e_A8AG+DGwG5?0z7Wmk8C*hexQ+u&zGBQ-JG5|q4SnQPXZ&c?AnFli zAj6V`Zbk^bR7)P~gD~_Pc1HZku6XiqnU4HyCd1qZsUTXVIz1~c)8@29Q?8qH9tFJ! zj!{)AlO2ho^xlcOtgb9K4eTNNY43t|?=ucmzGh zClh_?)wEX$=rp^~kw&lgtzQ(CMxpIjx{S@;+EUel_WTV<=rT zo?o*KJqn`PJlwsR#JEy7YGToWTdfX9nSB1Zvt~94xHEzpvo}b{7p@D3{-{#Du0D`N zwdzLKMR(+U5c(aI$97?7A+juc7!`WelA+&04}QOC8=6wBp44Edvd$9C=trCvInrFi z%A5?S6_4mq)r4f89!-boSK&Mg%7eRySY)VSOyXmijM~*?$O}?IG+Qqk^Bp^((X>uX zbs17YuZ7;sb}w5U$Cqo3q^#eB`*8jzCpu17SB6w@d=0&st@v$} ztWCY)NZsRV$r!paJ>&U%$sYG33GrUSb+<@_8Xc&~kzmoD~QK7e`! zwvb`IgI){0S*5yeQBT@`o}I|$WFW(xArQ?Yf~F&?%IiSqTx=;7ZoYutwsI8>*M~= zJgsuIk_=0rB|>f4jR;F?3m;BSplxGyWJm?abG+>yA8jn{zc`w9Ew0H~BD6lZ|A)<_ z{^}s*92rf&R@RfblAR+pp)*V*@;0)}`1o=CHz_bZJ+ z4G(9bEkT)L%yz1UR1nQhDvWAOb=&l#+3!Yj?@`dZASbpv)3FhmZRtaQ1nMA%$P;Lv zLy>3|`$-%79;1ETpNo~EzGz`iWNT9Eza<}fJ5fi|xm-Sn?`?1`H=Bq1oj^1t?)0X^ zVs4c;l*eahC%*`?_p=9G>=ePR@`h9p&AyC|7s=XWPugj0EP`VLs5`$d+#yLKqdjI) z&E_;zWnmQR7T#LA_I41rFO~P&^Y(p7iad*^TE=sc0rG{M*j}=eZOB&rS@c&>DklT_ zHjEf-FLI66B*twnovyQ;LktNFMZv?YrDmV{RoE?CawHZTSbEZ0li0ZeT_>VWO&z3n zGx?btIHRLdRc&sAcP7oIC+=$zj0Rg<_CoPrdP_g*OvBLURjQ)O190lN`PB1m42OX7 zAey~LwYwl@Pjsa{YZf6m9$d(FO@7g_lFq7EVd%l^7T5avQkBPUbnk?_2$nzu?@_%6 zTGOqoJJb43BIh5_+M%zoj8nfS`4~2jMhAu?*lTbEsJHeY^6XPtI^(SDySw?dKY40D zlj=7}`i+_xNr!_*Wk`ZlxJcrwdvH0$;ivKC#lBXbi}RMT%SV? zdBkbkw&dzQZ<_VOmqS1*Xff=@DgAdiw)R4L<#_;?aUhjVJ6|;ClO%m`wP#u_@vcga z6Hgjxn24agLIliRDplD21NeZ>5^CRb5*qPn9tsHPB{l6LV`wG3C8l&7sm&;!M?1{j zkD$fHdp1Y@b9+hGYA(VsuduHfzq@F6hA*PaoR@P5XnhdPR^2zw6=WSR`t5BT>i_Ji zG$l%u?$!yyF#GT_E1oc$)j5-1OHVs9)pTakN#OX;acdI<7`=QBVLX7kjYj7Z_RCG^yX z<_MNRd5{xZJ9zglR<-n}Q8T7W@C*nTKcGC7YCw-lB<cl*kEnNTHGb;n zL+t{)Ab4s3j3qF}u(sMP;hAfe(k811As7uHy2a0dsB7DPl0O>C{6iSdEhb`QF*o1)10CE9IPVW-kuPfyN#C)Il1619kSkRG&h#jt%~yRmgL z1NEga*8uvIdPRJDH$n+!m>CXm@E=4P}4rpn;#nhphtWRP_!Cwma-W9?@p4fmEwc0PTM` zn3J)x=~!)tz8xjEYrYuv4V(Q?HIsJE4WPF(Cvm&`p**N9%beS6q#SntXYlMi5uP9b z`9gW@ZKAM;G;S6A2Da$=`It*Jz>b)G=i*KZ=iHxrmk`1~>LAti^{{cWO~ zg$Um>AQj9$D%Hl#OUV}N#nkYdxd<&0qItyESB<2q?6&l=F3D=x=kVkX*#GQa%i3ys zGS8BhEDsVs);W))CELZyG5qWYoE2e+Ic@0Ryx!DhpQ8v7uod{Xy9*II)H8bm4GwnT z+UmYv7Mf#E#1+h=V7sw7vW(U=zji-b%S#p@6_f#Gt5oBj&m>LEmrzZSmh)QJKG1{N zSAd)kctvM_+F)*O=CSaVXkeYL(u?(42;x#Y+rN| zYahN2psk0j5a4+-33W!Gr8oLY4$tdh7=u-+lpPt`^>5hOq7!Fv2uKCxsZ@Pm|HA!i z`qR+6C3diea4f=)GO8vo!VOlk8(ekQ*}>5Sq=F+H7E8QO;`90b^lPJL0vuUDG(Ug! zC{H98xB1Y)bsGyX3&X4*d3ihP8Qer_yXh4hExDOWq-3)X9Wcv^LqIBvuN#oTFm}pK z|91@0u(dI1o#{(&EV0ahG9VS~S(R#UVJi~&#Fu{9bXb5Tu%96(wt}vw63W&>ejKZ8N4sbE|2 z2x4p{{Wuvw-OdbE!?THCi$XNpOQtf>njZ9{Q5iJ|Y*FZ4g{_7n)AZib3Lh1#`Pgx< zMW4q3v|8O0b}$z;OK}^ z{oHke8X_PSpQ9e^x0PfZKn2aO3|ImY@KhZ(i!-h}IeFKI9p_TscFg9;Y8((2E}cf- z-FiVFRi8LD`YHC2x=*i!d4yG4jo5XiAC-RT5m*8d(5Bf4dGG+y*u|eNy z5qvpWj6M=Tn?zVikSfTb4qD}DFD=0yGi$5*q&~ef zwJupVZK&Kazff$`nrLP$+k_$7CjEx^=FEKcjSmVU!0<5outCCW8qJjtpS&ru(U#zL zD++&GULbxPK1FEf&(J>#MWb!WLjLwm3~||IHF2co;>kw~WLN@aK-ntQ*$b6v2WpOY zZ*}6df|{%dyD82emZjPJQqjtJZWVg8ksYbK!cm4bga{~)y-nz_-9h~)kgd7-YN!=g z5735eb}+vSX|yUIzl>cfLn_$1yo{K7#v~&wp0r>)q#**f8$`3+9N&}44UZu5M4m3g z5{MW(@w~XcWw>ByuhcwNs6lm;>d?l)LodOD@aNpF%cDNE?KVKIeN5PgfC{i$#Ya#7Cy z44L6Aui92y=r?c+`JuZO`SxlqemHRqFRHp0eYwo;M>=~9?`pjUO}dh$c{5f)NJZZA z_uIu8fnC{72!Mc87md~+AI2%cNkN3)U5GY^%oT5VES9~WuP&95zVHa%vTY5rW-?sv z9>EjOtSS9}&tXRyA}I5@v}fV6%>E<&Wk?0lrx~YXm$Ed8tBx?llNw{>YtQFv4f1Pp zh$@ZNBAwhU&6bPDD#+LuGhOc5GEDf{I3GQ&TUPVx*LW(3W@kXme@2uu;L;9s*<+%&fM0vi)v`S;o)@v25wt1By(kdVzmGZ2#dKtpQz@_w-%G^26kZnOk zsf-Q_QnB)!c`-|)JVSYG?Z-ceCv$lOq=MSAcg|VQkW!B!&0OfWeLK)nCcTyQTC6-@ zzM7>`o}oN;PxU{DK@|{?3Tn&dshhf#-cYfewb{~#WionIU5}M#hih3H)Z1>po>IFuKn6(t6mFD6BjaRuAPF%44zQA4H{QJOWZdZB?pFgBDcJ z&qsUl?f_avuS`aIk7#^3dpjC*JxeptBnG#=7lTArC*6@-S)Zep)#yh{b7At_an$I1 z8KRd#42OW6RH}EW^Jvl37;)J20|b^pzSVBUl-3WIM$um0K6KjcDD4?*89}O^HMXPU ztmfHAqA-sr)OykjBWDX9SJRPQ?J})WGI=V9W*O&HUAlMEDy=qqBrTA3qlL^$4w>!4 z8|v?3r^04wd^haENuzh7#q9r&e#f$!Z@J?@g;5@2M65BLCGABESjlzAB<#9*FS5yJ zcP%YU#)A#_An{g~CS}F}hS=dbg$iyxwLii?5J&~ly|ed~a_XCv&Jc4=7SoKF4eFE> zAM*9yK4e^&r76)K$EM@skT;X3op2JL9v6oi-OtioXD1yq88(aPp?lGpo2v#BNCnZn zjF){}sZqO3VVbsx(+W~SG~4f7vpcQzX|#6edn>N3U_JPnuUltKA3hlUy!v7OsC( z5CyO6+T327T6(8N!**pc{PLue_!r9=(XO^)E_;^dY((~>0!p8iC{q3lq|3&}A$`{F z3PO2S`a^kM#ZIBV{iN*wY)`dQ?BBaml#*?ETmMA`(QI|XlZQ6XkMAkHR|aYYHQ^EE zIw^Nr{A9WhW7$&C1frE^7naqO|CiAZ>XBZ0(+1QE@`du)DC6{Q>rJD&l(rR=0ow}7 zQ>k2rjzz7-m<)ZprSxTLS$u7#y zhtmpb67^3%NmG@!sy)|Dp0lcvt$vmJWUTuU^x@W4QTHjv2|JIWCl5agYx?iOV+S8Y zuk4=-V}9&oh|%-hvLY=V>1x`Flh1|W!IKYcb;K)myJlM@XVs9m!Q38aE(uL&Adlq?DE zpEoiYkC|3V&oBL5NMH#>w4AR&<_Y=g5<3O)njxw!zTSN-L+Ax)P=je(HB)YFz>o@} z*$HN|-Q@NKp>{3n-zTt!jgO}xBfZOls}PN0i!h62ts5TLKiyXMK8anNhI&+eBn%%G z!%;yrTYts0vJBXkzF&2pd_0zpVs4EQJuZcD2*`=8hx2ihzw20Kl-w-j5RmG%X&MR| z{!WPhw1d^WHPcFe;zipFm3bME3fcnO-9N@nHdSrNh<3kEAl2{Z$I#`ZPr}ldJ28*= z%w%+b8EWUGbD!v+N=LKZ0!26XFbwO&BL*`>|KH1P>oTo4>jPE^<*|96Id1ZDgIULC zRO4kpzBQhtqj}Y%#ew~lv%Kprc9S>1inIGvRLEI7wD7Yvj-i`RZwn#qm8|CI>Ly=n zz2NwyF89gTxKw0vDOvCum%!Eb_svw)6J-gGHxDwzdJpCw78BC9HMvh<3Dk<0(UaA@ zva7kR#A*(y+~=gCQ^QvYC2fG=JOWJH&v?m`EK$kuQ#@4UkVANf@r9%N;TQf zOH0TC~aQ&FE8TQsIo$xOzEBo|b}ega*z>IItfeGj_OxJX!YDi|+u z-i`LCP6^XPL-2ie?&RYwcZKA8`x!#FUoaBP2hoqi^<*g`6>TuvEsW}x$WcKwv-Sns z&^lLJy5V4J4gsk)O1sdCfiXf_4dtu;{iCmqWbjnTk4@TM0j64smF9+uNM;XiV?BB>T@$8B#%c6WM9Oef6w_ChW9e z7DaXQ(4d!V$;Mw3i%{c@#;Co5IO}=o^NqC_X$zBPA>S z5x1!j)$4E#53T9S$%xw!iyrLStTDi$m`BX7`An+)bRkXl@aB3D_FB{9$B=*K7a<{F zHr>wxx7TB49eU{*^>-}i$vA-}xJa9RHj<$`jOFoDy zf6f=Sty<2ZS!_S)MV71|L&xfUBi$axqXb_f3_iCELj;t~e9(M4Df;0=@20#V+J`J> zgkWLp%Pkn9c|_5RSmGmD(G)Ke3aKD^+>ZqGp525UTz463-RV~kkO>{z(+<%cDJ+4A z$N?Ipn(igMU#Xl<`SqrjtR7jJ-Zd1DqXqkIff#aP_v4JaOx*nl(W^6> zLMn)!P?Cs_UT7fv9Iu=&s$*S14t(<@GnY-K!g39AdzzwYfj8hGU6asF^POtL?tz#` z46a!~Y)&jA-L#3R`Al`Eag&Ojcwf48Q+Ss*8aN94|)LuZb9 zm9f3sF|^v%1~+%j(u7zh;Dw*9@WE+Wn$G#Kc-hGM5xN<`rXtG>= z;kPn782G6>J@?6%TpV!2l+mAnOyeY26 zS(*uNHdl~Q&_Sfmt@q-A6L+9H@Y(GkGvN-)JE<+Srqf-LOhrH}i#Hq!WfA z0&-&Kq(+3IfT?rnEO{P*R1od#tS?0BKNgy{Q^r@Djfzmmvx8{Z=gXW7)j3PM$3v;m zb@)NdBfe{%qh&Ap(FR-cIK-9ZOT^7HlZA74*i*{`#3Gv3%`O>h=t*@`BW49c{5CJ){-2(}tyfyv|zSYN^ zLv&v5EJm3e*H~5w!h!E6WiA|@tqI(w)FZ2&T7DgEPWA?MppXj6<7MR5ZN}yR0%fPH zMXBmKx}|aO^^SGeFszvv$D-Y(!E5k|(;9IPd+xGA@$<4@pzLvGN_V$EopC%Xk+T!= zh@DoY&-9a*<0zfE8h=5dX#x|vhzz<5KF8c+_e#aiBK?J0F@v}@uT$^$P zyDL?8@~F~%l|xxcXWxSuqIpCI&k?0HUst<98brX_LNpu6G#gcl*tcNsQAh>RunpN7 z7CjrfJuB3v_V2DTEcx)t3VX90b$if3to+}KJ-=eDUWRBFZD>>LKM+cey2B6<&EA-6?4#7}f3c85R+5eA*DfdTR{L{8n zt284A4l(Y;C2Yf}#v6umXtsZFR+(1aesr<%v$~8YGODXfR&rDj&Avf4EYm7^X=ko= zp;nL+JH?}QS%2(Kx3DpIcnR+s%-;LFqqw%>5lau2$6gY-puv_q??w?c=fA;4WxSX&YSiB&+&`7X5UrY*Arfsmr9vu*hVqn%7$~n)*GpHP zKHo_pE$%%RY;)^k<$1htR>--oU;4c7@NjYMu5nC;f>8b{KZR=Ht!3igFC$8+Alh`) zY|(xA=zkC;0VlebBStx_6>oSC{uiR0lR_6LryW%NMR-T*i1S|7EJZ-H5V}KLYu@KS zw1S#IL^-E28Q1Rrw~TVWO8xfc#fyuRq<>^I8F{~Jc|D+v^7c^>e9cw2?*FYv)zjAE zuTB%V7KJTcrj_zn`N0z9SzFg$SZHcriZ17*(DD7@sJBya8r`&%3L?sT^WTV{k9~y@ zO|yR?$~l!GMlQ6_C{GnNf#}mr!;PI<{L@yE^$hzJDel`;g`%!X3-v30HbbnGQTEBC1(Pq!Y|FDwsR;*Yj9-%&v z(e1yqg7s*u%@o~-wP!Mv@q$9F{1m?a>xt-{XjG~RtP_tIA?W>WD_D=mug+>F>?o^8 zd7Tu_e4k&vUr*fev_xC6-9|m4Vpb1>|IiBZh4L~!oz*Bd_HP-NUr{k_!-Y~A15)(F z>N5*UpA&QHi*pY=V=Ef}FRjWoQ8fJAv7z{C(5L@EKq}Z)&RQNOD^WPT;7l(~4MU@zgLZx|7L3qu6AtY<+ zmQrm_)fH=etWo;B@s21K_8(E^A6z}|j2k7!sfYdxaWvaYOtT#DABfbNJA}mLm9&by z8w=kFgAPC#yDyot?e@qpfzN z9~9$1?kuH(@>$SU6iWtqTPyYxieJ*deGQ_7! z<4WUIMNJ@r*Xl>op1(c_W%O-6N*p%011GOchA8;_^(e8GN>oQ&E~SEqa!zH4n97g; zY6YnvdeePtapiY|f7;6SmS<^%Q|eJ(qC7)HpC-k^n}Rd{(Yk$hHWE9ws9UNPMDvJR z7yACK2Sk)pDe}6v%M#9wP~vVy+l9Uj(f@-`?5eq0ZCj-c6kZTfPNn>xj|`R8rv8m^ zV|BvBwf*f&eXu;@D2SW>wZ%G{beW%5)T*49LZy3rq+nM4P-!caN2RjJVh*NvN{MD+QS4A1+oXTWa)^GH;=8$hWm4Xh<+p4Mg;=q6O zAdKhJ244`0^~+*n(lb4=vF4xm4_Y|?@?X1xZB@&-f!OER&(eAvdA?D6H(vZFCfba+ z@wXo3C5k2xQ6Blq>e0CG@V_!36^vcw(XI@k{8fGmUl3fdk8*u0*5iNI3f2R*+yB^=qSX|8hrc~oUZTi=mRO!e|6PyroT?zosg&pP zjQVfeo!inxta^4-skOsQUC!zMMwDBIBBR`5{;d_{3+3^MJd5Uktpr-)==%Ewr>rKW z8uAE5lJZleLn??aA8RRefwaMHzrS`>UZS9_d-w^(sm)4dlyfRWD1Vh-MJkBC{`XzY zBjyL0H)Xi&bvv4vn`_Ad(?m^;#oO`p!I|WQ{W!JH%k^c=gT3opl+6?&G3&HqIty6hsES18YjQo9!X#cl%eO7LG-tsR}bx@tTwzN zUMEF*&hn0l%Qyt2vfp!@EK92+j7B>d!u2R6DeMIET>V)@Rgg~JpY1GM=(LN|okt9a zJW959oFS*ap2W$3=*;j0GQnx4@XY-!lR-R^$hzw@<*IW=b22{YrIXKTLxt|0c4HnP z`$Q4{khyY?&fN(tfe7#XH1ht@0%6P1JxoR?jW_9>x^Uen$)6vR+ltDu0_meyEnpwHiFdkP4!8R-}?G^EV1! zEtDDh-$}K|p(I~9uWLMqfK;dbj*^#Cw+V?_Wt~j%-IKW2Y=8M@RS#Ur^$6)WVW;qY z6OZN*ogydVSBnDV!|J+tqIU}Eow8eagAzG;kP}-Me$oZ|&k2xcKW@Mw+Os*bJ`Q_? z{8cYFv`Q7dqLa4L&j7hFBsUXML3wB54wIRU_XvjR%B?8bdX%w z)?FyJ`HBM#6G&i7Cn4|Q2OQq*VsC34s{O=J!-19wLvG_rL5P-FS(wjp%d z*aPHn-X+bSgkPMD*V%F8TTVi^Q}zmC((V}Tmvar|X@`b$2*?-8V{h^E4@-el&E(f> zWUd~NFONuA7*7U`?kDRfR;9b&Cy@=mPiwZseZ_UZCz5C3_tl=aKH=V7lgN$*JvBB< zzcZ~uv+rh_ws4l;dwnIa-C?`ImS$}gCgB+$+~l7-*(wFlQ;-VwEVIO1A5!hBqg=`H zCxNyE5l}<6&uhkRaxlh4CUf_22uM|BO9Bc1?jh(eQsPw|i{qp=a*Y)J)Q-)-ty3-Ku^L;>N?<+s z{n!aP@#1@@`lPs%LH+IJOJAE&*tbwC z=r`;JNz*_wVf8>cd3tRQ0b2p0nMYO0AvYckl-+i}AXU8%ky=9vH1FPg=IjdE8(Ud3 zqJR`yviri$YYA*oC1Txj16hn0-ZT{|h@8#F25^i`D+|il5s)C(@Z$da{Y0 zBZVcVtQ9T<2dXm`mbG*_Cl(nZ&x_e_7sy&_CZq5EBvF5%uN>RgjLc_WmnJ^lBivb{#t1ub$I4a4h;xUqtnHh82gj< zndzD~zn|ijx0jPvk1uE(?!93B5tbsMuJgvrAyvPS-HSZQ#*Ig83kNJBRqt$4 zPl|hl1LrL!8cRLl@z47VL2KHhxZhTC>lvNti*pNz)7S`&6MD=cASZV6mw}bkCf8TK zRosk>W_@m>Iv^mwLY($)C8@2uUg);&5nk3LlKeikL+~_y#AG~5wL>at!9=hAVqtC7A`I)t)@%>>COwTbk}XUeD3lIu>3c*7c^+P@dDZPT)2iXx z`_hb}iE?rK@0<*%6_m&B|G0ckI@;Jv-j=z8Yh6h7d)f-}b56KmYOh#gmuZ!e{R0!( zw0#dwE7(?0Lv|N-gJ{V&d%m3Dvzb8agM6VpcK_gl%hIY|E##ku{VA-WrvEAuHM>AF z*XS)Ca4Lf2C*D;jCMh*v`zcSlb*!yi#jqEJC9vHfCw4lFQBUdXP(L~Mu^xe%KnKd$s7XuHbk@Af!C!-%`+TiyTNU^9)#@%WwW(7 zLcC8iCpJ2r@&hE!U zhaxyx*gpo`1d}+As{D}s)zLp z$>a4L`C9S;a-^v*N${~2K3%)d@rCkKs&w7Y(#FG{a{YaWI0U3}E>M$)0p@}+QTEq< zi))E4x=fYZ?0raJ$)pr-GGmiQJ%$~w3ygl?MP;Yu2JXxJcJZ%E#Hr z``hV~>R0^evXC4xT<0cUzb#exx{s%VXq9S0r}yOfmMPT6+K}S~(FIZ0uz}HLq0<0G zhF!D~H3{oO$3*Cg8)jX>>gV%>ufb6mQb9E9!65^wS@Y&Jxn&Ow5hj&#vFXnyLc1}pvgLd1gQ#rVbnte(s6bcbkm?%)ScImRrN2n*Lrkm~!fVmxK?dQFzm zrV5D2FaC1B^BSCGpb;SAWp*)6?VF{Ucq&>Q0`z)*}AXmv9J3HGOO@er-X7EsYh# zxSOj5zs#-Tt&agRAQpR{Z4EIGaym0_YT1jtx^p(x0j!aJIQTTec3#r7)yJOsv}}o;)WxO@wyyu zq1lWOT;ugqEFQV8Uc6ta`Lk>Nf+PFq-)iiBki*t+aFGDJYCq3@pKiD`C1%EeME8L=5P z*g6Tn@8B&D|MdblTz*DVayb}7G>`CdawTRut)x$bmdLQAsNeS2ZecKnoY?Mu zTUU90P*<{`?NtPIufOF9em1(ZV0*b@&3$re$#=0H9eB-1hArB%(-VBic7hPyU?tZ# z>@C}GI0=hfN{^tw4;h87NO zDO5KPPY%8=H2bQw)!L_(sF_J?ik~!*=ji0(A4$Q&6lNt*Ufu0ia6=qkr#TElW1r#X}>_o)ELR7*-oZZC$8w)$YE^O@j-Ma^P z-^1s7Jr95AUT5yt9aB3qJ3G5j>vTYQmn^`{QSPv%k!-O%nmTvBF1AaH)_V3072Ulr zi_fPzYFpcfiYzhmPZwcr#rn=0wU<*u#b=I>Mehw!+WZB|yOy*4 zW(igW2~vdV03O#LOyhim6@Xc7h1DMpOC~283pfSmG}Z(ofNK+}ez=7+cI5)5%yGS1 zb>q3XxLUlniKygNSj%ww{=KF2qMR2~+p!In_>#lX>HW3R!l*?|8^ltW=D2b#){0#- zOY!;b{TQz>;pX>JYMo{n9|La|_x?mPGe*kY;(OA!Wne_Bx zU2G52a9+lv0-9HKm>e_7n_}y@3~)>^3Qv-#k5dPki!o#FQ8*4v!;=P~F1_@_M@}>= z#gqrmH*6bD>#>LvJH!r=cZ@X?uoUh;a7-MR{P2gk8Og zzbjP?7$LWtyP0AexGv$I54`GFSDu~PQ{FyvEz|d5nk9Off0IlWK9j!f>A;MAFoFAH z7-e*CBX7UHU-~nonSlG(Kf^DHPsi5Kp2=7tvc!O8rt*~XoIIq44b!*dkrU1ZcuVM6 zTiMR~nAF<6k+5@8wzw}>@1ngMEMgnjHk?&lD_UwgH%u(Zohx7|e)M^fV>NFZ_fv@ZH)K^J?*@yDk@FZKjI9G8*yaVwQ=@@22sV>hJJQ!|q)D z-Ahvw*8?#n-jf_0+l)WieTlfh+EI*y>oacy#4C}W#5HZX_B;FzXN#=N)sG4ZN!e7w z1}3mQj(fNxSKoYozJp=|>%s)~mg5Sda`g+^u4umj2>*JMNP+ng-OqkY#OpiGi$hvJ zcM1LxDEir+7Y9Xc)=m2w2wn{a8`9$ODeHj1QkcfJIj(a|uD;pY4?4vwOkk;FJ1>ZQ zbDw%tM&VJc79lmclg5ynuK)rLR-T$ZNs8<^v4Y*3?-c zVoe;kbWg5+TBT(vN(o|JcVLzh1GAK0FiXKS%u>Ndn{!s8{Mg22XdnAcdryyi8`YcRpuaG3d2Ke+oy7r*Cz z!t`EMq_5|%5Z%CFF8IqCPW1(%)`C1Sczc1?W$g+P6Ic_xk-H^V zKXUMv7Asuslp!JMh!FUL(YNvDcuZ;6`;U#Qfy_kk4iqE08 zyI4900)bPoz1okTiQzRQtwo9w#~H9u*7uOpN+56wCSHAiA^LaOq}`vT5Cs9bdh1G0 zQnmoG&i$2me%Cnd@+&JuEQM)UVcD9iKiKPwPKg{7SgN$sYjNrWOYQ8NijB^(x%%3! zbJW_7Q!sG>W=O9-N4n(RRfyhD6Q8%Lp;KximbwJ9u#w&1JhFQ$M3y*|{#5^W-5{44 zP)p_xF_*>_oFn#Q*;;~Y564v)m8T#5s;Bc*uz|~zsampLRp^taKl`qR z^DH2+6s8B>Dkn8={EGB?t=tVNe|)GP>s>xI6$qSyiKo_OC2gzs#5_|W`8>9-tn9y4%IvLGfzHxcg$84W|6z z`LJq$2y7cx)ogP0e=m1;JPZWx88FQfk2dG(pL|PBR{D0o9~Z_a#xgiFb@C*hnem&!6%0lYb>#Px}NZ=K^<= z#y{@qu~Zh&WgjJwqvg-Ry+3qN8oy_rtvu$rv-|-F|0&*N@LPYq3{u(E=a9`4dHp;1 z{dr7(@?pg&AVOLs^0_0; z2OB>-%_i5Lx`^1`QLtftbQRh9xdYf(&Y$HMMEe~y*)*Fo{T53b!KMx;Sq4@BRFMUbE%Va}P;a z3b$a~Hen>QGL4s_r^@*j7bT^w74-~Q3ey~yV|TDT-9|k4&8+g*7QQls|vreW>X0<7<#K9CYRFYMqX4;Fw@c?cGLw zk6z($if>SgGzI9{b)w9IeU-9+|ajk<< zGS<8HRhUX#9NJrtX^z_&SfMy_OmN=}`Bo**MvrM&9lTemn7~q)X7lQ_&Dvv1d8}XE zI|=9LzWhXK62y@g6{%N#SFVlhA|Uc|xy@A@(|o+nY3dzcdas`K*Wp8^0SCmif!YNjL=)xGunMk@_uF8!sm9UzL5`wF}b z)VkMh^_}y}aNTmkKD~BlfV3X2J<2Psc1J*qVgjcunq`oh-YZ0gY!ZeDNHMJ{=z()tLht7idVxggldg99b>#we*Y(0YlDWx6_&ZeDSt{zk?+d& zh8e3}!qy*9X_oldW?8X~B7aK~MVb`N|JB5jQkX9HCR3;6;r};LB&BHT4#XA910{(3 zhn`Yu`7B+=`&<|0I>dcGsUEvruUxN$>!a{HYonwTra!{FSyh2H5TW(F)b^2gUywF$ z_)h#=+)q=kUvGa+xCWPAQioBzW`Q3}?J?HM9p zSKie@xl&TFUgIk!e9V!$|35ac6sEgfG~uiN?gF{1#;qS7FKVkWE$$ZAE0!;;JjdLEUP@DA-_Vty%&+qg-FSQ7q zDqyKP{mV;R%DyD^-v==&p;%^;=V++3sx7yP`Rty?D83)!>YHEu#vb znF}Y~o{kY4!)nwfbv3HPvIM^VYg4&&?ht`~^Oc0RXNbr8sbb2c*-}j-k;HzUBli3A zUVQnoG=KB6vRdofYb@U{%13i?7MkW{Cw^gS*`!A{p(soGI#t!E_Pn7 zh110XWB4t8#`4?-BV;T!%k7MKc>Nc$vA;Rl`|Y#%Bk~LB{WlMYX|ch4fo*lUPL=+0 z*H@9^w8LM>tNsoI6Ic_B$aaHQmAlC|S2mOnH{2tdd)DInmrvE=n8L{BK)5$~YCrg`6ZDCh_nfXlYwi&Djm#c?Dh-~v*Od7i z&JOZW7ke4&(u*#Vh4&Z29jubZ5~U`l@gEMhm)Bit!`Q%5n1WrKqgE*-FMK z*q*DAqf{dt>^WV6IEK&go1CN@zl8A$ z6WAVn&+Bg}A8^Y=3T(baI04oNS-=+zYmFAM6sDnXe;dX3sJv3@vUxs3U@6?@VV&XW zO5QBWLh2W~m?3bq*d9EC4A{@d=}t?(rc7h{65P&N8>=3iup0s++%QDZrTz4<$;^hO!vtG*2UOBG@LNr=`i14NS3%cGZ_Ng zzMIk9Ja? zShrny{scS)_k*krhlMHpnS&;BwTEs3PQm$uV}ib9>>hr0 zxry?C(vN8D4;$&RS9$(?zywix(_Z>JuN0pYIHN>Q-R;v+zGGR9{BFNS*h)J~8DBn; z{&U&h8OH=~XNDZ*PyXs5=cLtT2rPx|aon2b$^7ScE#(zPf`FsN_Hayan(p=tKGLMU zTzgbo=KfKBewZ{ZJDY_24ij;a{bpP#Mr$MN+RPLjFAyANDk zSMlOB{%zzGd2`+sic>Ig7xL}v;Z#Bf+dv$h(vR}35@*Vr4ka>P-Q!nDmb3H7o_ifd zmUv^epMPaEOEw8gVA=;Juszr(^J)`+J8zM^mkeMCJQjJHw^HJApOMzyj^I_jh){m) z3m>`Z0D3?|sT`Z;+uA8^7~Hmznwu_suHwb8WZR=&$UUwJ}EbNU{F=0*cd@yJhe>>7o-mEinc?ct~kOL-sAk3pM%@VH50{D!@ezGnx zhas>O>y^pV0KPI11#>5+e1KinSCxQ!(r zQnm+-!ta(@#cvGqk@xs?lW+=-33~|d(NEgNFT6NQ?z<^osslC-UNYi4v<*$i_OK=x z@2)w_n^*FXr``H2;c+{rSz^?N1pez$H~Fr4IT??mF@ZInxdEt2*o?pQnrw&zDww1Mv zo$U>4uVF7YsVfr;U^SxoyG`mkY|)x5$Bo!T)TbE=p{!pNNhOCG=m`60{bX3nP<}U3 z*D?}}`C=P51rxnsEkhw%t7{ph`*$fOa0({Q!y3nYAet^w*5T$>uUSms6if_+9#tV? zphtywGYUvCF{_Wk_vX#F=`n%h}#jNQkcfJ;cIDi4Xd@Gakd)liSjg~=$Rnv)r7)0 z`tP^VjDR>a|1x#M#9vGttc|r*3|?^`Y&BRfws#VqTAzBDsdH+e>=xPTU?6gS+i8^N znZY+Qb=;UbdMx!6eowoWsrxWlg!y?|RYM#)jjcvG|H|fxVU1N;Z!KDT#Wbv6wKdq# z*Jz``DcCF4#(Z-F!QZ!K2qh-`T(v0Q;Emim2I7av64)zD!-%Y$f$-kePJ^XN#`NDB z@~ajGV%tDlre5Jv!*v1P)vskBqBpkFC~L??YsJf;_U(YDuS<6Zsn3LqVuJ6b7MA(z zE!GTyeaGH%+#IM^O5M%rZmYqbU>n#ryaiGC?SZ<@>=+x^cdSY2bNmJCsr}WbWJ-;j z53A&}pZw7(*XKTG>Z*tQR95r1I7R8g_CtGL*UQysaj~x{qXBJ4;txTBxqESXC!cH5_I4y$;>!Jfy; z`YwNAt*?E3!!^9SWMt?W&h)d@U|pENwxMQJG}w4i(e8iZDDnh*2B7+}*L&c!9wkTqdp6O$s*ht! z$lX$FzL2SQZbZ3`s0cRVh7u+6B27w-^%tBP)^g}$v4|nClyY4TG}TjWJU(J6ti9A% zTklX0VRg^D{J^R!c-JOxh_vyldcDS`G@tq4I$yB*3%St-)?c}9M%QWh`aRksbgF=* zyndWeiSvET`4vqssKl9z<$+k)WHb%53`_q~ut*pj7{?C+8`1FHmVuZEXiXUm^DSCYAW$(u^UnCOF}5&z5}uPVM!7fq1qERuQ<| zf@adT7)$Mx?Tdws3y;%>fZoi%4fqP%Zt0clW}m8-AW}8$rKD%E=_wCEAvq5;Ox!Ny5w; ze17IK64$$eGz|2%JLXPa|1*+yU$Nl(ZTABkF}s4KdT-&|o4*$bSeN-Rr&VbfdtbWXSI5y z6z$@Wl4a&2V5vtd{)xIeRroQ>R+J!WRvIadi+!K+ysD3YrIzRa6)PH7;y0HIDnTT6 z9xZj;+s--b^CAID;mBF9Dx4iIdAcr7JJi%iICQSgQZ7veFZ8OFp-u7nH}%t%IfM&tEvdoaQ6o6ilR;n@ZOfH{>hKpA3YnXA8-9 z+bZq4Rf`2IwSPbbX~D=wyphjX!V(D|jHKkjpVA&bTf(#tT-$N$g16899u+6l*0`KE z^<&x~ZnZ42X|cWdDQTlisS|8F&vB`$_7eUfc1)XxyTK+iaa3&C^ow`=1T2MniHN%m z`Jd3vkL&HAotyQyBPUKa)t3Lw5?BiNN-$T`{v{os*{9p(vHcY$aNh-W*Ze52+uu07 zbwxh`rwn|*g8vSl=oq$%FKCQ)#wFGx}!M@Ai zROJqkWU_*^v1y?H{i-iNZ|-su_w=CNHoQ0AdsP4s2TsHipRV0fr+xC1x2{~E_OBn` z&u66SxK$O8SL(qhH(LsX>6d+^?N19QZ3zNPZ8hp6HtX4yUp-_I5Cga)OzJ1J0AXff8M*J#*ppyQ z9Oo&;liQvrooj*(EVa<=m3jvlWc?VSf)>=(p8m&rg>94@SV3}wx^O#v z9C+mzFe>e2kI62dfxs!4XzI#IeZ-c$yNg1+eH@nF+GIf5cpz|!bj?J%dcO(pdSV>G zn&27alv(Mn#*S&>Kwznpy-lTnmW}!F7bS@>r_Ox&*KXR@$?)Yj=xfJMYQ(P^F_zJb zX^v~2dyt&ZT<$EEs8_i5;W`Fy#ry0hc>_h~CMD`F&QZ2~WE7;6s|}MC!H41qPlQ{T85B2<-?wHsA6^zttVgyv4o=VJ&8zpy6P(268pZbOGQ=*{~n-YM4-uZi?_qZ^A8+e{MXcbw$OH11hFQg!$u8B1Y$f7B)Z!ro#0Rx2HN zWs>1R+dnv`P0d&&;}lFJ)-ue(=D$q?A}=YDeu?g$-ZOc=j8i_>zsh?IcH;wF(+SoD zXP8bpMEN~J`b3vG@=f;~etp;w{@rVtU;=A`H30q;oxWk7_Tawha^I1+_zUd^@i(uY zCYWZ4+{UNr=ry6*(%#b^2 zWu!0-Yp*_L!i~iHdKEFmV%@S+9X9`~*TBW~gnk^1vvC2XVH(fjI{%KYXX#vXiUbe5a&;(E9A zJ+7t#mcn#hCqs=%xdA)4xYC_R38m}QOgpr|h#|1lFFV5+<}AmQAgruJtMFAkp>f zOUf+O>0)=SvZ`WIxZ+WCeWgo=vLEj4cXd^5&8}z3n22{ZmC68N-2D(k!yAY1n-try zU+`Hp2C1a!kF;i^{)!6W7!;(g$&`odmx3F3RsKU|m3Updl0$I+_bSnP=sI%V#!uux zDr{;vxskbBG=l4miC2J_^TM!ZslB_3nsQ9VmEVohpeZjif;MLZgbhTb7)^ItGyXmVJmhZ*u}NU1mnT(+Gy!5&+P$vS=+!F7S- zD#rdS&Ry&kmclfAPgv((>=kYYxP4SDWg;qh_^yi5m)MvMR$Hx-11F>0)RxnA#zcap zvNw-Ve;?9uE)ZuehZWnv1h$81j%!)NshGgJ^6T!^D{G<4+Ioas#QNN4J0~5H_Vj5c1$g*ng?zWzB9G7`)O;feZzm1qnnA*eD{%p8^DCL367Sp(n z!TkJL!{XeXQJuzIQ!GOyJtSo;FuK^!X4C;Tgy zSfX)_x@zRTb0#O_Ji%W5ZSJnN|81?#fQ_ExrWD8Va^^DrE7Xj3Pgjyjp?Y-$FeKia zEHm;~e_vW>U7=S>Uow9ClO!Am_OMcAE7jY+>yv@lcluSLayL-oSlZD{?K4iif6T?~wC;_2_$uY2t>p zr0%ZP^c`HUy?YRdg^{(3Bgc6XHC<1X6~X@3@<{z$Ltef6d&P`YcgIXUe~=tFwGLCKPnXyT{`{I zD|hEX{*`&$&$C2sMZKFG{i+ya>lyR4Sk%&KS z)a&!#jd*Mu>W5dgVy`fPrLb-2MJ?+U6JL8csd~v;Ge+;V9vb!cPHRly{!w|5p)Yya zeQe6eIIWseOKZn(4X>cC>E7>Z$47n{p#DB@wk;6tuTN9^l4kt^bOAnt)%r7NYBfH8 z+FrGW*XrMp$M-Ido8&DNdu7sWib{O{SC0R2beekob(1lFZuVLADcQ*1W?*AOt^eNC z`{rb*i6J*0l8^K5sV(Z$=%*xf)g1Mn*y8z1$lY7!4NpW6b-?4|zIj{InKsQfU)?O!Gt6xm~wf0uy zC_iE^Nj&MRUI)i+BP=mIp_fYZ9~*rf_g600)~nAQ$0ztPeHV;<20XJb8vD3B4^gGK z#sLHqb;4Ju_7dDyfLDgU!hHaU&^U&xwC{|i3=Pk=Gj7?6=_j=fuA5xZ0TWn?t%+-{IuzR|s(mGE zBCeruir}1PY8=m>l+|GyxIMCMu-X_i)rNF9)8X{Y*=k$MN-ZE=j^0sQ?Sh;6WW$4- zYCEsj^&7--`JP54jz1;Gac^+FakeT&Q_7a;8A79)7MBNZ&)7rOt8u$qs5V9nj84WW zxG%vT!Y)>QOV!5uxCjkS!7*V?(C@}`s*N3jBNI7}c6Ekf=fE~MW#_=#y~f3Hg!s%< z^D5fyAHg{`^;F1s>BZ(XDOuV#1-dyGr!CTA9Z*OYHG7FD7t`evDzC#HWl} zJk|tfVDGD?md99|hW|-c-QYFF zC5Q9nEpLDQ`Pi5*ao}`__L)ra-4D{f1SFU z#^kCMV-HphmIoE@pu?*J*mq1rJD=rUT;`a-QWhVmYR`LSEAXo7S8vs;b+VBICa_fh zjqzG_#Ui>n5YYn-Gy2?1vmBINQ$=ffMQe!44l2A-2;-fWS*lmA_BD=U8(1%16@l{; zD_>BF+>UD<@EQr0ay?pBuXx2ZZUA0Ye)mr$nst8YfKxP&i8^9U$gRYzw!kwM-*#%f zvc6_<{Qk`q>i(pIcWd*Qz?wKNqPAf+@h_>VBPQ_p8q=`<>Y!m1-di``0ZU;TkKtkO zpo?LjWyMa_9dQbt8?fW{HydshmpPti;CTW&HwgZdtd@Cf51k{Pd0`sQUf>?J+t9b4 zylSt*y1Jd5qRy%IZF)r3zMiOFuO9ml?&r}qHH%v>?^H(Pn&4e+5rPy^i|Hk#yQQw=NJDK%FymE(Wcq?V{BQ;sR#gXGxXS~w9&)Z+kt4mHkkXKz}3~S*^4~N%Yu@t7^tgzd5#eE50p~dUs zc>Nk`d%%A)NK9aRn1yv!#gxPFXVOnz|}KeO-CN+BhG*MD^;;hz<_;DF7z0 zCOA{JPmSU@FoF9OwlDem&#-Es6{hY!vA&N&iPwuV=`s-*wtEHWb1<{68B-_BhU{ zkf;!7%MjR}GXJO)WbhXD`>ZjzVHuBa#3@fRvx7aczi0xq-dY=qK9OezDFka#EP-@J7 zWj?cq!K;Ns?KHTgFroZDb9qtST@cekZ(Qn^!#darcro3F+Eq2-pCo)F%5~-z_{vz~ zM=}_4T`8xWw;v($mTz0=pQKxBB7sm+Y=O86DVS!7ofB&dLvPI1=s)*X2}RdAAo8{c z(qT}7{aznZugAQ%;(Nh0oLMuWwtC7;o9R!Bz>}= zKYuY`JM2C80iu-47Twko1eQ|l{b!@Yq}qaiT$$AF;8p7ft7uKff&3MzK#Qd?4bQg6 z))s<|jGb-1^%m+Ghg0p2fqdf~%^BaZCfF4QL<^_aPECNodNI9ZdKf+SU;y7aqc=pJ z0(te<_Lc4sc!dcpHKs-=9pcfSZ+3S&5D^f$RIsi6N{Ae%OxPYw9WM9bdzB7hJcNB@ z;FVX(N~dNeyuw68*C4vdqbKhKr#*1oqgl0uN7HmE=J~8wSSqE(3ffWEjrZ{03&bz5 z5jMU;iuc#v0!|4i8%TefcH-OqODN&hCJ!i&;WTAg39m3w-)cEcKfv=@9YwHVGrhL3 zr&9&zo9}uHIHlsmWpt^LGk+{7tAvd|kXPU0BT}3oudvkRtpRj*e|z5P_vI2q-6^$& z`yc-}J^I*Nz*2Fy{b`Ra)_jinof3r45& zrAn=W9NB8`R7gAv=#j8@mF9nl9m!W{)KvrBeANZ|uxBzErrJ>Qw)@+g%E(WsvQMJ# zENZH{emb3_2O}S=Qf(HWrS8UW3yH~ASCXr4kl~#;e__y@Q*?1lGhWe^zv2WXPphbO z=*dhvHPKl89cJ`Pvy!7vRZuF!_t z`kP5FD~2hv76JQZE%z_n(fs@}Tb14B!;hMn`N*sgDC#dxb6UyDWs8(WHk%w>O+$cQx6h(;Z zE~X8{5&veY4P2{-gN<`f4Q+xY%qw&e#zr?4Mh=m*c9!Sp_YTj<1ZdkkEzZ#{Z=aGW zP%H23x>pdoIwrk30pdr|xM25TmWk_~~E+(<~uNp2FA5=V`&^SS)~Re^H}d7Sc?#fE>9yB1&6DYAV7R5JppkwDGs;lODU$ zah~8@@I7~hh78)GJ9}pol4hf6pG6S!7_R{_(6&i7W(^_wBcQwoMm6`aO;(VK4$Nmv(_!rnp&Zl5Cj8`YV%v6iGeCoj=?Q8#p>yO$Tg zgNOGHHY7nc8;DpF%)H)C5Qw=QwLEv7A+Qu{!!3Bc(4d(G-T3DL)6TICY#Ua#Uyc;I zlnLSaf>JW>8L*U9`-^m6Ot$W%eSOHQ8sprB{+a9fkiOp-8(0eWD;zf^VvsPlrke}b zqKb^AG9hxW+gZ9#5zUyM2-fsn3~K;SBkeR@Z=9t&^Rjf3T@5kj>?!BL-8#81Rw5SZPL+rAsbOp-e;RA2 zG5vF%mV26|du(bWR@n<94k(X zt9-j=b9qAvHib2^sV`2@M2Pm&;_2d_$r;oFq@LCqE;=-m=~1Ymdk&8V;vKB@DXXcq zJKAb+N|T-<{R?Ho^%^f?O|bXF*5FmHBWnW_wHs&9Heh?`UN5lGV~BxReFjbn;nV0o zsINEMdy3U1JvD(^S*e|$mJ=F9vN!;zj1aN?>T9-8TdZw!!m}zn&6~# z@Jfke!?`w^+o>>Xgb0I?9KUL!*;B}t1}N(!}x00>6Dmcuc_PnFdYYd)WsJ5A||jV z7-bZ;!LR#lHMrg3_PAcYLLWiC8MmJbZSYg!nH*cH*=g!GIYl|BiJR|DV(JxJOLjXO z;uv<;hA9tRnz(G>yOz-VD6O_)Z#xZ6!3108=`9V!LO6{Cr{KDTYbERoOEA!TksBSFk4dqNkaGIQ7Dgv4IKPufV&OaE6fL)ooKd4er&j zJ+@C=^t!Os-nC`=MBESJ{up+s7uNQMP_J+=ihF9@&vV?V_J%mR&$VUlwU}VESF6eig8*DUbV5`AWn7&oz3T*_Mu1!gV_AwDoHd5+t zl{h;MZaJT>T%mDrCp*2zmbt^hig01wt+AVJgP2&J0ydz(>OWPPtDP)t9}ga~1eRjw z=f4Zj-jQJh5MZ*Ac2CaI)tj(3eROUl9ed1h%@US{=U**OvDM&|l0-pjmQI;d!znj# zZj@3>sF9sY6s6#P1#5yCOW_G-$Di72a4zEBhaCajt7*vHs#$hSd0?6)uDcow!g6!s z+G?acsA3v@73fL6q%IfvlWFvEbvQj|&@!>i>QtJ%D@*6&sGK}Je%WREqtB-F=_Z~s zmcsPU%rt7;b2J$>8{T2!c0RHa`i4H{4{g#iHU_mwrIRw}k_r!kL@6kh3YHs)uNT~j zxHZ2^3)cT;@-J?UU0uiEG&Pbu>Mh0986`P(+p~(~c$@VFsV8eRqVByX_e=_Sv zB^i5y>9j{FbYJbQq*e!bvx;+CG*Xy&{2n3OO3PRmmclg0b?h`!uy&75^=xV^V^6SD zXyLU7g-Ibn$A7kx3+QT{w3 zm9`wYm-uEc7jIljq5aw<6RosNT#}SZ+x>|rrrnfUGQZj*`lpS(aG_=u`R;rjeb7@T z@fTUb<3I{s(clPqUR9~>^VavHi+3HO*`d?qc?n18#x)`t9}q5nTyvBjO~@qo|AvX; zrepN^sgopRR2UG!K`p53g9CKTtr@aQwIkHLMKXDGY?X*lW3Y-DK}TgP$W_+W+Qqnog_TxXgY!O4@JrO>&Rwvtrm5D`l`Oira4H8+wQZIw8} z&RPpj4z=mu?@sbsA&rvLJ4oYDHg{R#_hb*D%C#5#E8q7Lw$b(*)bPg9r0M)%#vbgM zsQ8e6N?JyV(`Xr&6fQw*o8wCDGo$W*N6{TrOT$$^nSA4vsAk0T?&cs>L+5aSQ}Qatc1X9GeM`}n7WI-!nWa^pHa@j z@>i9G!%-Kd*o`T)gWEyUsz)&63HFfVl5ScGwzpddepa~*v3Gb14Ve%}a_+M<$2D$~ zNuQ6pO$V3^Wa7ZShxALOHIHPFJ>E)r)LgKiuI+T4Zksz?#wnOM83Fz7tTV*4hSK{a znv@dSg_IT^!?!cA6mGRFF~%;8>RMN)vl6}JwfQ=_`o;y~u*+Y>QqvmhXv3__#B;pT zUpd9SruBRE5?YVAD7~Giql?<5kanZlQp33bZ$S*JAavc?Pat3VGX$18`BO)KwLC)B zSSa@oADG2=n_5=r{;z|KeaHPH_7J`|;qi)I`RE}0wJI-TuQ0*Zs~-!tQ`1V}v}3=i zGL8`IZEJj-Hu!Rl*MrhhqL6qbs&>(P_Jgi(Q2hz z3Bw;)$z_iwQ;S;?xw&G)* zVSB8NyAB&@74s+b_RnFm9Fa&v|6L%d<%7jn&l73C&DTi{`0_;!E}0&!nM3aURlZaG zby5udH}Db-a394GSc=Un_vhWHrQHZ&_Mz{LS8-L7sf$rENj()V;`pH7{nVY78^8JgSiIm@Ql)R}D$>_!QU?yC7K0n&m zS1?)Rz<7o8hb0mkhte~H$_g*;^<^T*(c&5dtLO8Mif5KA5xUfRB;s;TgUGFq9wTqL zl4YLc6i6+*)EBmzQ5oyPxq!2yw{fW7PdsGTGo44lOFUNn`qTjD>I~z6VpUaH+9g zweS0wJT6Ct@Nrg5`@r^C8?p00i%a{B5Z1IclCdY4U~|{mvlZ>}#7wwmJy6EFuqW6< z_~zt2H%c?F(A-($Wjt2Ld4*|sDs!$so!aLBO?f(v$z42F$76Vo+ZLB5`nfa`-Yx1X zhZ-HDN7}`cn-^9wIf~=sxP#pt(^{OYD12=_gt38R!uH^8j(IE6J+dncmCg^6aSA4| zZ6IPl@!iA2sY}m!@`9*%YBM;F42p~p@mvIJ;<(d~UBr*W{e+F{+(nDceQA2w6cT5B zM6_J$Pq&7Ika~Aw#f?*j(RqR=nSCT3YKi|lC(*mKpV0aD7IDw^QFNj>kJw!~#Ly#* z`p}GRQ;2=5!$2Ia+efUv-A^#Rl0woPkI-`G;)uRgg!n^ylr~>`n4Exod)4?DHSZly zc3)HOIK3D3740MZgs*#kkXLn*X!L`l)>P_r?i`sK!1%r zLgw%hBGv@wUrqEB$L1~-)>hlhzgQkak4)PM&uBL>Qex6(Y8<|ejAnB=4>q!%3SvzioR{f+G#yJFS{zC>BO^)5yxk&8%n$D&x*hQoGOaGA zZymRm&h_3%X3gEfNMRbz)2}l|91A6Qy>D6l`HYqHZun|ardvAWA#0;rub$$Ict0Vg zg3Q>!Im!|~egnjxJN$&Gv#ZJZfCKc+xc%g0qqR(V;BtZ|)x$=JeRqOaeI9DDUX!W2 zDY4y4_H>D7VuGES0VBkNF@A!64X4M}F@fWQ^F?p>73akI35yntB8Sb6(;qoXtI4nB0a-(lhJcn zV!^wibj&O#vVV345IqXui->)i(5U>OGS-V})<)`qqf)n%orGg473BT5+~|=<6G*uL zk?|^jZ4Vj@Z!N?RR=f&J-YQKF7%Z&%^j^XQmipAM7xfr8k?a!`;@`50QpM>Dg|f>> zOE_hM=P=sTYbu!l{UFu^r(X#9;^Cn_!lm8qBrJt#n}5Bj*}f^nuc>0A;g37g;V+g# z+nKGH+{Iqu9Dz6z%gJ9Fw@#@ucbJ^ zX6fFOFmd*qxpWWMI2Emo8O$0NuIa<-IZi3~(ucanXX*OviV(3Tc&cCc)rI80wwj+X zzK(@BoR%CGG2zg_n%>zB&sDpw1{>am?|NDyhHKg@_O-h=vH2a zH%6*wYyd)E_+^JOS+*LS67)EPUk7j0B!50AVoh)cgzZrEX-1C`BQ#uUGyZ{ZmhOC+ z10p7{CYWt!2dD(Sd4eIZ)XY<^eCI`Q;{T+L;8oRM^OQZ7a^|s4$=C*#njLtPl-&#O zn;h8$#Iw19@NH***|*b4C!Df+!b8$;96XmlxKYf5Q{@^i%+l?sst~tlPDxgXiWP#K zuoR}TJ&wybZg`vg<_eqRSn4d?-}iWD=^8KFCt`1*XZYZ#zC~Bxs@?JMC)-E}Sf6u# zpNI*p3BJNtxYwW~)I?lrxD0Sz;JBl849{4GIoL4-mSStk)52#(!5!>0xGv#Z$r8H@ zzcKRH-d2NCFu~T{XN6CZANzFItmWP4IcPb5GBds|N5~O?kSs`;(QXT8l_J0d!@LVfA8ru(I9EK+G%MhVcq} zQh$3Sop(7)Cs?I{SN{s1j4tuE(cqLel~&U~*--Pdlf~4Ut7zLxS-QTi#}%S5uWH-c zX?iwGqFL~~_Il_M7$NVW1$VP_{P81VLCw812cF#({7wMkKw%qvImw#w3fp6CSV0_0 z-HqD?JA_c~VktJS-uN0KC$FqEq3TwfxY~<|} zeNA>z&s(rtz<*B(;!fe72@mKKo$iIx^ov=#*7K8?o|BE^dEwhj`E&6~5|eN6Y@+b%L;No*4VJ?8aE*b} z-gK=Dy=bzP#^+Hq?Q$(k*QxAU@&3jg)ClfA{W5}?T!2#}wj0WPd}u2TmcsWa_KwqU zkKrx4IJ4Faf$gy+=;m&)(Yb#c#;c`f+bMjmTNjwMLFDtI=u5c1I!ft96aF7t=N;G6 z_doDAC7Wb#B`c*6jeG7rW`-P9~j? zZjk!1zn`e0+)bokERV(uoG(mXL9m0Mmny)$PAv=-LHzS@&tF5^^xQ_feg z-XWfwq=T24M;taX%V+%EC)3f;l#>DD0p+nw>{YIn+Pxdsmq3D-aeGC%Rtv6Sj)0{W z4@i}kT`5%Gd%cNib<4I~#y7(*T&snd!4nee8I*pvq(e8ZXMhB3^D5QwzkQTT}rvtMe&>bh=tl-zu>U$SJs zf7<1dT>bshvqy#MXKqIsaqjOPmZQl%&0(onmmN}Lwu5dN8?Sic#$R7`jqkz{P(w(w z`R?Cc79Fd0=j?#G^F)n!ebK??oaK+Rq4MMVrevrG+tGL~ow&bq%UwU%#`Mi|YhX7!U1uoR^890%pvwW%h!#VW+7Xnk=mT5R=)5%3B}1U1hs z3?46JEmeq@=k>*!N!4?%Dg?L!3DwB_oWisEyShC>6Pe{Ivj6Gplyz*hzw* zUal0N+1YJB^ua4wRc^ivFUx`KqsaZN1WZLFYYtyqW;1NSW1ymL5DpH z7p5hA5zhbG$t+LWt}o7`11vsNl97H~jgpy72bZJ~p6GU&X(c77uP_2$fy7(AT%q+$ z6>4%vk)b`bt(ZUcrs0>S`Hhm==-(3|wraK8w)N5cM9=UfF!0E)461!i~QRGiEDVwf8m<4g1Gs`!E8Qia9X^oxS^7 zXz#R>@PzIr1F>q86WOCG5n;ooqk+4w3DMnl5=g65_PyJRhD9^2{3}`BZu=sn|Ld^O zr0z}vY4+y*mG)wr=cU=J&+uB6w2MS4w7 z#qMz+0c&DweaKig-0Rh=$`nyHi)eu|7C4D#>{pYgItY!)b`m{X#gcaH?>kr?pJRV# z-wczC|orKwa?k}evPtbG9$k?} zG;Xm-cbL6+9&IAojgrx@O+&<;zf+kVAuWvMi)llx+bk7jSPIfm9-9FSHOF@?_6dnksM2Wb?GcXr;HgxX~_+BVbMJjoj~DWsB*ftXFU5 zEr(jEI2kqC8_PdC*R-A(#1qgz&_1@K(S~{VU3B&{H&KQ@f!4lddAyZnNq3gVY*!e| ztFMDode&lj1qoP+&#M(XOOcq~=J47lq4H>_j^t*_5OH9OwZ!S#MUAl2L5%OehFI6r zD(iz^ZCt}-yx3Zb4kT+^#xg>!Dk3A*^R25dSXWl6$K*owOIE7+y>n!gb6} zrIc|{iGdQ23Qx1InKK#JI`6kw&j=VPNN;_5g`9Y= z7HrZL?^gd=iZ0dslO4(kc%^#x>tt#4QNc!2u2qFRb|UHJJE+#re%VJEak0})()aao zLF@E7E`q;|KNBUIwW5{vt7A-t^Q-n2VT>rad5^d*?kbW$>jJDirTcz@-dmkC}z*cn_0W%I}B9zC@#kqeE zndU_0)UHJI>VA)$DNGeCf0S!gk<;ueeEy}VYM-R+4UFh}@IG-@M+us0<=I|Q3es#Q zV^)fGj%;X^&WK%A9}@KhPvKQPo`5y6{wlK+ZF^&JB&HH^3q2yIj&u=bHsxvduD(+# zdfp?$ayuimj2@Gim3ytO4S<~F=F9kQolM;S82x+uqO8Q8S5E} zdjIOB2!BM+~uWCx^kd|XJs zB{t&cvt_H!j5v#T{fB_1VDHLyY_WDezLC02E7;dgzpbsgFF1aEefGfSbH7=<)P6*N>uFOdb+`KP`xKIrqD3Fy z?Et* z_->{}YbG~9r)MT|G<$z=&{S-zcFXOYUP?c+QVYFmieIKAlGIC8X_dehqW$Lt;uTkw zE*!<~AgqsY;*#A&1>jjI=f4ogawOwg-AP@W(@ zjSrRA*Jwb`1TI2*-zSjKb!*ei#^aC>vz{Q2X4LKMY!tjkSyijuwI=!DW-7Mb6e=$? z(V~6VcR=xz6S-25W@{Pgb;#QRW5nCRybM^cb(3avYT!DwzlS2DnQn8krN4{#WI?D5 zOHCEp(rOLT&^_;X!V?$onUm3}O~sb6Y}LT413l!Lg&G}WmIK25(hyoQ@eG=bl%C<@ z4KwoffGCCru~h?b1rks;+wZfuJIR{bPh9L5DxYp*LZ5gXL+@V35hxGV#K!XjJ;*8b zZOJ%rstjWQWAoC}n^s$S2t8e|+)WIMn?e@8^Og2~@s;5fSTC%JwWvf3VpF_Z48IW~ z>+QgFr9%mFc(9g0Vr}(7)ZqF9l&h;)K4h0f>X~JT!6!pF%L@k$r7b+3pjioP2u~Qc zUPavPM@r-F_;Xsl9pg;0YKT=mi#!J@++(53Ul= z3=WmYkJh5&jMTz5*89LX!<=R(T372q?9~Riuj4>@NQpP~^XQKjA4nlEf_#g5o1vw# zeWrycPIi;$X&h;kizn(nD2YItCwlB@FGh84k6Tn3C>sbC)a8nRj-nLOtm8I|^tV}%nkf*7;$`Fsx9>5W>UP!Y& zsb@QgLnB=!g9rZdfgvsFR&{$6Q8S4^ztI9M+W+}e>o>=fnT%^gbx_U8eQ@);on5Hq@jAH!ol1xZ|$@~5y=$=O-dY}jrgH!z!g4Vy)MqRt7ynhYkR>8Xz5v+x=C$AJqRQP|Ik zc8}X9%w2bYK$^|r8mPs|f97NBYH<{ns)KCk#7Uk)Bh4X_)5(oG2PF!Nx-0vy-sD+| zW)uDK-NTbO0+u>ke>QCvu}!EqK-mZIa8Na?tw%y}#!-=z4(0L0CX+$9){&1gnT&cb`bocc7~` z&8fR{M(;nCJIMW}ZRw}`6NLs-wlLz+w1Lvs`91N!UgQq}GPKIPe!%PS~v{bVcJ^kuHFW|4A#UbW^x&H1)7@dnS+ z6xIvn!JKB}py5d|SGz5Cs5gjfwM|l6)7#TagcYkc5SY{KZhK!<>GAO4c!p5}&T?oi zuhsO+mqk2%1P-{OE5poyr6A4Tl}Xtn3bRCPb<0SGK7pD*n!WjAP*d!F1LJwNU1VrE zY_+ggVly(`Q1Q@heVmXvkRxCzD36`?)*cDJcWL33E8S$+_pJ}^MbjQcp*zdtEA?=D z?@dI8-S0>aDN|)w3d(?e7dx5zdsk~$^P|!OJ#TKTg*23{Qf2#c& zbde)qH2DZFU3f;kwW=;QJvmZ_*$1$O7iPLq- zYvnYKfTeg}wYa@qST-g^a{A`W&Eeo!!V_Jz>!Z@AYo#4l3pfIng0WGl%&Qtm1v}mG zqwFUXdKC60uvcOy%FQ#Dn)$cHtB={p+uZ8Vx*PJkVRZYhP%`7ZUn z?+7>OEh+iktVG5k>QvM2^br; z&vMp1F>KN~Np)^IN5E3h(`*O!6;ts+=`<;$r9U_Kfu-O)h{>>fp~+NvW3S(N^senJ zx?}Tq!L{EmvOaPa9d-Yt(C=0z8SW5AZw!4SbZMoGA9pTwCl;1=c;eUQ^6e)HwBZ{o z)R5ilU)7mK*VJf_#%$V5^q$93{Z>s-;!I`E5Yy_l=JAJl*mYkj-7z|owu#OYnygMG zcZ@P=&Y#DErCVYp8GqWW(fB>|$FCB{(aAxXboaR3f?@s+0_oHXv*_MV>B6cH*-XaD zkr8AL?S*Ul_mp?`@u$*+p=dUHsvnu*O>O(lN6z61oQ7=Y+4ZHweOymm?@2HD@W@!I z+r<;P*NY+0rc3!5wC`a@v}koWlc9Axmi*MVmlhZV$XN%YX?)QMv_5DB`N(F--@lij zYKvBpwNt&R#X5qHw@_yKHD_)oUq3vRI#!=7YxPZ_pPy_;OV~S{Witq-C|)0ik}diVm4fbw`5^EJze^VX-5CEImBZ?QK$mXVCwI3-)hz^@xmiq zk5hOBW;@I=CLv&MysAoLaVH2Yffj`pPE7Z?1#w3-Zk0xgFgVdpdU zj?v8e;E%Vi8cU(IPg98 zh|Lps?2z_>!cs8DU~k9nCgvT?ofZ;`E!dfX&|28r!Pv03gdWC{_l|Aw!4bBc9kBm^ zHnBPNqAg^5%5~{VgK0918q7XOvlYm%)ipU*q1a{6Moz2kJ2Gj^*3E*HyO%%>*?D9u zCeU+zmWh@F{pGhaPEn+LLajS}A<=DkiZ)8GC+wcFkaV1OlD4uhP#ak)rziEE@``lp zz7Gwv2$B1IK21-qt128g=|dnrb>$iQLc2h{&(nty-%pI9H|Ks4@6GX(VZGDd71HNb zn+ffz29U<~C+PJF8g;Yy07eY4$fTpj7)YC+ddW3h3h3C`4wP`gvUOolq{DH;FXOq|;ygwyJLt&?=|+cwBpdm-V8gHt!q zaq1b;)nG3v807Cs$eN;boCfrWs+mv;?EL}W~YCDT}cxxlBABeXK*q!zmC(r)ou&j za)K%msV67VQ@guMk9RJRom~s)pnJOL=1xBX38*cbCwk;l%U(s2N1l`X`q@!BICHw5v5Ov~FRfH)=euBLc`jSKy;D0< zGIH^eC!NfrI`x9k*pa?O9wk$~k7H0H*FYi&N9h_o5P7MUnD;@^bjSidY#TjLZZ?|G zaKHNKvF%b4`IgYUP%6y7zk-ahl4;mbdfsKvQbqP3Uol$=AyhXkXipMyxl286DYyii!1AhOFz zL#JlMpw}r%mUvbfL#uT&!qE#YI2o{Bb)O^jWSwrPe_iDygtK!*n)2Qp7oF-Rcfx8q z{G0_k_jx&a{#i}CjH!>F&s<4(;(V z*5)B(wcQ~)>)TfJaCuTIEh22Dq96HNT_ko&2^zo6V=vi?T zfj(qUs*gM(R)!}e|0bSX1n>FeP|b&Ul>gb6^BdbwU93gD|Ll=EmCTYK8dBQia0IfO z=F7z#W+iJM8rNe`y;}A}4o#G7ujRjpMrvP_bXK{`!FETf^9?2?4xGhD5SaDx}yO5g-k|!{nf-`ZK;%zJVl1FoxL=JPF%VN zjS+(g%mua@mG()q#>*AI8Cp$lWw@W7arh!!%8ut^?%O<*ZaDKpNDNb+O&qRfLRxL} z!o6A_qmY25VEkDoKFA`Xpo^V{IC7czJu8E@H<*EXH(E}DefHBQwPvH*#mdP>8n}9W`R99_6N#Y)V9Msx{LVaN#zns0F z&hyzT?0US7X=N3A9}OBCiW|3GM&K1ll(2EPf9V$C^UarFzrIoDP6eCYvd9J*16 z%iqP(JmEL`JwfTyapAGEbf(uqYP9UM@Vk97fg18!ZQGtio~>Dk+jm&XSq?RXHL?3z z@ha&NR2y6WbmAfiqh`M$i%#|PM0&}}==|q(5xLa6E55P{$?ys!V2-hSoDau{o1+U} z+O!%MK{&#}XsT4F3to^dtq0(r_w>2kg#<6dFgb@T*Sjf|&Y3E2OFT&LyxW16+XfJr zV|-raiEl`U=^b&RRUaAF1;;CBA6ub6T8s9I3&c-qR-rRaAEbwuBnqAT?&Kl}Bg@Xr zyqiaQc;1kHESW09ksfNuYjvrv0ll_k9-gpy6&?8^i`wdM6PCQ)L}1ilG}#(J@Kcg> zE)XvYsLv6w6x5dW)HS}5345pG59loIa65~Jt^FiC>=Vo76_m$D&PUB?wH~9ej&BWa zUIH@_*2KPv6mgdn&#Qx7O`T*o-+|Wh-d(n~C%vxkhv)1wqwAJuQGbUxL1>mnpci;M zrsBG^)(9u;m{d!K(%~!vW(=E`U~_tF!z8S=poIFaJVf)Z9TjGsT2CO&TV9&fl8)Uj z;@x4LILo07m@#Z+BCP?Pa(6C1tCzsFT4)E9&HAhF1!PG~u{5Q|blGIEn$F+939Y~C z$IT6)57~(GW(1|~3-On!z3HgchiHeZkwSy;?VPWm57|AZMRPi1cn3UiFXm=sa2CeL zLub7<-TX-l$KDvjMG%%cZk0{9t{R8NOjOp$9_pJUhyaEX*kL@EHVMa%- zn}jbBDUcapZk#j)0}0*V%n-ia-xebimp=x-ygw?+u`~ zDpgz3kB&3$g;$w%Gj=d@;TKJI#oG2G<|hszI(DP1vQ2BcIvHaBTtF1T|#6Pve8sRfp|xlUGm} zgW!wVRMV@6pkuX}@ZOys)_~ru^+_6YVVn$CJfJ2}9y?{T>K+>3W*R=28A)MXP=>93 z4%N@G5H zk&6e6!NeUJI%-~DB-d23J)op7U0I}yXZzX9@Cqbg_OS8X^ep*ySuNFw@#a=PU{=Ch zU^@ZFO``*&ba2nFBe-=qD36y>W5P;0^=mV{x=~-*e65D|D7YmUtHZfR-kDz`Sqd5^nr-i028ve{WkU(`hRK&mw6+g!OgR;F3WOHdA5t%d7l{2JNXKFw&t z#4FODwNqqx1?Cdemi2I>is`f^t~jOkHg>o2zdi$c_tt@2`d)S2ddigb%vWniU!~Iy z55lc$y{6D7kmiY2m!H!+Uxs6J?jVKrJ{_J*XUe0j54vq6JdtmjL)7b2rGn3Mxpivj z1!y08`)u+CTIkvk-~G{7hHKL>2Cx;dw@gp(plwDOsTmTUWN*KxqET zd4feq6oHyRud|cbM&!`0o!enK&5W}H60j!LU!4i2TjxBMGB>%&aP1yy$ZM5%<2$|a zeJI9yhbWBNp{^P_cVUWpmfwa-5p1`)J)ON>mJVEkiyn2 zkgs1jN~Li2o^dx{0-saBnpCRL_OIzgJqMhVq@gf>pjK=5X=wbm0oJ+ml-<$o@4uo= zcK5}vcD&$n7t%bjsqQWMFwhtmp%yaq`xDGifAuhp#tx{4`(7B#t!%^Cz?^1#CdM41sYo9$|6;}wuoSP=jPOQs{0R%3_9dS} zO`xxw12pupcw8N~MVTko*;-SM--_{|U4`_0bwVF@YLxwa!+HW~p0KjNOKNspCgrbR zz^%8#Xz~%Egv@3Cs+*4$sb+nB+q(t2~qXZgAsP=ph09#&+q=zf5%o zo8YnATFSv{N+(_FCG1#v45@mX&! z9xw(_HhaRmDx9_}IxE%lcbDN43}`KH$BVc|vW|x#*6*p3N2LRIYRGG~ zKe;On58ov{ReQ5<YWOFQB3U0ZVmlm}^*>dftt^Z<>P{2I=Y;S(O{H{MqdOrOy| zcl2?}>~=D&3(DZ_7(C@RiAbF;)ywyl@2T@?QqVADdtf1f&!(U}HfNZ;n%>OLltwsC z;k*l<4?}I)SCopk(ZT25NcLMDxo5&K$M|@7?>41t&10k^d*^bNN7m1$-<}wt!nyv0 z*Q%RubsF8Tx1^uyFT+yMCZ1>@)srI@)WmZZ8OX=`%kYeSAO(9WZ~yBt^7th0)v*`3#mOJw!b0n*v){<8100!oKsloPO!K&_y*DpkJ_ zl^ozvA4eVT%ta8&7<4|5S`K`yuDw=@d1d_R{l|j=Y}7MG(s1Eq_}rgD#D~ zAmyJKBg1_XFt7N%2Gsg8-B+l>W*z!*mP2cKV#m+~`f~YNsm*vsXcNF zng6^pVr6eL`7hkj~Bm z8!JQUP%B8QRI%A9bnF;U>1+(Yvj);|R}Xu?cG7sN-%>{k+w3bteW9;-!gTx#+J%Nl zYa~}WzDhpr`je>Jvag*$8N61(b@Pacb4&4N2ERin`_)Nmr}-fq+qHl|AF}f-eN*TO z^Py6})LGmvBq(EOlLBgUw#eFeh4KxB(+djeruu88+^Oy|yaEZREqn9+;SJL6dTX(v zTZjxbfjgasY&b;&N{$KdT^2AIZO$dqr9UP}9(%kw8E|J6@2esHm+6%{A=2q4?wqe6 z0kviKwR(5SO#2pM{vh60me!|fnDrhjapGWp=NXg%X|`|a#2td%v_x|kUMsj)4enuMYnJ`mm7N>4Ev~zH+Z&I`>OqC- zKMf+t$XU)$TuRIj zveOWu9kA5+xB2uBBObj~?$7(F%k3EV-MB1*6_J88PXxJ_Yc+3+8ArfUQSI|-0n4{O z!OC;B%je5w{-FScemvj9rCt7{o%qgj(|0> zGoAjPc^0w5)O^{!qqOO}0=2n%1xLV|*q2Yfm)p^Ic6W~G{5g@DRxebiRG-1oY+qk; zIq`y>nR)nD9<_L1ppIS=Ngx4bt5jW2l@oEFjX7dV^E}$*LxI}!R1`<6R4B8YNE%{l z{xevnMXZ#wCYmb+Y4(od-}4jo?wfGLi}jQ~XD!(C`5KO9XT+~6m$59}#2o4liTCX8 z{`IE<^@Lx_X$zM(mJ?cL>`Q+W30?WQK%Mz9o~xH9HsqH_aL{0$xPD#3b}|>Jm!>3g zG+T8}FPEX;n0?C>lqz-A(AHlI)MRu@CF11Y^F<9BnVQ?IjiF0g6{=@7K2IRgXu<~C zpmCvk$cJKPNBdSE%FeBAI?L6(&hdTpd&5HY@1-A!QtBx>H3S>u0l^4K%Tp)M8*5m1z12}^xyy^ns> zD^xpm`a&j6-b-f&vXhnTeq(kVi>{dy&)T_9+LYWz*LKkZH&3YD6MvE$yY|r2DTV5{ z2|q~v3%hCbr+oEYi=T|BTKvlL6C?CT#9EW6o%Gnv0(D3RPr#bkcl+*{99FdYxo`Lp zs1=j}YhvGt`z4jxvEcP*%X5k8^hDo6wO7b@PAgawd!x#*PnnE@R@T|jLP+z3E{Z** z^l-wwV~3!3p|5ztskprNiLPa0Zk;-fUT;^ZK0GFXzzB|+X+T#<>@;QfJtcEaCa%|XRiL&b6C!!||Iv<`*pRGT+k zDMellLl(`)@0g56qsnC@9yj4~7i!4oRm4H4ZO>| z+uV0>89{=db%#-dr6A4h7*uY#Yi?IAOQ1Y{eig~GM6tuZPgiqzg(Ey#(et=a?Xg99 zPdNEY`5f+9P*?N!>( zG_%vcm3UlQU~2wm?qhOmF#G;_+js)&g*5w$QgM0An*_HrpAq|n7_&LGz5fbsP7P`H z)Us!}R`)*)Fn{vxDUsRC`|#l9906-m&d>>ymH(B0${csmj!o$EnI>hk@Zy}a=vW=Q zvfszQtw)!~=(8+Qh`rrEvwpFh=zM<-ib_b;D0CY83P$JO`*W4wg&htdmE{ZejaxD z4$>`ZTUM{D^)NJims=SfcwsnlH~yAWPTXJBSY08b;))^<5{{A)n*O#Q`>JkbUo{_S zjE;SqSLPpeTRl{D!u+z|&SE=s{rup+zJgk{Id6vUZa!v?5N z^Bks?A|s}bVQ=M^QmUdZ<@eT&j>vNS+%g#zvdisgr_=GD9g)>-P}HCPWu@YJ1f%IS zXO;b~pvz?_|11BLdc&gDqC3)z{}9UuPDewoqyNVasC#d%Okse#K_xqsnEynv|6=~F z#dfr?=HxONUB50yv(}rJ{r=#*8X3BF{VQW*aPNPXSNKHH5XzW7Z=g`}u;u>~53Mn2 z>J+mUoF)p*6S{Ri{PR`b+C%7Jid&f`P(xlTt==X7?8q)=_cB#-$|49gtdOnvly6Z` zMn%1fR(y+6IOSiNz92JT#_*YVqEySWf~dHn(2%IeX{B74JZK1E^Pm5=57@dYGQXTq z{#X7f^UO=na(L6@5%OVbUUiA*aiJSJYH4V`bF3e?-LQc0Ht65naq}y+yvnJMMzbi(fa?3+B2mbX86<3sc zd*RC{Y1e=Zmr>Iv_@5n6MxTcT>Z{876{8akstT^F9skOZ8s+|z0X2a%PbiX< ze@b0&lz{|q$I|dQ|FnWcMJc7Gig87$IZU4N(e0mB72^afrTnfKSIUW+ucH5X7mhL& zr4)i6KeAi>FR$Q;Q&CDGDn^EK8Os04KjjMSogvK=rwcOvSq>vukr_%&718`}`+&Iw zbF3mO60{@GD+MbRA+ zN4IW8J5zQ3%6K>W_`mj1(K;0Z(mauVwBJ7&6;~7jw&04IRH`kPL$Ph?mqXisHWGjS z(9kv8x1yqM(VE-M3AOI=5E&lprDipS0uH0B6}-u3-M8EsgN zP~H5u=xgI(Mr1Og-QE_K_a5*vV5!~p*?u-N@FXpRZZ2A@|l((Y(N3jbx?l`gYSKY>1#6Uo{jP74_F#`n;TuWAaMQ znlKqXZV!?z?RFm-^0h5C)c2$Hel-%q;)WgxAq!~)qlYISw;ocwkdBOQDE2v|wpOY7 z){*2(#-D^4i@IW13exFQ1Ip;|VtuBS&|!@H;_AAbyT&y+LbqrEJ@`OZOdZ%y;AOb4 zc9%EQJtdsH@JWI)bW?rGY^o8REZC;R4*S|HC;=5n0Hfv zrJ!u)U3Xvk)uMJnyMiSg0ZZAunNPPJ{Dx}u{mEpQiGFgQ2{}UTE&-e!FZa!-;Vd2@ z&GisZe8~=wb=?|TAH3lpRn4DIZL2>+l2dK26r@$E6O#hvZ(6sqvm^U*1T2-3F`xGO zcpXi8(*Uve?&_J!xu@%CN(-&A)F6;fJK9+6Q-pG1oMHUgnKe`E$n~DtUu0W%-g#NK3`8bM$7{gqoKX(87> zVC#Zyg`NFbG=kcA$;{uo}_*e;s(V6CWG!lX(q>cja#RKFlKcXq=-jxe9Lnr^DD zC#Ggj*Fc)}K7H!acfXce`>YDa@CqbcPsLHYC-ucXqr+IMjc!$i?sNDowD}N>VgCVX zo_JR;kNl1slY8Y(2!>Z+j{|E`sp6`yBcr>#w!)5~7?wIeH<@-}>(no!BQ&rdV_men zH+j{$UGB~`q4)qRB{Tp0-V?#~YK1@&uFtWwRX+ zpYCd=*U&=UAMpgNxA@mC8qQ?D)Qw>>CN$luu}Irw{pEcqhF2gl=l)JQyttaE`+7Aa zCU$xxEGUq3M*R-O@XC0jLv+vJUuZ{cv(V9S3Du%UlZPRECq}kb2XQNPr-m%=SpF%OL z3zmX3^X~KrYp1+TM?U|Rp^UY6TJkcWY-N-UldZ>gXQwE$Uzzji!Xd{|fN4Xd{7%Td zioztlvftjUrp3;Bh>glYkv&;iyr=HgtZ!^&QAV7nTa0qUXDurm0j_sxr&0c{j3t^p zWyFbddv2}}ij2yoDrm9IlCs{;{Y4E%&?-I5*=!$MoD4ezWr&W8%1VVLKg#8afY*J? zWYqBq>;;J-^~1^tzxcddNVC=2;r3-jo4T_&8Qp;GeG`0ZZwz98*R(v(-voxqmeJM?l@7wUB1-@P^hZ zBgQ#jHdoq#lI=b%8fdQi6w+AsyYu9Qxjf-Dw@F!Em1QFE36ueAV&_vgzEhU%3IXed zGrgP6$7+{I2LF*r^c{r<4&<^J25$ z6|JA;^Xqo3&BK}$?aSMr^2_V5f6Nap$yI)*1nxi;zZJiI9lJ1BrP}m&zWYMeScDcT zzrXG(MvArj#~0EQW@nI7avf&*Lq^<5%(T#oYQzz+RPeMyn%G!IVQWg5j5Umq+NWfr z=DZA8YU=Dl`YmZc%J$m92%{_I_XcD28j0}A|7V9{6Z--fld)z{eXEJ*8i~+yXcMf7 zJzXklRCaHqVI;H`68db`zvEU3>Qi>dvi)o$QZzT`Fl7Y10*U{`qips3)X(HYVP~h& zun7y$>6>j(2>X3smwlP^`eKdp_jOwA3EjLltbMQu%F~?;dUv{-d`Kx3&Im(Rsxnbg z6Wc9PO-CFxRKNGLl292E<3}x~G1p$BwbLRscS|tsK&p#B^XIS#4y>vpmNuzz=s6>X zTP~vM%ccn(iz76xdoQAM&t6747b7$;?|7EUZnR?wBRVo-vu|8hWdfE`e!r_mWk?JO(eQ4!}!F3$9J-^tc?dchhqPiOjoJ=M2usodAP*3=Pm zEoZBrGOb`K81oDFN7J#_8wdj~2Qi{i108YimALE&jDS}laka~6I^^9bVds2>uJGUxe7`q(sCFtiEOz?#@o z{U6oD{Jy)gUR9C->xDJ3*-}p(G5BJZ<%LQzRJ$B$vsYULpA7*TC{Lw|?^jLK8&Gt_ z;Wqo~8z=?qjiw`Lh~*Yxc>4fmIh~>-zB@I->To3)Fq%BEuU2^`K4t`rt@68ZYxXrk z)`}p_-XF~zGsP5-r zp%L|Cb_}YoBR-J+SUh9|yaEYZI|u6h)=tnkDa2-$B^zxmEENJ?fkfnHdm2}_y5RT2 zmk~uQ+v|_7ldWXp7SW!LF!HeeTIj2Rr68?RS?lPC`#z2+%UwvoQhCPqRJ%F*vNcs? z-2PTgTytl)`VEr-+a2t$U^G=KN2XQsD`&ORq9C!VLkeBU`YZY}K?7;FigSy-X)$oP zd~oR!A!gKYI#FxApqlEhIXu~c(k9NrS$98;j=^xcEh9lFY-@?w-Y9pGE?O5T*I%;4 z8eTy|9qE?TSl~_)1}Y7ULl+QE7>SpBWf|J z;a*~$8W4&n#rCAXVm_g{cFxE@<~Pw<^9j8ezZ}g-`b|0&*B1BLFK6-iRn(S!U7?kj zn;wK$Ec-*wH`f)-LY5(icU9=jdriccUW<|M%irXYRz0zA4TbR8wu0<2jLr?3&C8g_ z=AXN_Y(?us^pFo5Q4g~bb$Grq)^v*}qzIHP|gp7zJ!pN{t?9SFgZL)3f0Z5%#afsKTdC%Y+cLFtZe@9jP3Dr@Kx++ ze0VMSBsP(vVt8NKZdB1ND;kPPZ1n~Djb;1v2;zLTd(Ln#wm#a|i5l;Z7ee;3RgYdH zsoB?5q0xEsO1_F25=qQ{ZpxX!w1Qq#T55$RP(wD;Zy7;y{Pc1@Ga2;3XzDVdfiUl! z8CNe)G*}ct`aE*VY0d~J1JbH`qiL|mcp+Zhompq$&sW{ZqX6V3_f>ZsVJ=x)UN$TVXUbIvtyZF1UWiwTh1TmD|jWZ z=5X5P?ph(u%CeGH!TOOTtDbqzQKnU`D#Pei(*U8)Xe+K1q}h7ny$G^2V04Zxvm6rH zjt=yq#$I?)- zLH6|3u@%-{#sccddJNo@edYSlXhuA*89^Gg+mO?c5%3C>2Ww*AyE_+7ZeHwVwTTh1 zUbC+Dv_v~k-G69h8J?-}xn1(K@!$upxbq4fx@A^t(L~>eYen^pv}kzU=AvHhP^MM0 zri4VhRmZ3QIOE=Ky=kDOp4j|~h^DrxMJI;06PI{RLj%Uvp^GN!i>k2`8PT}aL9+T` zx|H-{HioSe%DaAcJ~gfS3UzK=lMyxEogyJ$eoBc3tIHR58%P)wZ}|r=hjzRG4^aIuD$nWjND)lE<(&|I=QzVGC z!GZk-;k6;U)bL~%5f@1a%7Zj}%XIy9vS}^CIaRvi@rgdPe~+4C)Qv15KGT{WTc#Klznv6+3P z2*_r0pCw0#?=%S)M0UZjRO$Hhq-h^>akuX@BuWoRo08sQXO#`}ReGO&gf{JuCyy}1 zeN%GC*Y=j8cGa0&DM+*3R9AM8(=kIZZQqh33I?W?% zHV*L%C2vSyF{#}GlzcXU1Sj_s*FAPZkY-vPiy>iGU2#I97Dvp}8AR3`94Owr;?L1+ zCm@O>wg>0qF>lvPu-;#mE69WEwql86dvwC&0U7iji5Jc`VwRttLdnP-LvfA4&AA9d z|G?O=cL7eMlIcxGV~-cLFf0Xihq6_w9o?4^_lr|-YSU5)>K^y&i{_%o5b@Zj&`Ngv zzOaoCOvL>VlD?{CNe7#~$y!B>ue<{^C^!!+Mofg9>>iOx~rJ z#c1q`AsY78g?e+ykIwUPyFnW`JD_)UL;7plEq4%Cv{=GqG!5%TUj6aMwKAL~pXo{H zP}nHZ)x;M;4SB6LyP1->i~cxkq?-hku-tsyf`&A{QF=OkUWl5(r@ZB){}x#mP&LQ^)pL>?X!G`!^+oAlA(sCk|X5i=0mO5!cllBkJy3jq2sk67P7ph#Qy1 zvb^#vG?2#c55l$jZ__k%jgUULjS)ZpZcAFB1ZnMuf#T0hD{|8@T>8^;jA*>bo6Yn) z@3g|}5^CbaktNh#@3?e0;|;2lDw2@+GtzzYaMaPeHZf*@U*-Q0b>1?75ub1avhGYM zUh9>BGR<2^FRRZG<7@XO_fPedMlJFZ_l28~s!^uW$7kN+7xpbSHhwHzr5X4%6n|~7 z3w`t*Dm`2=TQpj=j4L(j_E2fSd~b0;l@5%Uo>x_hd=iXr&UVPz*fmhPxX?pf@7y`PK9*M#n`wG=4!|88U8FJ2{Ul;BQzXY`p!>giN)wX2#1K;(bk3}$ z^woBT81`f?^OfnJR$|L70XXo69Y+jkK3Uq3GgZ{>Jr1Sr8!BZ7d5Z@Qv|~iUxVj|# zRUn=-zlQ|tg0UgawIvtLWO3}$jg0WhH589dnu}ux?BZnT4jd{?d*LDKw247b9(&(; z$8L0Vj5lr@BTJ1|_LTO1^$-txCm~2c``BrS3p$EnHi0HfHqt{JUgw5zF=M4PGRaX~n9z;c;n6~m+^pq~MO#k^ zS_m!wX0t~;7~m!b$(tGB^QXQv*&+bDtkdUYzU&BrsNS4sVf{H3_k31Y6x2z2#Pgk(Qsgt*eh z1wnbNeRTRL#*UnU=cb&q-RXk5P928V)M$ch*!7VNoLt1u z_Sp!=X84Z!lHp1>QKQOLeAV7VG|0EYb=R2U%q7z#?W+UD>J3k#M;9hZ7hk!Gp}`vw ztciWO_l}CJv7LlxKX@%Ioq0n1QO#9MirbIokN6~-sK$%m9_&M{hsa`^&#vO|D|?uX zn8J19ia;wIIL{Q+?3P+qev{Z7hGEf|SdN-5tB7LvM=Eq>1)x9-_n!H+nP7K^JMqJ)Wjd;uJ zjnfy`+^d6g7mvcP?_$Z&$X=W`@f=F=njqb5Z7tqhe-lBEus2_pB#Wl?4Dq7X{W)Lh zHe4*7dfr=18g&{$`&6p;`NL4t!Wy`v`xs8f@|^n8)6fy(=e_4pTfL5wWBdSdq2n!P zhyH{S8gHX6IJ9*i4E23^{Hjrk*dtEfzKSJyheS#5V?@bnux2lG}nzK`y zfbNH0he>VyO+=kq*DKlKP-8Rt+5fCWGCeVrUca-m^hh=pFV=j-c|oO0NDC7m@2QPd zZ%1KRFSMNZRZwR$bh31t)YN4jK71TWk0MRQg4ibr%7C)jcadF(h~^U>N$r+7}(mY;cd2-!@0CapU)nX>~DFtY5qT0lol6RG3-&WjusTjeU*u13s3^c{P zR2)4o1Q+K9NG}^#7i-RXhkou2mb&Rx7k!$&L!NhnCCA!z#GoHshleizPkK+?!9 zff!!VnHVCu7&Q{xJ%7phjlE6Y#9b5T-PF3|TPO}sA0ZuB-9&s+^A#$(Ge#P)x=^jF zdW}vq*^?6s)d#cQF&PtM_iBbbbkFJcjwdo7^^#t(^|HpcPdS=>qw2#MjYprhLg^-AIygXeLlhbb?Yxes+BNqL+fgsIJXxb2f+Szr&p}BpzY=`{^@2i%bAB)M~o$)FU z9SnOl*fYTPuTpK>q#{dK&BW(RPDrqw!#!(gW*WTM(0aN zGkNq_Jk`D`*O$Qd2>W@J>g&@U;`CmQc*nj581|fS9E4s_sUp9sNcDI>Y`Sb7H(R>9 za)a2qyPLT7TnggHk7jf0kuz-q@Y+Gn($B(`qU7T$N>36HB;W|gp5vUXqp9cRi+8y$ z;bs6(cYbtkSk!>b9~6jhIQC(u(EM+%2IcWGcGr9*#@dA7HYNvip9iN)!^ZXy$DY+C z>9gY{Iow7Z-oTlg&#|{<&pncw*SITPUpPo^yYIBryYLiRpBSu}&E{>#R@4=dO@d~b z?cSS-r=uON+r=y=kcw90Ksw?VcS0M_W7g1OI zSnD7oIvcl^rn9wOzx;kAcHa?cL}W|x?vb7 zUd`tZl&ba!#IaR>Swmvri{p|otF{>KTAcfw)g-NNDW>jJw6dH3TG~5yJnms*Lf^M4 zkhb-%E`|jKX?~OxN@-L7pzBFNoK5WEV^wYJ{sUp7^gA@A`$_5Hs<-I!GQJd~RjM12 zY%V+B3rB`%5hw%t%JtcC>85FIaeb6+r z-?!g9pX2u)-)s8M;hA&R>zbK+=Df~1rt)EbA2K{HjyZTiRnM%%*0l}l)?AnE+f~9q z@=e=@YtfPCQ!s2V%sEUc_|nKV(bs6$M#a{YwA({+u-J`Tx2@75hw5Qkhe)Qaf>&msPETIn(bwe zuYR#Z39HhnKs@mBch)HXSqf{%=(`uhgnyN!>|6@>#R9)lex035 zb@2OFgSj$bt!}c>y#G>C>^JGnYPEk~HLkidQ}Jeomz;aC5Swf-&x?*+NAI66#4A_0 ziS1Ucqp-GYr+>s3Yc}|j@*|_Ag1}37&#*iBjd39A_~!Lr=O)w405Pqj8c`W2UI|~%iE?!(2u&4Rn z-Cz0(t)JtDtDdfw8*I1W4?%6w_NHVSx??kTtNbcnGD)E~d#%BH?X}RaSO0rYcxw$N zVjP;^e=#@aa0FjnD#UYQ!o{HWYK4vA9q-~&v#!`>rl$;lx&EXOpDT$I%fE&HG3KL- zAK~_){@CQOs|-^?>*L#DlJW%Wd0oOI9!->?^+7wH+O-gOS#(+qo2>Sa7TUG=Z1-pQ z?jBptqt=joeD=g8af(AYUDYigJC1)ON~_hXD%#zfu>FjmIPaxGhItiiE5MdA6{k<- zeTBWMd;dM&e#wYz-(oDoRM1mlZP_X3rCO}Ldl;$k*Og&SpwB}zi?p~?fZu(6gL8UFJ9>=}Gtr%GITaqS;1uhOr^%{QON zrjgUQGPZOn#U`VVi^&Bp|2y~jZ&qTr8Hpk}V{;kz?xigcW~q*+R*B`mCQ)xT8)#p4 z6n8Gvrx4B5dd46!?s6vX)2g!!Q^hkxkFlm=psnE_h*6yt)$EfKttO=~) z`!Of+(|~HRdb9eqv>THwarusa$cz{xnJzwp)7$8yt((H>$?My&<3%$xZDAbEoxcZH zJ~u^G&(-ZXl_a5)y#|t>4Wj&Rh6hf{bVlDxlDJh3u0)Jk<1qmhq-vALn`X!(w+zRL zDgPjwR!6usidz!}MXL?S;z<>5e70DIzra-#<|GKkhb&cQ+jim4>-^-1NL{?skKM#% zCDGExGOt3&LR|Yn&!K5$kKsWRn4# z@tz4&P}sc<^j<(B9_FM#+ag2h`$6GYZ}t?FqOp_Js&*{FDLe9U(0ea#1n)*?WB=8c z#C~N_wDR#mTozp^{?n*_0c>0B2wd#goDA#WEWhi25I0%spfkOrC}do~HnE%Pv@v+G z-B|oAEI@|&rti(gH7?oW>AioJG4i}Kj+)|%PaFElqdFeNLci1E*;CsoM8KSwO2HQk zJhIGyEJ++E!~TJG1#2q^$?U@C*{6-T&*cElO5m8ge;SUbH4H+-^m19t-9H`?%QAZ^ zT;D3?-AC-Pb(dbqM?Z%SQB1^srHjPt!*eK)c+&iscrt1?uKMLGLu-Jx1g(d?8tUPy z>SU0D8u}~cq`P|f_wk{qnIf07D;}Zc{YC7W+LoL%m?6Vm7%Xr6P+ffBloPr-SiKIm z4eFyfdnR6Cz#>{<8L;k+p9kX$pAAKgCF+*X**8k8N?nSaqLniI1-5+5-U&FM?R+uU zR{i!_5qm*CX;zrHxJfCuyKIL=J4cav^fK3zqWW^WuU3-L}kTsdK|ELS-VdZ#~ zus(|$8x~RZej}RH!xrD#9?V$@w5y4$Jh0*C&S<@{dS+;^a|Eqe?nZ29{giqy^uQTg z7NXR~Z4}OGnhEx}w#f^<{HoTi&A)L=43)={*J-`v{4=`j`*j}Lz}|m=J8yo>Z_nvM z9ecDRQ%+5nPZm3(FLvY6uC?hjxaK^{wsAyTj~wRO#LkeX{Y2$$`V;p9h?{pkwbo#{ zhaHkjnPxlpHIWxsgDe&Wl9G(MQr2vCLOXZ?N>=z$*e3pK;(O_36h6=o7f)Wz&2Vtv z#`o2%lvSz@c{W6d?J2{$!(QN9Zr*hfYPl$gL?4^d)Zt)=BVg%P}Sar(+wGyWNw*IbRTt zK0AyWdML@&#=8o5y9CDu_K5oCr#oJFEre*c_g2Ak7+4lc+Q z1#DyJftLC1rKhYXqLSB6$fg}r;4iL4XDr;&vtH^KLpFXj!GG@!A!Sc1is1Jv{I2E8 zIAY#K)$6B{3@Dsi0PnfrZ4dlnW!&?&y0ki)o#I&a;?Bt6%`v=PWGBKeG}?+y)|OU=dkir@Pfe|MRMwA|skn3Nk! zGe%oWnwE9qq^g~?#;m#Yz^n~=>Z2YHvoRQiCvx~Qti6- z(lU<_F+f-SPJ_b2nf@F-y3jw3N3=6-&hEuc#M_IKC`7ZjGxyJ?wPW|^7adf}Z{Bs5 z%mQ|brc-y(`zD4`vz~{<+vy2^)CwtQQO~UF1xF9@Wx$%ioLFqe^m+8g;A}vu7_6NQTJ8FzcKXZ$TWO5c_mY>`@dAK ziOnQwficQ&wd)T=!dWGKsecKTj|r21ELb4DS$$tTx;cu%@?w@dv$rB2iEcw(w&0j07n#0~K2Kn-c{fu$&RBVgg-h^-nwGzUM zpw43Id|#@|+Hp{tD}K7}!^-%5+LPLh>|!M)DP@?di*}i0QEntIYa2j4KbA?q7k^bu zPxoht);4+yXjxTYUj$h+#|#*u-b6 z;yF_ShUGytQ-ZGYq;79E6=X8R?S^tG^N@~W*#$oi0do=rX9rI@tE_85*WG+O{zU6E zGNsc0Dc$y(>`7mBHz+Xt|A_y7frvQvf_>!r?7RVM)QY_!w*K_{@T=$-36o*}z;?iK zVsR{$#ng0Y6+Ym#n6nZ%g8X>cx4A;oz87Je;$?D&)p^ppMF&LvJAo8h2}HA9hFLT% zkwVF0=SBqiH#XO@rAe{PQFwmzA6%S1E^*YOeJD9p(Go+1CX3X2r~5(F9T=suV>T9E z`bE_4s9tf3924kpqfqj7LkkR9K@b6RVqd~Na_HqOBcfYmOI|YTTcw{Uj?mavw2{U3 zZQI1+An&jKgRAx;<0PF_)}1_iW5Y4eAev{lxo%CTrF+(pZ)^K=+$hM!((nkEgqluh z@vU-pD>E@Ok(PE3B>hZ$xOPC+6KoSZZ}*C&D&0`>_DD+%`vmqb-}0XAqiL9dlH9Ns z(YU2kq*mp9+4rC~w@={tS0pozmJA6Ya-lJX94NTs;CC7Gtu|8o@-Xr#HI^#_&W~{a zAP6TrN75?0P_oxn6GytoNa>k6Xu~dV735#>h`+0D(q5ZfN&M1Z7&2lZ8}r>DQOXJI zi-aYI8HXk1y^7|Xwk0#XjL5(*$0e8RDPnPuY^k>J{vS7p-Cx-jl^Etr7cBOO0=b^g zv?dRnro+ND$&FeU0#iXWv>0~hRYa*<=RU;Gbu`Dug$&%;9>3`s{r+fbkNG0wh1(pW zePl~K_H{6+VV0Qf-9zk_kR&*X97h9Ex?IGrX-hZ+WJmLS>etDUbY0Kv!Z(Z;4x>aM zlY9b;9w{uiBU+@WqnEW-M$)fZl|`Ky0!E3z_zy>Uos`I8Os;ACVk3Cb+eJ0&+D0q0 zZ%P91`yuZD@&g!4?_9cSV_bp7Ql@JFZ|`#%58&GR3wi02{^S8X3G}1)PaiKDv4tr* zfOr)+HZWR+eH-kKq@CKIDC)%80qYB+E?|!cLfF(uy6|U7(S|<|Fcs_(=I2qxs)J9p z#2t*C0NVju3t0<{w?vA?$w#-~akB#mWT8No#W$qH1{#KF)cGfDJX}WYENWp_jOyxm zCI{rR!14s)OhzJIUayHevAGwr?%|ljI31=s6vy5=AO8ZGCx>#eOAyUlN!$W+g+;wK zJ`xkk@k=0c1lCXx26fOuGg=nm`#qPlmt6mkK?8X*e9M0yuo64Znuxt_1ao}_^M&QH z_}W%j)wO9MHunhP*dh=CSvG8j(`S}Asz2IM$TLzPf*--*UCmT$-><|AnNAT*1$jh# z8S}4X(D4RY_8dQtdj`*uvJt*wC4))h~P(Stdzf{`e2MrHHW#9X>!@E-j3`zkK-1;&-|y=(s?Om(j)Tv{%zCUDk=D-OR# zZAvYmNoDu&-8Kt31f07dnsK)Grl>mGj3v~zHr3_xu;$`e;68!h0d((r8+|zJK`QPvaBN)I zyO6`iPFU6n^q<_N#CHtORfGI1$XjFWIQCh5^LYmGnW0S}cMS4(p^dTg-MS!D{KS)_ zbZy}H)DR6vlbwskrx&=@yOE$}zcK7ZSO%;idrx@FGu1cbOq2^+6Ug|5V*|N(Og-u0 zWx65CmzY_^<8#9UrBr>U{1v&qVAb0IsYg*qRBU(1ir8j|J1UKT<<_Csj0Hb+$ zMEir)w8c;-5?`Q2;C>gTYW(dlwTse04krh(-O?rPV>F;P3l~oH;bsOnf52TWJJS!z zLg&0aNyDH9jynkXf_(4(`|1>(o$5)RRXo5j8VJ@3wuvb;rPNU4>_z0w=<68P7b0N4 zu~VGiKhV^+K_qRq9fpi?$cTsRMy7LDn}UAF1(WmltvTC;2*|(}gu<=!ikk9$Nmbfj zE*1b<2DBJdBmW$_N7^wwgzFBpll@f5{;?rR%bAO9USt1$)D#0L|{tNaMUQG-?~ z2pNtuX;!k5?AIKog7IoWPh#kxi{nt_U00RWy(eXQCUgxszT1TBD}%q+NIg$?LOvT6MY)kd zQpEC3Na#_)G|8Wcr|5+AP?Bz1jbKbv#mNw9?`x*+`F?E?tRdsQwvg%gi)+Z&EF%o_ zg5$v>UQg|fUmpn}$6Iz*!59-5^Rbk%_srkepg?CeU$oW7pQ!I&VPwksO;+$$26`0C ziG8uOibeOF*f&(#LMu3G5CL;yjFg@uXhN})^jh+%07me@n;4#ryZMSG-H@jwImHuH z+TC}lRuczw+b&TB#~j)Mdu_Awwt~m>~*eP@wCr^5K`6JfQt-+ zcPxB_+o*s0QvEU|S~RFbH* zJFQ?DupJKmrJ}i)6DqGQW7fW*-5V8cP!fanpRM385W)AZOSkp(ZJ?4=rbQJ&3x~eK zTl=D`hiPJF2qE{{;vXJi>?NyC=*#dFF5-|s@p2iTNe4X+A*P9cVc1$|`7kHOZnKJ+ADAEZhkT7oGVk!sy$!{Z5P_B z^+^wGpuZIT>fKp=PTgCJTHjNWb1#|~!qouA;6a;ayVp8Bn!&WMimQ^XpoPbO--i}v zxS|_PNt7Rto1I6|HB?EOtj`psC!5klUwbs{$~Vs1p)IiJffMZJXI%(s3jCY1U3iiP zPuK*3Of#n?vXU$=IZ^;?1?vvm#NLluP%i#trxGVGF3W@WnXupZzADbYEUFk{WU-tN zQ$aMpaxOXeM0JH}SsqgqT0+}}{R8`rsj4`R$BTXklZVyyMbH``vm5fP1);-*K-zO7 z(_OasqJZb3(AuFFFm_wzCR*1rjD+gniN$m)$e<8QqF_+Xs@4I^)w+Wk{%z! z_9YFP82$oJRbfu-T(q$rsrYaTI}NnvA{1ck0nb*i-Q5>=+ZIC7#+)mJx8cyEpr^6h zrTeX^<6R{QZkfj2hQqj2-mVtdIMd+WO41@do?Ex!+z!1!5FYnjO@}UGt8-Q}?$jBM z+BbQ&w0%k+)bDT&>#N)!Ayk~BB%aq=A$T?oM~z2B)@`8=*m&IbZ-L<$z#fIS^5ki{j?Jb17dC2DHdp9q}fUMD-NOG!=a0oaaJnO!LX?IoK52jr*`Fa8DQ8*Jp z?_w+q2YWj7sFE1jtS^k*(O$}k8ik(BW4vInL*jckY5sOPs3er!DsM#az8|)nkEy=e zd^>eX3?m1p9^`r#-bX+*J1-#vaMp?tQW(-#0qsX$Hv{|59g0lT`A7oB{qR!YWvOe3 zL*aT6_9*P>hKG50NTwkg7kZJ6xrf6*l4v`ML{->JFs1=UK?LfQ;+`8@qCsDc+1#$| z)B#(q3MJY(uN5#aSSwgII}v`|i8f<%`@KoGt$bRQ7Cj-3X!C#=3g@n;TMfk5+oz-1 zlcHG}Y4Mmo&u6Tck1q=091hX^c%1BSM&5K9K<0(VNU*-J9VZ!=H{bS<7hh~^PhOGlA6O&!VlPGwRt z8{2`t3F7+fW)x}zsQ;ez{fn4dJd(9se`XrJ(_cyaZw^p&WA|MC77xVQZ~ZB}C58UT z)U4Vk&}H^Y5@?7yJ_AJah>S;1P?&{3X|KPD8xL4_*bA)XTg^#JZ9}r@GTYs^37h2vkUjaG5%fW8{d|1V#|UL1fx=#3(aTXH zj&@%|(w$8aOa=MvJi@PME_%gw$U5&eIYvC}1&C(n?YbjX4?if$kuyFb! zEzzXc4+RpV_>~ge^+7%y>_b5)-ET>csFcLx&^XJ^EWTs-Gh38)e>2xtun$>`dzmlY z#qQK1qsoe)7eViW{>T*NYU61Dv&1z`<2Xx%Y#L~lj6v7qDk`sDLSD=~FTvi0V*_oB zanpS4c7mVV4Mex|4_#jHmh1CcK1?891c8_fiEmr zNrnv{g9diV$3Ny8qp;l_DQpMd@^j9UvGqscIKw@a+)CFon!hc2k`{p8m>Jl3m)h3h0AyR}8&b5MGzZ(b!WnNmlcg z@>#ly>bs9cYx>91JkLF}d=WwmbmOS%X-jFpY6Ob@spi8ODD|+>=h$(= z`cYC~Np{4wBKMQ(B{nqwdv3C6X6J6&XcIGo;fOPrRG2`>w)l*@JdUaP5on4-sEmIiis(cGF|-&f?7p)6roIbzD)OhE8-S zThG5Y!yE#p;#bau##Z#EzmmMH^Pun-h=6+(L6{%Af@aPSCC1%bNRWpLXKj9_KKLwx z{#YMMT$8_1mE8EGgyM_D@^5p4ol|lEzs?!j;!U2R$Zol-}ff7 z#+;ELbM+fL*YF=$Cl0wgit>oJU2|z5J4qeu-BE(6;2O>&y!3qVq-kTwuE4G`v_xp( zFcOh{4|ep$IbnfhZHfVByU;439Sefa-5a=Di6`+3?Z-tm?q!x=9o-FSDiN0x~oT}`%Ma*<#e&?jJI1P3J`LhS6 zdH$qkoHrMnQLeWJ7nQo91tF1?U)4ff`{0F50i?st=@P67tRWxGG0$QUUbx$rv?^II z!F=Jm%OlQNEI?Nq-H7#xpAwucVO$X($1*ke5i->Fd$E4!KEb-WxH5@OTXT)2tNTDz1`H&e?j&QRNEQ4pnpLtP2%bct6r=E-D zuEi&%n0M*oARJ5~Uzq0z@7kL|biCM|bj#}97nICE8xwBCSUU0qJBZ-z@S6-2|@GA7{J4On;gJsck4#>LmdsOWWF zPhi{Z3UQQYB&$`6qCU9Wxn*S2$D>@WU<@yuB^Xa%N5rWv-ek$B!xEeUU@C}adxorJ z#p~3?q;J{{3C;j;)#u~YPR*XD(rvbaxJ<~Cpr^uA5Y6`OjZ^4@ZcfCjpp6W@6MAjj zmdWT-cL!86Ppw9ha(WZpv2hhy>zT~?Al#8dUtua~y9?;$YjcRzmCsT{%n0e1Z9gOq z*~GQ;tzIMTbJl%d*g7NaO z45P?wJnn`Gdj4w(LtLM~6?f`6hq%6};cOSykVp8qnB)6h-N>tiw;TeN$J>>>b0~J` zHiv|MZsIHv#+<{oL=aBoS>g#bZsft=O%lutmI2XBTfIrZIA=DI>V9$SAk+qcs}DPe z(}+P48wV0QQx?ezbZX!_2&4Yl+3S|(*e+!jY1T%Ai+zQ4=WCU!cNERdb|r_d{gz-& zU>SU^){jr1`@@~c?10wX7YnpL`1QiL=VwpSe{b0m!OKWi<-1FfD>@^`DTpq8&n=m(j@|4WCa1o&_|mM$A1WS^KABi+*e7;3IEB*|foddB zM}ytCNAAEHl{3hcc5fwEE9iI7AK5o&^-es(QzX+`7;^1s%k*8QbkIPKJ-jK@(O`&# zXl!aahO~(7%pqVZSe_unM9E2lZn2r-K2E0^SMk!bJc$h*T@ zE^-pi5=2hnFXQ0)+rkGcTeJ8HTnEt(`|4|5ZV&cXlVr<2Ew%1Bie*v2%v*m2{G-6WQKkG8bhE(L6%A zKqPP9MdL#`hMZOy^e(u<2|{p!CAqT85_=jAkf8z|)bZjG1I=&YypDP#_RBENYoQPF z9yLH?BEFYyO!llB&8;}lA9=N&7oRrcBeONgwYsUC*TVG`Dp0Z8rTi(l>AVK12z26J zgM#_O^4Q(P?cvzNvn81uGoABusAdE`n7s-3cr$AKbCA{OrApZ^d_GQF7$j!c9-&aP z1ZtVEcV%Avg&#x;q@iLK=TR_Us1C)xibDRO1rOHaiS1X*;>t8|N=GVbte(hB;N86DZo2PSY6r360jKKs+)0fa1V?DCSmc3>M z^kksV!}W^2mC|VdefzB+>DJtuD+8k8dc{ss3%Ak}f&uxf*k1nE<`W(7YJxUwNuW@3 zfS(!q24_+qmn2*<&6iu%+D_OmrMAB$KCj(G;aLrv8M>Fy%k(9#IqA-MEldSZUYM%m zJ1Y|T$pOnx`f&aM)$pLNurHRCVff6{i@0wG4;h{zLVM-U0Fv(d;MqB6@SIhPxKjg& z=Jl_1Gfi;b$b3b{fe;z0Wc_7&5T`dC6uU0p^@onvtRfrycx*OKd%u(`1FC&NO)sVi z7}XD-)nr7fk|i?q37CpkFtccL8&$?u;qDrXIctX&&aY|?Q^(VG=WpPNwu?Etf))-f zpM4ul&!TTFF5vsROJz8}!W97Sa0Fpb;2Anv{|0tCyoj?BIOZ@XL3p@7hfb`XK!zSO zkQe8tO0OzUi8U^3Ia`7@#_m{hMv}P+IcRLlVRAY9f>>N`r_kSI!l^~V*_FjjoLh`z zox<^#$3C3q860O`5$JVrKm6fA26p)B&CPId1o`opcE2Om`85N(?OrWIolKYtqS@P- z;os5JcfQ#6PynaU1QGlUH`BWeHBSt|gR28%I1j>chU3p74#O^pblgTD|O-xUJ z{Q^;EhB5klQ7J=3LZ~RnYa1$&DzR>5QJ0^*o+U)^eWgFR6P*$? zD}PfBKOXsK^TeR=^LhGP4^zJ77TpW5xsN+}d13K^1&brg3AtPWah*tmo-^<->&oHY89(OfF-n~_?FrU5e8(Wv6 zc%*(2nEgF(Zi-?Ed+T>wo9R-3&u)dm)8V2Zn3(k;d(VuKTfe@i$X+sCy04$0@Z7vc zHORzCGI;5#aM*7qI+Z#}?%xM0K9s7}@vSVhN#GDCdAn*>5k$azA)2W)j|(Kd;)0~7 zyG|=$URl^#s>nQMrSD}bX0LRXsw!1^F-Gc_#-Fnn#*#GzDR`GlAx!mQsk3z9OKD#I t$UhPKCi98+tJji_)1x9-Iz+>=S+wj1d+hfpSni+Ko@+VmH`pdY_ + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-05T11:41:05 + 2023-07-05T11:41:05 + + Z_UP + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.498039 0.498039 0.498039 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + 6.35892e-4 3.26574e-4 0.00350511 -0.01336407 -0.0016734 0.00350511 -0.01336407 3.26574e-4 0.00350511 6.35892e-4 -0.0016734 0.00350511 6.35892e-4 3.26574e-4 0.00350511 -0.01336407 3.26574e-4 0.00350511 -0.01336407 3.26574e-4 0.004505097 6.35892e-4 3.26574e-4 0.004505097 -0.01336407 3.26574e-4 0.004505097 6.35892e-4 -0.0016734 0.004505097 6.35892e-4 3.26574e-4 0.004505097 -0.01336407 -0.0016734 0.004505097 6.35892e-4 -0.0016734 0.009005129 6.35892e-4 -0.0016734 0.004505097 -0.01336407 -0.0016734 0.004505097 -0.01336407 -0.0016734 0.009005129 -0.01336407 -0.0016734 -9.94861e-4 6.35892e-4 -0.0016734 0.00350511 6.35892e-4 -0.0016734 -9.94861e-4 -0.01336407 -0.0016734 0.00350511 -0.01336407 -0.0016734 0.004505097 -0.01336407 -0.00341767 0.009005129 -0.01336407 -0.0016734 0.009005129 -0.01336407 3.26574e-4 0.004505097 -0.01336407 3.26574e-4 0.00350511 -0.01336407 -0.0016734 0.00350511 -0.01336407 -0.003542602 -9.94861e-4 -0.01336407 -0.0016734 -9.94861e-4 -0.01336407 -0.0016734 0.009005129 6.35892e-4 -0.002980709 0.009005129 6.35892e-4 -0.0016734 0.009005129 -0.01336407 -0.00341767 0.009005129 6.35892e-4 -0.0016734 0.00350511 6.35892e-4 -0.00310564 -9.94861e-4 6.35892e-4 -0.0016734 -9.94861e-4 6.35892e-4 3.26574e-4 0.00350511 6.35892e-4 3.26574e-4 0.004505097 6.35892e-4 -0.0016734 0.004505097 6.35892e-4 -0.002980709 0.009005129 6.35892e-4 -0.0016734 0.009005129 -0.01336407 -0.0016734 -9.94861e-4 6.35892e-4 -0.00310564 -9.94861e-4 -0.01336407 -0.003542602 -9.94861e-4 6.35892e-4 -0.0016734 -9.94861e-4 0.01265186 3.36054e-4 0.1240051 0.02565187 -0.00167334 0.1240051 0.01266384 -0.002318084 0.1240051 -0.01636308 0.002059459 0.1240051 -0.01339608 0.004263997 0.1240051 -3.7311e-4 0.002322435 0.1240051 -0.01636308 -3.99486e-4 0.1240051 -3.53113e-4 -0.002815306 0.1240051 -0.01336407 -0.003222346 0.1240051 -0.01339507 0.005036234 -0.1129949 -0.01636308 0.002879619 -0.03398483 -0.01636308 0.002835273 -0.1129949 -0.01339608 0.004822194 0.0449391 -0.01636308 0.002621054 0.04501509 -0.01339507 0.005079627 -0.03406083 -0.01339608 0.004263997 0.1240051 -0.01636308 0.002059459 0.1240051 -0.01636308 -6.45446e-4 0.005516111 -0.01636308 0.002621054 0.04501509 -0.01636308 0.002059459 0.1240051 -0.01636308 -6.04826e-4 -0.1129949 -0.01636308 0.002835273 -0.1129949 -0.01636308 0.002879619 -0.03398483 -0.01636308 -3.99486e-4 0.1240051 -0.01636308 -6.45446e-4 0.005516111 -0.01336407 -0.00257498 0.04744213 -0.01336407 -0.00341767 0.009005129 -0.01336407 -0.003424763 -0.1129949 -0.01636308 -6.04826e-4 -0.1129949 -0.01336407 -0.003697931 -0.05675482 -0.01336407 -0.003542602 -9.94861e-4 -0.01636308 -3.99486e-4 0.1240051 -0.01336407 -0.003222346 0.1240051 -0.01336407 -0.002509891 0.08577609 6.35892e-4 -0.00310564 -9.94861e-4 -0.01336407 -0.003697931 -0.05675482 -0.01336407 -0.003542602 -9.94861e-4 0.01641988 -0.002368807 -0.1129949 0.001980841 -0.002941489 -0.1129949 0.01602286 -0.002447128 0.005568087 6.35892e-4 -0.002980709 0.009005129 -0.01336407 -0.00257498 0.04744213 -0.01336407 -0.002509891 0.08577609 -0.01336407 -0.003424763 -0.1129949 0.01266384 -0.002318084 0.1240051 0.02829986 -0.001702785 0.07664513 0.03063684 -0.00166434 -0.1129949 0.03129088 -0.001697301 -0.06555485 0.03111886 -0.001714706 -0.01813483 0.03012186 -0.001716554 0.0292651 0.02565187 -0.00167334 0.1240051 -3.53113e-4 -0.002815306 0.1240051 0.001290857 -0.003006875 0.005568087 -0.01336407 -0.003222346 0.1240051 -0.01336407 -0.00341767 0.009005129 0.01593285 6.05914e-4 -0.1129949 0.03129088 -0.001697301 -0.06555485 0.01624584 6.12084e-4 -0.03393882 0.001193881 0.002905726 -0.03393882 0.01531386 4.96144e-4 0.04506111 9.94891e-4 0.002678275 0.04506111 -0.01339608 0.004263997 0.1240051 -3.7311e-4 0.002322435 0.1240051 0.03012186 -0.001716554 0.0292651 0.01265186 3.36054e-4 0.1240051 0.02829986 -0.001702785 0.07664513 0.02565187 -0.00167334 0.1240051 0.03111886 -0.001714706 -0.01813483 0.00226587 0.002699494 -0.1129949 0.03063684 -0.00166434 -0.1129949 -0.01339507 0.005079627 -0.03406083 -0.01339507 0.005036234 -0.1129949 -0.01339608 0.004822194 0.0449391 -0.01136308 0.001115202 -0.1079948 -0.009961068 0.002030968 -0.1079948 -0.01011711 0.002084612 -0.1079948 -0.01076406 0.002030968 -0.1079948 -0.01104009 0.001850903 -0.1079948 -0.01115208 0.001729428 -0.1079948 -0.01091009 0.00195235 -0.1079948 -0.01124209 0.001591145 -0.1079948 -0.01060807 0.002084612 -0.1079948 -0.01130908 0.001439929 -0.1079948 -0.01044505 0.002111792 -0.1079948 -0.01028007 0.002111792 -0.1079948 -0.01134908 0.001279771 -0.1079948 -0.01124209 6.39164e-4 -0.1079948 -0.009685099 0.001850903 -0.1079948 -0.01130807 7.90444e-4 -0.1079948 -0.01134908 9.50594e-4 -0.1079948 -0.00981611 0.00195235 -0.1079948 -0.009574115 0.001729428 -0.1079948 -0.01115208 5.00884e-4 -0.1079948 -0.009483098 0.001591145 -0.1079948 -0.01076406 1.99354e-4 -0.1079948 -0.009363114 0.001115202 -0.1079948 -0.009376108 0.001279771 -0.1079948 -0.01104009 3.79364e-4 -0.1079948 -0.01090908 2.77934e-4 -0.1079948 -0.009417057 0.001439929 -0.1079948 -0.009417057 7.90684e-4 -0.1079948 -0.01028007 1.18694e-4 -0.1079948 -0.009483098 6.39484e-4 -0.1079948 -0.009376108 9.50594e-4 -0.1079948 -0.01060807 1.45774e-4 -0.1079948 -0.01044505 1.18634e-4 -0.1079948 -0.009685099 3.79724e-4 -0.1079948 -0.009961068 1.99614e-4 -0.1079948 -0.009815096 2.78264e-4 -0.1079948 -0.009573101 5.01244e-4 -0.1079948 -0.01011711 1.45934e-4 -0.1079948 -0.01011806 1.45774e-4 -0.1129949 -0.01028007 1.18634e-4 -0.1129949 0.001980841 -0.002941489 -0.1129949 -0.01636308 0.002835273 -0.1129949 -0.01091009 0.00195235 -0.1129949 -0.01076406 0.002030968 -0.1129949 -0.009376108 0.001279771 -0.1129949 -0.009363114 0.001115202 -0.1129949 0.00226587 0.002699494 -0.1129949 -0.009483098 0.001591145 -0.1129949 -0.009417057 0.001439929 -0.1129949 0.01641988 -0.002368807 -0.1129949 0.01593285 6.05914e-4 -0.1129949 0.03063684 -0.00166434 -0.1129949 -0.01134908 0.001279771 -0.1129949 -0.01136308 0.001115202 -0.1129949 -0.01636308 -6.04826e-4 -0.1129949 -0.01011711 0.002084612 -0.1129949 -0.009961068 0.002030968 -0.1129949 -0.01124209 0.001591145 -0.1129949 -0.01130908 0.001439929 -0.1129949 -0.01028007 0.002111792 -0.1129949 -0.01339507 0.005036234 -0.1129949 -0.01104009 0.001850903 -0.1129949 -0.01115208 0.001729428 -0.1129949 -0.01060807 0.002084612 -0.1129949 -0.01044505 0.002111792 -0.1129949 -0.009685099 0.001850903 -0.1129949 -0.00981611 0.00195235 -0.1129949 -0.009574115 0.001729428 -0.1129949 -0.009376108 9.50594e-4 -0.1129949 -0.01044607 1.18694e-4 -0.1129949 -0.009417057 7.90444e-4 -0.1129949 -0.009483098 6.39164e-4 -0.1129949 -0.009574115 5.00884e-4 -0.1129949 -0.009686112 3.79364e-4 -0.1129949 -0.00981611 2.77934e-4 -0.1129949 -0.009961068 1.99354e-4 -0.1129949 -0.01336407 -0.003424763 -0.1129949 -0.01076507 1.99614e-4 -0.1129949 -0.01060909 1.45934e-4 -0.1129949 -0.01104009 3.79724e-4 -0.1129949 -0.01091009 2.78264e-4 -0.1129949 -0.01124209 6.39484e-4 -0.1129949 -0.01115208 5.01244e-4 -0.1129949 -0.01134908 9.50594e-4 -0.1129949 -0.01130908 7.90684e-4 -0.1129949 -0.01134908 0.001279771 -0.1079948 -0.01136308 0.001115202 -0.1129949 -0.01136308 0.001115202 -0.1079948 -0.01115208 0.001729428 -0.1079948 -0.01124209 0.001591145 -0.1129949 -0.01124209 0.001591145 -0.1079948 -0.01130908 0.001439929 -0.1079948 -0.01130908 0.001439929 -0.1129949 -0.01134908 0.001279771 -0.1129949 -0.01091009 0.00195235 -0.1129949 -0.01091009 0.00195235 -0.1079948 -0.01076406 0.002030968 -0.1079948 -0.01115208 0.001729428 -0.1129949 -0.01104009 0.001850903 -0.1079948 -0.01104009 0.001850903 -0.1129949 -0.01044505 0.002111792 -0.1079948 -0.01028007 0.002111792 -0.1079948 -0.01044505 0.002111792 -0.1129949 -0.01060807 0.002084612 -0.1079948 -0.01060807 0.002084612 -0.1129949 -0.01076406 0.002030968 -0.1129949 -0.00981611 0.00195235 -0.1079948 -0.009961068 0.002030968 -0.1129949 -0.009961068 0.002030968 -0.1079948 -0.01011711 0.002084612 -0.1129949 -0.01028007 0.002111792 -0.1129949 -0.01011711 0.002084612 -0.1079948 -0.009574115 0.001729428 -0.1129949 -0.009574115 0.001729428 -0.1079948 -0.009483098 0.001591145 -0.1079948 -0.00981611 0.00195235 -0.1129949 -0.009685099 0.001850903 -0.1079948 -0.009685099 0.001850903 -0.1129949 -0.009376108 0.001279771 -0.1079948 -0.009363114 0.001115202 -0.1079948 -0.009376108 0.001279771 -0.1129949 -0.009417057 0.001439929 -0.1079948 -0.009417057 0.001439929 -0.1129949 -0.009483098 0.001591145 -0.1129949 -0.009483098 6.39484e-4 -0.1079948 -0.009417057 7.90444e-4 -0.1129949 -0.009417057 7.90684e-4 -0.1079948 -0.009376108 9.50594e-4 -0.1129949 -0.009363114 0.001115202 -0.1129949 -0.009376108 9.50594e-4 -0.1079948 -0.009686112 3.79364e-4 -0.1129949 -0.009685099 3.79724e-4 -0.1079948 -0.009815096 2.78264e-4 -0.1079948 -0.009483098 6.39164e-4 -0.1129949 -0.009573101 5.01244e-4 -0.1079948 -0.009574115 5.00884e-4 -0.1129949 -0.01011711 1.45934e-4 -0.1079948 -0.01028007 1.18694e-4 -0.1079948 -0.01011806 1.45774e-4 -0.1129949 -0.009961068 1.99614e-4 -0.1079948 -0.009961068 1.99354e-4 -0.1129949 -0.00981611 2.77934e-4 -0.1129949 -0.01044505 1.18634e-4 -0.1079948 -0.01060807 1.45774e-4 -0.1079948 -0.01044607 1.18694e-4 -0.1129949 -0.01028007 1.18634e-4 -0.1129949 -0.01060909 1.45934e-4 -0.1129949 -0.01076406 1.99354e-4 -0.1079948 -0.01090908 2.77934e-4 -0.1079948 -0.01076507 1.99614e-4 -0.1129949 -0.01104009 3.79364e-4 -0.1079948 -0.01091009 2.78264e-4 -0.1129949 -0.01104009 3.79724e-4 -0.1129949 -0.01115208 5.00884e-4 -0.1079948 -0.01124209 6.39164e-4 -0.1079948 -0.01115208 5.01244e-4 -0.1129949 -0.01130807 7.90444e-4 -0.1079948 -0.01124209 6.39484e-4 -0.1129949 -0.01130908 7.90684e-4 -0.1129949 -0.01134908 9.50594e-4 -0.1079948 -0.01134908 9.50594e-4 -0.1129949 + + + + + + + + + + 0 0 1 0 -1 0 0 0 -1 1 0 0 1 -8.02641e-7 0 -1 0 0 -1 -3.17502e-7 0 0 0 1 -2.53226e-6 0 1 1.6845e-6 0 1 -3.83453e-7 0 1 -0.5956508 0.8032435 -4.51083e-4 -0.5957676 0.8031464 0.004120051 -0.5954586 0.8033853 0.001068115 -0.5957332 0.8031716 0.004181087 -0.5963758 0.8026856 0.005646049 -0.5954885 0.8033639 -4.41717e-4 -0.5954586 0.8033853 0.001098632 -1 -5.59476e-7 0 -0.6886266 -0.724942 0.01589405 -0.6850206 -0.7285152 -0.003538429 -0.6865319 -0.727092 -0.003357112 -0.7145746 -0.6995592 -2.44153e-4 -0.6842895 -0.729152 0.009247124 -0.6911019 -0.72275 0.0032655 -0.5624081 -0.8268571 0.00213629 -0.6783512 -0.7346287 -0.01266545 -0.6844679 -0.7289862 0.009105741 -0.6853399 -0.7280974 -0.01355051 -0.5678427 -0.8231368 8.8506e-4 0.03839308 -0.9992578 0.003143429 0.03119075 -0.9995097 0.002777218 0.04352062 -0.9990521 -9.46101e-4 0.04428344 -0.9990187 -8.5454e-4 0.04449665 -0.9990084 0.001556456 0.03689754 -0.9993163 -0.002349913 -0.01403892 -0.9998771 0.006988942 -0.02075314 -0.9997844 -8.24023e-4 -0.01812815 -0.999828 0.003936886 0.03147572 -0.9994928 -0.004854559 0.04693853 -0.9988948 0.002472043 0.04349005 -0.9990504 0.002655148 0.04947173 -0.9987747 -0.00137335 0.04706048 -0.998892 -5.49345e-4 0.04846411 -0.998825 0 0.04849445 -0.9988217 0.001922667 0.04956287 -0.9987653 0.00338757 0.02832138 -0.9995802 -0.006134212 0.03033584 -0.9994973 0.009216725 0.02561694 -0.9995939 0.01248991 0.03125125 -0.9993383 -0.01861643 0.0311923 -0.9992733 0.0219087 0.1517704 0.9884154 -9.46086e-4 0.1516167 0.9884386 0.001281738 0.1510067 0.9885327 -4.883e-4 0.1489924 0.9888375 0.001342773 0.1489951 0.9888247 0.005127191 0.1516193 0.9884254 0.005188226 0.1474354 0.989047 0.006988704 0.1490874 0.9887991 0.00701946 0.1517098 0.9884181 0.003753781 0.151498 0.9884301 0.007385671 0.1527473 0.9882338 0.00790435 0.1508884 0.9885266 0.006927907 0.1517998 0.9884078 0.002655088 0.1494536 0.9887686 -6.10389e-4 0.1525638 0.9882927 -0.001403868 0.1473854 0.989079 -5.43821e-4 0.1475734 0.989051 -5.79269e-4 0.1473448 0.9890844 0.001312255 0.1472834 0.9890815 0.005066096 -1.25132e-5 0 -1 -2.77334e-4 0 -1 1.15119e-4 0 -1 -4.61182e-5 0 -1 -9.58777e-5 0 -1 -8.44802e-5 0 -1 -7.18203e-5 0 -1 1.68306e-4 0 -1 1.06344e-4 0 -1 1.89105e-5 0 -1 5.07886e-5 0 -1 -5.47599e-5 0 -1 4.47855e-5 0 -1 -3.31955e-5 0 -1 1.26946e-5 0 -1 5.97279e-5 0 -1 -7.0258e-5 0 -1 -3.26238e-6 0 -1 1.34642e-6 0 -1 -1.02394e-6 0 -1 3.43602e-5 0 -1 -1.69203e-6 0 -1 -1.91469e-5 0 -1 -1.26169e-5 0 -1 -1.51109e-6 0 -1 -4.43626e-6 0 -1 3.41803e-5 0 -1 2.72333e-6 0 -1 1.45755e-5 0 -1 1.71911e-6 0 -1 4.70524e-6 0 -1 -1.5141e-5 0 -1 -1.6234e-5 0 -1 -9.22317e-7 0 -1 1.77313e-5 0 -1 0 0 -1 2.83212e-6 0 -1 -9.13509e-6 0 -1 3.01227e-6 0 -1 3.41599e-5 0 -1 1.62924e-5 0 -1 -1.63305e-5 0 -1 -7.20755e-6 0 -1 3.43502e-5 0 -1 0.9864483 -0.1640723 0 0.789464 -0.613797 0 0.8790117 -0.4768002 0 0.9457473 -0.3249033 0 0.5465675 -0.837415 0 0.4008989 -0.9161224 0 0.6775027 -0.7355203 0 0.6775193 -0.7355052 0 0.08249235 -0.9965918 0 -0.08252263 -0.9965893 0 0.245615 -0.9693675 0 -0.5462343 -0.8376325 0 -0.4022129 -0.9155463 0 -0.245615 -0.9693675 0 -0.7892915 -0.6140188 0 -0.8791093 -0.4766203 0 -0.6777895 -0.7352561 0 -0.986469 -0.1639486 0 -0.945694 -0.3250585 0 -0.8802849 0.4744456 0 -0.9456312 0.325241 0 -0.9457159 0.3249945 0 -0.9864739 0.1639189 0 -0.9864434 0.164102 0 -0.6775027 0.7355203 6.1039e-5 -0.5467164 0.8373178 3.05189e-5 -0.677551 0.735476 6.10379e-5 -0.8791615 0.476524 3.0519e-5 -0.7879402 0.6157519 9.15571e-5 -0.7894377 0.6138308 3.05191e-5 -0.2459235 0.9692893 0 -0.2448831 0.9695527 0 -0.0828889 0.9965589 0 -0.4011742 0.9160017 0 -0.5476588 0.8367018 0 -0.4011486 0.916013 0 0.08218669 0.996617 0 0.08285856 0.9965614 0 0.245371 0.9694292 0 -0.08270698 0.996574 0 0.2459523 0.969282 0 0.4020256 0.9156284 -3.05189e-5 0.5461421 0.8376925 -3.05193e-5 0.4024512 0.9154415 0 0.5478783 0.8365581 0 0.6761834 0.7367334 0 0.6775662 0.7354619 3.05196e-5 0.7894903 0.6137632 3.05188e-5 0.8803299 0.4743618 3.05193e-5 0.789464 0.613797 3.05189e-5 0.8789989 0.4768238 -3.05187e-5 0.945694 0.3250585 -6.10381e-5 0.9456626 0.3251497 -6.10381e-5 0.9859827 0.1668483 -6.10383e-5 0.9864236 0.1642208 0 + + + + + + + + + + + + + + +

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

+ + + + + + + 0.000999987 -0.004499971 5e-4 0.000999987 -0.004499971 -5e-4 1.98119e-4 -8.91535e-4 -5e-4 1.98119e-4 -8.91535e-4 5e-4 0.0139994 -0.002500057 5e-4 0.000999987 -0.004499971 -5e-4 0.000999987 -0.004499971 5e-4 0.0139994 -0.002500057 -5e-4 -2.05869e-4 -5.07125e-4 -5e-4 0.01349997 -5e-4 -5e-4 -2.89975e-4 -5e-4 -5e-4 1.98119e-4 -8.91535e-4 -5e-4 0.01395899 -0.002202689 -5e-4 0.01390826 -0.001907825 -5e-4 -4.71754e-5 -5.62909e-4 -5e-4 -1.24159e-4 -5.28295e-4 -5e-4 2.2889e-5 -6.09979e-4 -5e-4 8.40373e-5 -6.68164e-4 -5e-4 1.34527e-4 -7.35806e-4 -5e-4 1.72919e-4 -8.10977e-4 -5e-4 0.000999987 -0.004499971 -5e-4 0.0139994 -0.002500057 -5e-4 0.01384729 -0.001615524 -5e-4 0.013776 -0.001325726 -5e-4 0.01369446 -0.001038491 -5e-4 0.01360255 -7.53803e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 -4.71754e-5 -5.62909e-4 5e-4 -1.24159e-4 -5.28295e-4 5e-4 0.01349997 -5e-4 5e-4 1.72919e-4 -8.10977e-4 5e-4 1.34527e-4 -7.35806e-4 5e-4 1.98119e-4 -8.91535e-4 5e-4 0.01360255 -7.53803e-4 5e-4 0.01369446 -0.001038491 5e-4 2.2889e-5 -6.09979e-4 5e-4 8.40373e-5 -6.68164e-4 5e-4 -2.05869e-4 -5.07125e-4 5e-4 0.01350045 -4.71615e-4 5e-4 -2.89975e-4 -5e-4 5e-4 0.013776 -0.001325726 5e-4 0.01384729 -0.001615524 5e-4 0.01390826 -0.001907825 5e-4 0.01395899 -0.002202689 5e-4 0.000999987 -0.004499971 5e-4 0.0139994 -0.002500057 5e-4 1.34527e-4 -7.35806e-4 -5e-4 1.34527e-4 -7.35806e-4 5e-4 1.72919e-4 -8.10977e-4 5e-4 1.98119e-4 -8.91535e-4 5e-4 1.98119e-4 -8.91535e-4 -5e-4 1.72919e-4 -8.10977e-4 -5e-4 2.2889e-5 -6.09979e-4 5e-4 -4.71754e-5 -5.62909e-4 -5e-4 -4.71754e-5 -5.62909e-4 5e-4 2.2889e-5 -6.09979e-4 -5e-4 8.40373e-5 -6.68164e-4 5e-4 8.40373e-5 -6.68164e-4 -5e-4 -1.24159e-4 -5.28295e-4 5e-4 -2.05869e-4 -5.07125e-4 -5e-4 -2.05869e-4 -5.07125e-4 5e-4 -1.24159e-4 -5.28295e-4 -5e-4 -2.89975e-4 -5e-4 5e-4 -2.89975e-4 -5e-4 -5e-4 0.01384729 -0.001615524 5e-4 0.013776 -0.001325726 -5e-4 0.01384729 -0.001615524 -5e-4 0.01390826 -0.001907825 -5e-4 0.01390826 -0.001907825 5e-4 0.01395899 -0.002202689 -5e-4 0.01395899 -0.002202689 5e-4 0.0139994 -0.002500057 5e-4 0.0139994 -0.002500057 -5e-4 0.013776 -0.001325726 5e-4 0.01369446 -0.001038491 -5e-4 0.01369446 -0.001038491 5e-4 0.01360255 -7.53803e-4 5e-4 0.01360255 -7.53803e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 0.01350045 -4.71615e-4 5e-4 0.01349997 -5e-4 0.004999995 -2.89975e-4 -5e-4 5e-4 -5e-4 -5e-4 0.004999995 -5e-4 -5e-4 -0.004999995 -2.89975e-4 -5e-4 -5e-4 0.01349997 -5e-4 -5e-4 0.01349997 -5e-4 -0.004999995 0.01349997 -5e-4 5e-4 0.01349997 5e-4 0.004999995 0.01349997 5e-4 -0.004999995 0.01350045 -4.71615e-4 5e-4 0.01349997 -5e-4 0.004999995 0.01349997 -5e-4 -0.004999995 0.01349997 -5e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 0.01349997 -5e-4 5e-4 -5e-4 -5e-4 0.004999995 -5e-4 5e-4 0.004999995 0.01349997 5e-4 0.004999995 0.01349997 -5e-4 0.004999995 -5e-4 -5e-4 -0.004999995 -5e-4 5e-4 -0.004999995 -5e-4 5e-4 0.004999995 -5e-4 -5e-4 0.004999995 0.01349997 5e-4 -0.004999995 -5e-4 5e-4 -0.004999995 -5e-4 -5e-4 -0.004999995 0.01349997 -5e-4 -0.004999995 -5e-4 5e-4 0.004999995 -5e-4 5e-4 -0.004999995 0 5e-4 7e-4 0 5e-4 -7e-4 0.01349997 5e-4 -0.004999995 0.01304668 5e-4 -7e-4 0.01349997 5e-4 0.004999995 0.01304668 5e-4 7e-4 0.01304525 5.02356e-4 6.69369e-4 0 5e-4 7e-4 0 5.02462e-4 6.68713e-4 0 5.38197e-4 5.82443e-4 0.01302689 5.35564e-4 5.86251e-4 0 5.21799e-4 6.09202e-4 0 5.09789e-4 6.38197e-4 0.01303517 5.20529e-4 6.11725e-4 0.01304137 5.0931e-4 6.39671e-4 0.01299178 5.97314e-4 5.28303e-4 0 5.82443e-4 5.38197e-4 0 6.09202e-4 5.21799e-4 0.0130167 5.53746e-4 5.63605e-4 0 5.58579e-4 5.58579e-4 0.01300495 5.74514e-4 5.4422e-4 0.01296305 6.47245e-4 5.07011e-4 0 6.38197e-4 5.09789e-4 0 6.68713e-4 5.02462e-4 0.01297777 6.21703e-4 5.1589e-4 0 7e-4 5e-4 0.01294785 6.73484e-4 5.01805e-4 0.01293236 7e-4 5e-4 0.01304668 5e-4 7e-4 2.21952e-4 0.01132625 5e-4 0.0115 0.002499997 -5e-4 0.0115 0.002499997 5e-4 2.21952e-4 0.01132625 -5e-4 2.90924e-7 0.01156806 -5e-4 2.90924e-7 0.01156806 5e-4 -5.45318e-5 0.01166325 5e-4 -9.8578e-5 0.01176398 5e-4 -9.8578e-5 0.01176398 -5e-4 -5.45318e-5 0.01166325 -5e-4 1.39249e-4 0.01139867 5e-4 1.39249e-4 0.01139867 -5e-4 2.21952e-4 0.01132625 -5e-4 6.52065e-5 0.01147949 5e-4 6.52065e-5 0.01147949 -5e-4 2.21952e-4 0.01132625 5e-4 -0.002154469 0.01727068 5e-4 -9.8578e-5 0.01176398 -5e-4 -9.8578e-5 0.01176398 5e-4 -0.002154469 0.01727068 -5e-4 -0.005992531 0.01667195 5e-4 -0.005999982 0.01649999 5e-4 -0.005999982 0.01649999 -5e-4 -0.005883276 0.01717305 5e-4 -0.00593388 0.01700979 5e-4 -0.00593388 0.01700979 -5e-4 -0.005970597 0.01684159 5e-4 -0.005992531 0.01667195 -5e-4 -0.005970597 0.01684159 -5e-4 -0.005740702 0.01748478 -5e-4 -0.005649507 0.01763087 5e-4 -0.005740702 0.01748478 5e-4 -0.005883276 0.01717305 -5e-4 -0.005818367 0.01733255 -5e-4 -0.005818367 0.01733255 5e-4 -0.005432128 0.01789599 5e-4 -0.005432128 0.01789599 -5e-4 -0.005307674 0.01801317 5e-4 -0.005546927 0.01776766 5e-4 -0.005649507 0.01763087 -5e-4 -0.005546927 0.01776766 -5e-4 -0.004878759 0.01829659 5e-4 -0.005030035 0.01821428 5e-4 -0.005030035 0.01821428 -5e-4 -0.005172669 0.01812005 -5e-4 -0.005172669 0.01812005 5e-4 -0.005307674 0.01801317 -5e-4 -0.00455904 0.01842015 -5e-4 -0.004392981 0.01846098 5e-4 -0.00455904 0.01842015 5e-4 -0.004878759 0.01829659 -5e-4 -0.004722118 0.01836508 -5e-4 -0.004722118 0.01836508 5e-4 -0.00405234 0.01849925 5e-4 -0.00405234 0.01849925 -5e-4 -0.003880143 0.01849639 5e-4 -0.004222869 0.01848745 5e-4 -0.004392981 0.01846098 -5e-4 -0.004222869 0.01848745 -5e-4 -0.003376424 0.01840025 5e-4 -0.003540933 0.01844656 5e-4 -0.003540933 0.01844656 -5e-4 -0.003710091 0.01847887 -5e-4 -0.003710091 0.01847887 5e-4 -0.003880143 0.01849639 -5e-4 -0.003061056 0.0182659 -5e-4 -0.00291264 0.01817846 5e-4 -0.003061056 0.0182659 5e-4 -0.003376424 0.01840025 -5e-4 -0.003215253 0.01833957 -5e-4 -0.003215253 0.01833957 5e-4 -0.002773225 0.01807957 5e-4 -0.00291264 0.01817846 -5e-4 -0.002773225 0.01807957 -5e-4 -0.002641916 0.01796817 5e-4 -0.002641916 0.01796817 -5e-4 -0.002521514 0.01784688 5e-4 -0.002411127 0.01771467 5e-4 -0.002521514 0.01784688 -5e-4 -0.002411127 0.01771467 -5e-4 -0.002313196 0.01757454 5e-4 -0.002313196 0.01757454 -5e-4 -0.002227604 0.01742655 5e-4 -0.002154469 0.01727068 5e-4 -0.002227604 0.01742655 -5e-4 -0.002154469 0.01727068 -5e-4 -0.005999982 0.008914172 5e-4 -0.005999982 0.01649999 -5e-4 -0.005999982 0.01649999 5e-4 -0.005999982 0.008914172 -5e-4 -0.005781888 0.008290827 5e-4 -0.005707085 0.008207082 5e-4 -0.005707085 0.008207082 -5e-4 -0.005943894 0.008583962 5e-4 -0.005900979 0.008480429 5e-4 -0.005900979 0.008480429 -5e-4 -0.005846798 0.00838238 5e-4 -0.005781888 0.008290827 -5e-4 -0.005846798 0.00838238 -5e-4 -0.005993664 0.008802056 -5e-4 -0.005993664 0.008802056 5e-4 -0.005974948 0.008691906 -5e-4 -0.005943894 0.008583962 -5e-4 -0.005974948 0.008691906 5e-4 -0.005999982 0.008914172 5e-4 -0.005999982 0.008914172 -5e-4 -2.92893e-4 0.002792835 5e-4 -0.005707085 0.008207082 -5e-4 -0.005707085 0.008207082 5e-4 -2.92893e-4 0.002792835 -5e-4 -2.51435e-5 0.002308547 -5e-4 -2.51435e-5 0.002308547 5e-4 -6.31239e-6 0.002197861 5e-4 0 0.002085745 5e-4 0 0.002085745 -5e-4 -6.31239e-6 0.002197861 -5e-4 -9.90717e-5 0.002519726 5e-4 -1.53405e-4 0.002617955 -5e-4 -1.53405e-4 0.002617955 5e-4 -9.90717e-5 0.002519726 -5e-4 -5.61788e-5 0.002416193 5e-4 -5.61788e-5 0.002416193 -5e-4 -2.18067e-4 0.00270909 5e-4 -2.18067e-4 0.00270909 -5e-4 -2.92893e-4 0.002792835 -5e-4 -2.92893e-4 0.002792835 5e-4 0 5.09789e-4 6.38197e-4 0 5.02462e-4 -6.68713e-4 0 5.09789e-4 -6.38197e-4 0 5e-4 -7e-4 0 5.02462e-4 6.68713e-4 0 5.38197e-4 -5.82443e-4 0 5.58579e-4 -5.58579e-4 0 5.58579e-4 5.58579e-4 0 5.21799e-4 -6.09202e-4 0 5.38197e-4 5.82443e-4 0 5.21799e-4 6.09202e-4 0 6.38197e-4 -5.09789e-4 0 6.38197e-4 5.09789e-4 0 6.09202e-4 -5.21799e-4 0 6.09202e-4 5.21799e-4 0 5.82443e-4 5.38197e-4 0 5.82443e-4 -5.38197e-4 0 6.68713e-4 -5.02462e-4 0 6.68713e-4 5.02462e-4 0 7e-4 5e-4 0 7e-4 -5e-4 0 0.002085745 -5e-4 0 0.002085745 5e-4 0 5e-4 7e-4 0 6.38197e-4 -5.09789e-4 0.01297765 6.21724e-4 -5.16018e-4 0.01296305 6.47241e-4 -5.07144e-4 0 7e-4 -5e-4 0 6.68713e-4 -5.02462e-4 0.01294785 6.73474e-4 -5.01807e-4 0.01300495 5.74515e-4 -5.44227e-4 0 5.58579e-4 -5.58579e-4 0.0130167 5.53722e-4 -5.63585e-4 0 5.82443e-4 -5.38197e-4 0.01299178 5.9735e-4 -5.28409e-4 0 6.09202e-4 -5.21799e-4 0 5.09789e-4 -6.38197e-4 0.01304137 5.09316e-4 -6.39685e-4 0.01303517 5.20533e-4 -6.11742e-4 0 5.21799e-4 -6.09202e-4 0.01302689 5.35529e-4 -5.86212e-4 0 5.38197e-4 -5.82443e-4 0 5.02462e-4 -6.68713e-4 0.01304525 5.02361e-4 -6.69377e-4 0.01304668 5e-4 -7e-4 0 5e-4 -7e-4 0.01293236 7e-4 -5e-4 0.01297765 6.21724e-4 -5.16018e-4 0.01299178 5.9735e-4 -5.28409e-4 0.01297777 6.21703e-4 5.1589e-4 0.01304137 5.0931e-4 6.39671e-4 0.01304137 5.09316e-4 -6.39685e-4 0.01304525 5.02361e-4 -6.69377e-4 0.01304668 5e-4 -7e-4 0.01304668 5e-4 7e-4 0.01304525 5.02356e-4 6.69369e-4 0.01302689 5.35564e-4 5.86251e-4 0.01302689 5.35529e-4 -5.86212e-4 0.01303517 5.20533e-4 -6.11742e-4 0.01303517 5.20529e-4 6.11725e-4 0.01299178 5.97314e-4 5.28303e-4 0.01300495 5.74515e-4 -5.44227e-4 0.01300495 5.74514e-4 5.4422e-4 0.0130167 5.53722e-4 -5.63585e-4 0.0130167 5.53746e-4 5.63605e-4 0.01296305 6.47241e-4 -5.07144e-4 0.01294785 6.73484e-4 5.01805e-4 0.01294785 6.73474e-4 -5.01807e-4 0.01296305 6.47245e-4 5.07011e-4 0.01293236 7e-4 -5e-4 0.01293236 7e-4 5e-4 0.01258188 0.001242518 -5e-4 0.01258188 0.001242518 5e-4 0.012389 0.001505315 5e-4 0.01276296 9.74095e-4 5e-4 0.01276296 9.74095e-4 -5e-4 0.01196795 0.002013921 5e-4 0.01173985 0.00225979 5e-4 0.01196795 0.002013921 -5e-4 0.01218438 0.001762449 5e-4 0.01218438 0.001762449 -5e-4 0.012389 0.001505315 -5e-4 0.01173985 0.00225979 -5e-4 0.0115 0.002499997 5e-4 0.0115 0.002499997 -5e-4 -0.004992663 0.01312065 5e-4 -0.004999995 0.01299995 -5e-4 -0.004999995 0.01299995 5e-4 -0.004885435 0.01346457 5e-4 -0.004935026 0.01335448 -5e-4 -0.004935026 0.01335448 5e-4 -0.004970967 0.01323896 5e-4 -0.004970967 0.01323896 -5e-4 -0.004992663 0.01312065 -5e-4 -0.004748642 0.01366287 -5e-4 -0.004748642 0.01366287 5e-4 -0.004663169 0.01374846 5e-4 -0.004885435 0.01346457 -5e-4 -0.004823088 0.01356774 5e-4 -0.004823088 0.01356774 -5e-4 -0.004464924 0.01388525 5e-4 -0.004354774 0.01393485 5e-4 -0.004464924 0.01388525 -5e-4 -0.004568159 0.01382285 5e-4 -0.004568159 0.01382285 -5e-4 -0.004663169 0.01374846 -5e-4 -0.004000246 0.01399999 5e-4 -0.004120767 0.01399266 -5e-4 -0.004120767 0.01399266 5e-4 -0.00423932 0.01397085 -5e-4 -0.004354774 0.01393485 -5e-4 -0.00423932 0.01397085 5e-4 -0.003760695 0.01397085 -5e-4 -0.003760695 0.01397085 5e-4 -0.003645658 0.01393508 5e-4 -0.004000246 0.01399999 -5e-4 -0.003879606 0.01399266 5e-4 -0.003879606 0.01399266 -5e-4 -0.003431975 0.01382297 5e-4 -0.003336966 0.01374858 5e-4 -0.003431975 0.01382297 -5e-4 -0.003535509 0.01388555 5e-4 -0.003535509 0.01388555 -5e-4 -0.003645658 0.01393508 -5e-4 -0.003114521 0.01346474 5e-4 -0.003177106 0.01356816 -5e-4 -0.003177106 0.01356816 5e-4 -0.003251671 0.01366329 -5e-4 -0.003336966 0.01374858 -5e-4 -0.003251671 0.01366329 5e-4 -0.003029108 0.01323956 -5e-4 -0.003029108 0.01323956 5e-4 -0.003007292 0.01312065 5e-4 -0.003114521 0.01346474 -5e-4 -0.003065049 0.01335477 5e-4 -0.003065049 0.01335477 -5e-4 -0.003007292 0.01287925 5e-4 -0.003028988 0.01276099 5e-4 -0.003007292 0.01287925 -5e-4 -0.002999961 0.01299995 5e-4 -0.002999961 0.01299995 -5e-4 -0.003007292 0.01312065 -5e-4 -0.003176867 0.01243215 5e-4 -0.003114461 0.01253539 -5e-4 -0.003114461 0.01253539 5e-4 -0.00306493 0.01264548 -5e-4 -0.003028988 0.01276099 -5e-4 -0.00306493 0.01264548 5e-4 -0.003336787 0.01225149 -5e-4 -0.003336787 0.01225149 5e-4 -0.003431797 0.01217705 5e-4 -0.003176867 0.01243215 -5e-4 -0.003251314 0.01233708 5e-4 -0.003251314 0.01233708 -5e-4 -0.003645181 0.01206505 5e-4 -0.003760635 0.01202905 5e-4 -0.003645181 0.01206505 -5e-4 -0.003534972 0.0121147 5e-4 -0.003534972 0.0121147 -5e-4 -0.003431797 0.01217705 -5e-4 -0.003879189 0.01200729 -5e-4 -0.003760635 0.01202905 -5e-4 -0.003879189 0.01200729 5e-4 -0.004120349 0.01200729 5e-4 -0.004120349 0.01200729 -5e-4 -0.00399971 0.01199996 -5e-4 -0.00399971 0.01199996 5e-4 -0.004239201 0.01202905 5e-4 -0.004239201 0.01202905 -5e-4 -0.004354298 0.01206487 -5e-4 -0.004354298 0.01206487 5e-4 -0.004464447 0.01211434 5e-4 -0.004464447 0.01211434 -5e-4 -0.004567921 0.01217699 5e-4 -0.004567921 0.01217699 -5e-4 -0.00466299 0.01225137 -5e-4 -0.00466299 0.01225137 5e-4 -0.004748284 0.01233667 5e-4 -0.004748284 0.01233667 -5e-4 -0.00482285 0.0124318 5e-4 -0.00482285 0.0124318 -5e-4 -0.004885375 0.01253515 -5e-4 -0.004885375 0.01253515 5e-4 -0.004934906 0.01264518 5e-4 -0.004934906 0.01264518 -5e-4 -0.004970848 0.0127604 5e-4 -0.004970848 0.0127604 -5e-4 -0.004992663 0.01287925 -5e-4 -0.004992663 0.01287925 5e-4 -0.004992663 0.01662069 5e-4 -0.004999995 0.01649999 -5e-4 -0.004999995 0.01649999 5e-4 -0.004885435 0.01696455 5e-4 -0.004935026 0.01685446 -5e-4 -0.004935026 0.01685446 5e-4 -0.004970967 0.01673895 5e-4 -0.004970967 0.01673895 -5e-4 -0.004992663 0.01662069 -5e-4 -0.004748642 0.01716285 -5e-4 -0.004748642 0.01716285 5e-4 -0.004663169 0.01724845 5e-4 -0.004885435 0.01696455 -5e-4 -0.004823088 0.01706779 5e-4 -0.004823088 0.01706779 -5e-4 -0.004464924 0.0173853 5e-4 -0.004354774 0.01743489 5e-4 -0.004464924 0.0173853 -5e-4 -0.004568159 0.01732289 5e-4 -0.004568159 0.01732289 -5e-4 -0.004663169 0.01724845 -5e-4 -0.004000246 0.01749998 5e-4 -0.004120767 0.01749265 -5e-4 -0.004120767 0.01749265 5e-4 -0.00423932 0.01747089 -5e-4 -0.004354774 0.01743489 -5e-4 -0.00423932 0.01747089 5e-4 -0.003760695 0.01747089 -5e-4 -0.003760695 0.01747089 5e-4 -0.003645658 0.01743507 5e-4 -0.004000246 0.01749998 -5e-4 -0.003879606 0.01749265 5e-4 -0.003879606 0.01749265 -5e-4 -0.003431975 0.01732295 5e-4 -0.003336966 0.01724857 5e-4 -0.003431975 0.01732295 -5e-4 -0.003535509 0.0173856 5e-4 -0.003535509 0.0173856 -5e-4 -0.003645658 0.01743507 -5e-4 -0.003114521 0.01696479 5e-4 -0.003177106 0.01706814 -5e-4 -0.003177106 0.01706814 5e-4 -0.003251671 0.01716327 -5e-4 -0.003336966 0.01724857 -5e-4 -0.003251671 0.01716327 5e-4 -0.003029108 0.01673954 -5e-4 -0.003029108 0.01673954 5e-4 -0.003007292 0.01662069 5e-4 -0.003114521 0.01696479 -5e-4 -0.003065049 0.01685476 5e-4 -0.003065049 0.01685476 -5e-4 -0.003007292 0.01637929 5e-4 -0.003028988 0.01626098 5e-4 -0.003007292 0.01637929 -5e-4 -0.002999961 0.01649999 5e-4 -0.002999961 0.01649999 -5e-4 -0.003007292 0.01662069 -5e-4 -0.003176867 0.0159322 5e-4 -0.003114461 0.01603537 -5e-4 -0.003114461 0.01603537 5e-4 -0.00306493 0.01614546 -5e-4 -0.003028988 0.01626098 -5e-4 -0.00306493 0.01614546 5e-4 -0.003336787 0.01575148 -5e-4 -0.003336787 0.01575148 5e-4 -0.003431797 0.01567709 5e-4 -0.003176867 0.0159322 -5e-4 -0.003251314 0.01583707 5e-4 -0.003251314 0.01583707 -5e-4 -0.003645181 0.01556509 5e-4 -0.003760635 0.01552909 5e-4 -0.003645181 0.01556509 -5e-4 -0.003534972 0.01561468 5e-4 -0.003534972 0.01561468 -5e-4 -0.003431797 0.01567709 -5e-4 -0.003879189 0.01550728 -5e-4 -0.003760635 0.01552909 -5e-4 -0.003879189 0.01550728 5e-4 -0.004120349 0.01550728 5e-4 -0.004120349 0.01550728 -5e-4 -0.00399971 0.01549994 -5e-4 -0.00399971 0.01549994 5e-4 -0.004239201 0.01552909 5e-4 -0.004239201 0.01552909 -5e-4 -0.004354298 0.01556485 -5e-4 -0.004354298 0.01556485 5e-4 -0.004464447 0.01561439 5e-4 -0.004464447 0.01561439 -5e-4 -0.004567921 0.01567697 5e-4 -0.004567921 0.01567697 -5e-4 -0.00466299 0.01575136 -5e-4 -0.00466299 0.01575136 5e-4 -0.004748284 0.01583665 5e-4 -0.004748284 0.01583665 -5e-4 -0.00482285 0.01593178 5e-4 -0.00482285 0.01593178 -5e-4 -0.004885375 0.01603519 -5e-4 -0.004885375 0.01603519 5e-4 -0.004934906 0.01614516 5e-4 -0.004934906 0.01614516 -5e-4 -0.004970848 0.01626038 5e-4 -0.004970848 0.01626038 -5e-4 -0.004992663 0.01637929 -5e-4 -0.004992663 0.01637929 5e-4 -0.003999948 0.008499979 5e-4 -0.005707085 0.008207082 5e-4 -0.004120171 0.008507251 5e-4 0 0.002085745 5e-4 -6.31239e-6 0.002197861 5e-4 0.0115 0.002499997 5e-4 -0.005030035 0.01821428 5e-4 -0.004464924 0.0173853 5e-4 -0.005172669 0.01812005 5e-4 0 7e-4 5e-4 0.01173985 0.00225979 5e-4 0.01218438 0.001762449 5e-4 0.01196795 0.002013921 5e-4 0.012389 0.001505315 5e-4 0.01258188 0.001242518 5e-4 0.01276296 9.74095e-4 5e-4 0.01293236 7e-4 5e-4 -2.51435e-5 0.002308547 5e-4 -5.61788e-5 0.002416193 5e-4 -9.90717e-5 0.002519726 5e-4 -1.53405e-4 0.002617955 5e-4 -2.18067e-4 0.00270909 5e-4 2.21952e-4 0.01132625 5e-4 -2.92893e-4 0.002792835 5e-4 6.52065e-5 0.01147949 5e-4 -0.003114521 0.009964764 5e-4 2.90924e-7 0.01156806 5e-4 -0.003065049 0.009854733 5e-4 1.39249e-4 0.01139867 5e-4 -0.003029108 0.009739577 5e-4 -0.003114461 0.01253539 5e-4 -0.00306493 0.01264548 5e-4 -9.8578e-5 0.01176398 5e-4 -0.003431797 0.01217705 5e-4 -0.003336787 0.01225149 5e-4 -0.003336966 0.0102486 5e-4 -0.003028988 0.01276099 5e-4 -0.003007292 0.01287925 5e-4 -0.002999961 0.01299995 5e-4 -0.004354774 0.01743489 5e-4 -0.004722118 0.01836508 5e-4 -0.00423932 0.01747089 5e-4 -0.004970967 0.01673895 5e-4 -0.00593388 0.01700979 5e-4 -0.004935026 0.01685446 5e-4 -0.00455904 0.01842015 5e-4 -0.004392981 0.01846098 5e-4 -0.004878759 0.01829659 5e-4 -0.004568159 0.01732289 5e-4 -0.004120767 0.01749265 5e-4 -0.004000246 0.01749998 5e-4 -0.004222869 0.01848745 5e-4 -0.004663169 0.01724845 5e-4 -0.005307674 0.01801317 5e-4 -0.003880143 0.01849639 5e-4 -0.00405234 0.01849925 5e-4 -0.004748642 0.01716285 5e-4 -0.005432128 0.01789599 5e-4 -0.003879606 0.01749265 5e-4 -0.005546927 0.01776766 5e-4 -0.003710091 0.01847887 5e-4 -0.003540933 0.01844656 5e-4 -0.005649507 0.01763087 5e-4 -0.004823088 0.01706779 5e-4 -0.003760695 0.01747089 5e-4 -0.003376424 0.01840025 5e-4 -0.003645658 0.01743507 5e-4 -0.004885435 0.01696455 5e-4 -0.005740702 0.01748478 5e-4 -0.003061056 0.0182659 5e-4 -0.003215253 0.01833957 5e-4 -0.005818367 0.01733255 5e-4 -0.003535509 0.0173856 5e-4 -0.00291264 0.01817846 5e-4 -0.003431975 0.01732295 5e-4 -0.005883276 0.01717305 5e-4 -0.002641916 0.01796817 5e-4 -0.002773225 0.01807957 5e-4 -0.003336966 0.01724857 5e-4 -0.002521514 0.01784688 5e-4 -0.003251671 0.01716327 5e-4 -0.004992663 0.01662069 5e-4 -0.005970597 0.01684159 5e-4 -0.004999995 0.01649999 5e-4 -0.005999982 0.01649999 5e-4 -0.005992531 0.01667195 5e-4 -0.004934906 0.01614516 5e-4 -0.004885375 0.01603519 5e-4 -0.004992663 0.01637929 5e-4 -0.004970848 0.01626038 5e-4 -0.004748284 0.01583665 5e-4 -0.004748642 0.01366287 5e-4 -0.00482285 0.01593178 5e-4 -0.00466299 0.01575136 5e-4 -0.004663169 0.01374846 5e-4 -5.45318e-5 0.01166325 5e-4 -0.003177106 0.01006817 5e-4 -0.004464447 0.00861442 5e-4 -0.004354536 0.008564949 5e-4 -0.004567742 0.008676826 5e-4 -0.004239022 0.008528947 5e-4 -0.005999982 0.008914172 5e-4 -0.004999995 0.01299995 5e-4 -0.004992663 0.01287925 5e-4 -0.003114521 0.01346474 5e-4 -0.003114461 0.01603537 5e-4 -0.003176867 0.01243215 5e-4 -0.003645181 0.01206505 5e-4 -0.003535509 0.01038557 5e-4 -0.003645658 0.0104351 5e-4 -0.003534972 0.0121147 5e-4 -0.003431975 0.01032298 5e-4 -0.003251314 0.01233708 5e-4 -0.003760695 0.01047086 5e-4 -0.003760635 0.01202905 5e-4 -0.003251671 0.01016324 5e-4 -0.004000246 0.01049995 5e-4 -0.004120767 0.01049268 5e-4 -0.004120349 0.01200729 5e-4 -0.003879189 0.01200729 5e-4 -0.003879606 0.01049268 5e-4 -0.00399971 0.01199996 5e-4 -0.004567921 0.01217699 5e-4 -0.004464924 0.01038527 5e-4 -0.004568159 0.01032286 5e-4 -0.004354298 0.01206487 5e-4 -0.00423932 0.01047086 5e-4 -0.004354774 0.01043486 5e-4 -0.00466299 0.01225137 5e-4 -0.004748344 0.008836686 5e-4 -0.004822731 0.008931636 5e-4 -0.004663169 0.01024848 5e-4 -0.004885315 0.00903511 5e-4 -0.005900979 0.008480429 5e-4 -0.004970788 0.009260356 5e-4 -0.004934906 0.009145259 5e-4 -0.004999995 0.009499967 5e-4 -0.004992663 0.009620666 5e-4 -0.004934906 0.01264518 5e-4 -0.004885375 0.01253515 5e-4 -0.004885435 0.009964585 5e-4 -0.004935026 0.009854435 5e-4 -0.004970848 0.0127604 5e-4 -0.004970967 0.01323896 5e-4 -0.004992663 0.01312065 5e-4 -0.004567921 0.01567697 5e-4 -0.004568159 0.01382285 5e-4 -0.004885435 0.01346457 5e-4 -0.004935026 0.01335448 5e-4 -0.004823088 0.01356774 5e-4 -0.00423932 0.01397085 5e-4 -0.004239201 0.01552909 5e-4 -0.004120767 0.01399266 5e-4 -0.004464924 0.01388525 5e-4 -0.004464447 0.01561439 5e-4 -0.004354774 0.01393485 5e-4 -0.003760635 0.01552909 5e-4 -0.003760695 0.01397085 5e-4 -0.003879189 0.01550728 5e-4 -0.00399971 0.01549994 5e-4 -0.004000246 0.01399999 5e-4 -0.004120349 0.01550728 5e-4 -0.003431797 0.01567709 5e-4 -0.003431975 0.01382297 5e-4 -0.003534972 0.01561468 5e-4 -0.003535509 0.01388555 5e-4 -0.003645181 0.01556509 5e-4 -0.003336966 0.01374858 5e-4 -0.003336787 0.01575148 5e-4 -0.002313196 0.01757454 5e-4 -0.003177106 0.01706814 5e-4 -0.002411127 0.01771467 5e-4 -0.003251314 0.01583707 5e-4 -0.003177106 0.01356816 5e-4 -0.003251671 0.01366329 5e-4 -0.003176867 0.0159322 5e-4 -0.00306493 0.01614546 5e-4 -0.002154469 0.01727068 5e-4 -0.003007292 0.01637929 5e-4 -0.002999961 0.01649999 5e-4 -0.003028988 0.01626098 5e-4 -0.003065049 0.01335477 5e-4 -0.003007292 0.01312065 5e-4 -0.003029108 0.01323956 5e-4 -0.003645658 0.01393508 5e-4 -0.003879606 0.01399266 5e-4 -0.004354298 0.01556485 5e-4 -0.002227604 0.01742655 5e-4 -0.003114521 0.01696479 5e-4 -0.003029108 0.01673954 5e-4 -0.003065049 0.01685476 5e-4 -0.003007292 0.01662069 5e-4 -0.003028988 0.009260952 5e-4 -0.003007292 0.009379208 5e-4 -0.002999961 0.009499967 5e-4 -0.005781888 0.008290827 5e-4 -0.005846798 0.00838238 5e-4 -0.003114402 0.009035527 5e-4 -0.00306493 0.009145438 5e-4 -0.003176808 0.008932173 5e-4 -0.003336727 0.00875163 5e-4 -0.003251373 0.008836925 5e-4 -0.003535091 0.008614599 5e-4 -0.003431618 0.008677184 5e-4 -0.003760337 0.008529126 5e-4 -0.003645241 0.008565008 5e-4 -0.003879189 0.008507311 5e-4 -0.00466299 0.008751392 5e-4 -0.004464447 0.01211434 5e-4 -0.004748284 0.01233667 5e-4 -0.004748642 0.01016288 5e-4 -0.005943894 0.008583962 5e-4 -0.005974948 0.008691906 5e-4 -0.00482285 0.0124318 5e-4 -0.005993664 0.008802056 5e-4 -0.004823088 0.01006776 5e-4 -0.004992663 0.009379208 5e-4 -0.004970967 0.009739041 5e-4 -0.004239201 0.01202905 5e-4 -0.003007292 0.009620666 5e-4 -0.005707085 0.008207082 -5e-4 -0.004464864 0.008614599 -5e-4 -0.004568278 0.008677184 -5e-4 -5.61788e-5 0.002416193 -5e-4 -2.51435e-5 0.002308547 -5e-4 0.0115 0.002499997 -5e-4 -6.31239e-6 0.002197861 -5e-4 -9.90717e-5 0.002519726 -5e-4 -1.53405e-4 0.002617955 -5e-4 2.21952e-4 0.01132625 -5e-4 -2.18067e-4 0.00270909 -5e-4 -0.004120767 0.008507311 -5e-4 -0.004239618 0.008529126 -5e-4 -0.003999948 0.008499979 -5e-4 -0.00482285 0.01593178 -5e-4 -0.004885375 0.01603519 -5e-4 -0.005999982 0.01649999 -5e-4 -0.004992663 0.01287925 -5e-4 -0.004999995 0.01299995 -5e-4 -0.005999982 0.008914172 -5e-4 -0.003760695 0.01747089 -5e-4 -0.003645658 0.01743507 -5e-4 -0.003376424 0.01840025 -5e-4 -0.005970597 0.01684159 -5e-4 -0.004992663 0.01662069 -5e-4 -0.004970967 0.01673895 -5e-4 -0.004000246 0.01749998 -5e-4 -0.004222869 0.01848745 -5e-4 -0.004120767 0.01749265 -5e-4 -0.004722118 0.01836508 -5e-4 -0.004354774 0.01743489 -5e-4 -0.00423932 0.01747089 -5e-4 -0.005030035 0.01821428 -5e-4 -0.005172669 0.01812005 -5e-4 -0.004464924 0.0173853 -5e-4 -0.004392981 0.01846098 -5e-4 -0.00455904 0.01842015 -5e-4 -0.004878759 0.01829659 -5e-4 -0.004568159 0.01732289 -5e-4 -0.004663169 0.01724845 -5e-4 -0.005432128 0.01789599 -5e-4 -0.004748642 0.01716285 -5e-4 -0.005307674 0.01801317 -5e-4 -0.005546927 0.01776766 -5e-4 -0.003880143 0.01849639 -5e-4 -0.00405234 0.01849925 -5e-4 -0.005649507 0.01763087 -5e-4 -0.004823088 0.01706779 -5e-4 -0.003879606 0.01749265 -5e-4 -0.005740702 0.01748478 -5e-4 -0.004885435 0.01696455 -5e-4 -0.003710091 0.01847887 -5e-4 -0.003540933 0.01844656 -5e-4 -0.003061056 0.0182659 -5e-4 -0.003215253 0.01833957 -5e-4 -0.004935026 0.01685446 -5e-4 -0.005818367 0.01733255 -5e-4 -0.00291264 0.01817846 -5e-4 -0.003535509 0.0173856 -5e-4 -0.003431975 0.01732295 -5e-4 -0.005883276 0.01717305 -5e-4 -0.002641916 0.01796817 -5e-4 -0.002773225 0.01807957 -5e-4 -0.00593388 0.01700979 -5e-4 -0.002521514 0.01784688 -5e-4 -0.003336966 0.01724857 -5e-4 -0.003251671 0.01716327 -5e-4 -0.004999995 0.01649999 -5e-4 -0.005992531 0.01667195 -5e-4 -0.004934906 0.01614516 -5e-4 -0.004992663 0.01637929 -5e-4 -0.004970848 0.01626038 -5e-4 -0.004748642 0.01366287 -5e-4 -0.004748284 0.01583665 -5e-4 -0.003645181 0.01206505 -5e-4 -0.003760635 0.01202905 -5e-4 -0.003645181 0.01043486 -5e-4 -0.004663169 0.01374846 -5e-4 -0.00466299 0.01575136 -5e-4 -0.004934906 0.009854733 -5e-4 -0.004970848 0.009739577 -5e-4 -0.004885554 0.009035527 -5e-4 -0.005993664 0.008802056 -5e-4 -0.003251314 0.01233708 -5e-4 -0.003251314 0.01016288 -5e-4 -9.8578e-5 0.01176398 -5e-4 -0.004354655 0.008565008 -5e-4 -2.92893e-4 0.002792835 -5e-4 -5.45318e-5 0.01166325 -5e-4 -0.003176867 0.01006776 -5e-4 -0.004823148 0.008932173 -5e-4 -0.004748582 0.008836925 -5e-4 -0.005781888 0.008290827 -5e-4 -0.005846798 0.00838238 -5e-4 2.90924e-7 0.01156806 -5e-4 -0.003114461 0.009964585 -5e-4 6.52065e-5 0.01147949 -5e-4 0 0.002085745 -5e-4 0 7e-4 -5e-4 0.01196795 0.002013921 -5e-4 0.01173985 0.00225979 -5e-4 0.01218438 0.001762449 -5e-4 0.012389 0.001505315 -5e-4 0.01276296 9.74095e-4 -5e-4 0.01258188 0.001242518 -5e-4 0.01293236 7e-4 -5e-4 -0.002999961 0.009499967 -5e-4 -0.003007292 0.009379208 -5e-4 -0.003028988 0.009739041 -5e-4 1.39249e-4 0.01139867 -5e-4 -0.00306493 0.009854435 -5e-4 -0.003029167 0.009260356 -5e-4 -0.00306499 0.009145259 -5e-4 -0.003114581 0.00903511 -5e-4 -0.003251612 0.008836686 -5e-4 -0.003177225 0.008931636 -5e-4 -0.003432154 0.008676826 -5e-4 -0.003336966 0.008751392 -5e-4 -0.00364542 0.008564949 -5e-4 -0.003535509 0.00861442 -5e-4 -0.003879725 0.008507251 -5e-4 -0.003760933 0.008528947 -5e-4 -0.004663228 0.00875163 -5e-4 -0.005900979 0.008480429 -5e-4 -0.005974948 0.008691906 -5e-4 -0.005943894 0.008583962 -5e-4 -0.004992663 0.009620666 -5e-4 -0.004999995 0.009499967 -5e-4 -0.004970967 0.009260952 -5e-4 -0.004935026 0.009145438 -5e-4 -0.004992663 0.009379208 -5e-4 -0.003431797 0.01032286 -5e-4 -0.003431797 0.01217705 -5e-4 -0.003534972 0.0121147 -5e-4 -0.004748284 0.01233667 -5e-4 -0.004748284 0.01016324 -5e-4 -0.00466299 0.0102486 -5e-4 -0.004885375 0.009964764 -5e-4 -0.004464447 0.01038557 -5e-4 -0.004354298 0.0104351 -5e-4 -0.004464447 0.01211434 -5e-4 -0.004567921 0.01217699 -5e-4 -0.004567921 0.01032298 -5e-4 -0.00399971 0.01199996 -5e-4 -0.004120349 0.01200729 -5e-4 -0.00399971 0.01049995 -5e-4 -0.004239201 0.01202905 -5e-4 -0.004354298 0.01206487 -5e-4 -0.004239201 0.01047086 -5e-4 -0.003534972 0.01038527 -5e-4 -0.003879189 0.01200729 -5e-4 -0.003760635 0.01047086 -5e-4 -0.003879189 0.01049268 -5e-4 -0.003336787 0.01024848 -5e-4 -0.003336787 0.01225149 -5e-4 -0.003114461 0.01253539 -5e-4 -0.003176867 0.01243215 -5e-4 -0.003028988 0.01276099 -5e-4 -0.00306493 0.01264548 -5e-4 -0.003007292 0.009620666 -5e-4 -0.003114461 0.01603537 -5e-4 -0.003114521 0.01346474 -5e-4 -0.003007292 0.01287925 -5e-4 -0.002999961 0.01299995 -5e-4 -0.004120349 0.01049268 -5e-4 -0.00466299 0.01225137 -5e-4 -0.00482285 0.0124318 -5e-4 -0.00482285 0.01006817 -5e-4 -0.004885375 0.01253515 -5e-4 -0.004934906 0.01264518 -5e-4 -0.004970848 0.0127604 -5e-4 -0.004970967 0.01323896 -5e-4 -0.004992663 0.01312065 -5e-4 -0.004568159 0.01382285 -5e-4 -0.004567921 0.01567697 -5e-4 -0.004885435 0.01346457 -5e-4 -0.004935026 0.01335448 -5e-4 -0.004823088 0.01356774 -5e-4 -0.00423932 0.01397085 -5e-4 -0.004120767 0.01399266 -5e-4 -0.004239201 0.01552909 -5e-4 -0.004464924 0.01388525 -5e-4 -0.004354774 0.01393485 -5e-4 -0.004464447 0.01561439 -5e-4 -0.003760635 0.01552909 -5e-4 -0.003879189 0.01550728 -5e-4 -0.003760695 0.01397085 -5e-4 -0.00399971 0.01549994 -5e-4 -0.004120349 0.01550728 -5e-4 -0.004000246 0.01399999 -5e-4 -0.003431797 0.01567709 -5e-4 -0.003534972 0.01561468 -5e-4 -0.003431975 0.01382297 -5e-4 -0.003535509 0.01388555 -5e-4 -0.003645181 0.01556509 -5e-4 -0.003336966 0.01374858 -5e-4 -0.003336787 0.01575148 -5e-4 -0.003251314 0.01583707 -5e-4 -0.003251671 0.01366329 -5e-4 -0.003177106 0.01356816 -5e-4 -0.003176867 0.0159322 -5e-4 -0.003007292 0.01637929 -5e-4 -0.002154469 0.01727068 -5e-4 -0.002999961 0.01649999 -5e-4 -0.003028988 0.01626098 -5e-4 -0.00306493 0.01614546 -5e-4 -0.003065049 0.01335477 -5e-4 -0.003007292 0.01312065 -5e-4 -0.003029108 0.01323956 -5e-4 -0.003177106 0.01706814 -5e-4 -0.002313196 0.01757454 -5e-4 -0.002411127 0.01771467 -5e-4 -0.003645658 0.01393508 -5e-4 -0.003879606 0.01399266 -5e-4 -0.004354298 0.01556485 -5e-4 -0.002227604 0.01742655 -5e-4 -0.003114521 0.01696479 -5e-4 -0.003029108 0.01673954 -5e-4 -0.003065049 0.01685476 -5e-4 -0.003007292 0.01662069 -5e-4 -0.004992663 0.009620666 5e-4 -0.004999995 0.009499967 -5e-4 -0.004999995 0.009499967 5e-4 -0.004885435 0.009964585 5e-4 -0.004934906 0.009854733 -5e-4 -0.004935026 0.009854435 5e-4 -0.004970967 0.009739041 5e-4 -0.004970848 0.009739577 -5e-4 -0.004992663 0.009620666 -5e-4 -0.004748284 0.01016324 -5e-4 -0.004748642 0.01016288 5e-4 -0.004663169 0.01024848 5e-4 -0.004885375 0.009964764 -5e-4 -0.004823088 0.01006776 5e-4 -0.00482285 0.01006817 -5e-4 -0.004464924 0.01038527 5e-4 -0.004354774 0.01043486 5e-4 -0.004464447 0.01038557 -5e-4 -0.004568159 0.01032286 5e-4 -0.004567921 0.01032298 -5e-4 -0.00466299 0.0102486 -5e-4 -0.004000246 0.01049995 5e-4 -0.004120349 0.01049268 -5e-4 -0.004120767 0.01049268 5e-4 -0.004239201 0.01047086 -5e-4 -0.004354298 0.0104351 -5e-4 -0.00423932 0.01047086 5e-4 -0.003760635 0.01047086 -5e-4 -0.003760695 0.01047086 5e-4 -0.003645658 0.0104351 5e-4 -0.00399971 0.01049995 -5e-4 -0.003879606 0.01049268 5e-4 -0.003879189 0.01049268 -5e-4 -0.003431975 0.01032298 5e-4 -0.003336966 0.0102486 5e-4 -0.003431797 0.01032286 -5e-4 -0.003535509 0.01038557 5e-4 -0.003534972 0.01038527 -5e-4 -0.003645181 0.01043486 -5e-4 -0.003114521 0.009964764 5e-4 -0.003176867 0.01006776 -5e-4 -0.003177106 0.01006817 5e-4 -0.003251314 0.01016288 -5e-4 -0.003336787 0.01024848 -5e-4 -0.003251671 0.01016324 5e-4 -0.003028988 0.009739041 -5e-4 -0.003029108 0.009739577 5e-4 -0.003007292 0.009620666 5e-4 -0.003114461 0.009964585 -5e-4 -0.003065049 0.009854733 5e-4 -0.00306493 0.009854435 -5e-4 -0.003007292 0.009379208 5e-4 -0.003028988 0.009260952 5e-4 -0.003007292 0.009379208 -5e-4 -0.002999961 0.009499967 5e-4 -0.002999961 0.009499967 -5e-4 -0.003007292 0.009620666 -5e-4 -0.003176808 0.008932173 5e-4 -0.003114581 0.00903511 -5e-4 -0.003114402 0.009035527 5e-4 -0.00306499 0.009145259 -5e-4 -0.003029167 0.009260356 -5e-4 -0.00306493 0.009145438 5e-4 -0.003336966 0.008751392 -5e-4 -0.003336727 0.00875163 5e-4 -0.003431618 0.008677184 5e-4 -0.003177225 0.008931636 -5e-4 -0.003251373 0.008836925 5e-4 -0.003251612 0.008836686 -5e-4 -0.003645241 0.008565008 5e-4 -0.003760337 0.008529126 5e-4 -0.00364542 0.008564949 -5e-4 -0.003535091 0.008614599 5e-4 -0.003535509 0.00861442 -5e-4 -0.003432154 0.008676826 -5e-4 -0.003879725 0.008507251 -5e-4 -0.003760933 0.008528947 -5e-4 -0.003879189 0.008507311 5e-4 -0.004120171 0.008507251 5e-4 -0.004120767 0.008507311 -5e-4 -0.003999948 0.008499979 -5e-4 -0.003999948 0.008499979 5e-4 -0.004239022 0.008528947 5e-4 -0.004239618 0.008529126 -5e-4 -0.004354655 0.008565008 -5e-4 -0.004354536 0.008564949 5e-4 -0.004464447 0.00861442 5e-4 -0.004464864 0.008614599 -5e-4 -0.004567742 0.008676826 5e-4 -0.004568278 0.008677184 -5e-4 -0.004663228 0.00875163 -5e-4 -0.00466299 0.008751392 5e-4 -0.004748344 0.008836686 5e-4 -0.004748582 0.008836925 -5e-4 -0.004822731 0.008931636 5e-4 -0.004823148 0.008932173 -5e-4 -0.004885554 0.009035527 -5e-4 -0.004885315 0.00903511 5e-4 -0.004934906 0.009145259 5e-4 -0.004935026 0.009145438 -5e-4 -0.004970788 0.009260356 5e-4 -0.004970967 0.009260952 -5e-4 -0.004992663 0.009379208 -5e-4 -0.004992663 0.009379208 5e-4 + + + + + + + + + + -0.9761871 -0.2169305 0 0.1520573 -0.9883717 0 0.1520573 -0.9883717 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 1.16884e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.84901 -0.5283767 0 -0.9257904 -0.3780374 0 -0.9543975 -0.2985392 0 -0.6257329 -0.7800375 0 -0.4855885 -0.8741875 0 -0.7480252 -0.6636703 0 -0.3316226 -0.9434123 0 -0.1681886 -0.9857548 0 -0.08438402 -0.9964334 0 0.9751317 0.2216264 0 0.9666868 0.2559622 0 0.9823791 0.1868989 0 0.9883732 0.152048 0 0.9909014 0.1345902 0 0.9570001 0.2900879 0 0.9461448 0.3237438 0 0.9403447 0.3402234 0 0 -1 0 0 -1 0 1 5.1521e-4 0 1 0 1.11345e-4 0.9998442 -0.01765561 0 1 0 -1.11345e-4 0.9999999 5.09219e-4 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 0.9889115 0.1485061 0 0.9876874 0.1564405 0 0.9969195 0.07843267 0 0.8090303 0.587767 0 0.8910139 0.4539761 0 0.8306108 0.5568535 0 0.9510608 0.309004 0 0.9560143 0.2933201 0 0.9023097 0.4310883 -3.05192e-5 0.5316439 0.846968 3.05194e-5 0.4539761 0.8910139 3.05193e-5 0.5878015 0.8090053 0 0.7443419 0.6677988 0 0.6437109 0.7652688 3.05195e-5 0.7071068 0.7071068 0 0.2837984 0.958884 3.05192e-5 0.1564108 0.9876922 3.05189e-5 0.309004 0.9510608 0 0.4113112 0.911495 0 0.07843267 0.9969195 0 0.152658 0.9882791 0 0.06790441 0.9976919 0 0.997057 0.07666379 0.6163083 0.787505 0 0.8378868 0.5458441 0 0.8927485 0.4505554 0 0.9161881 0.4007484 0 0.6990348 0.7150877 0 0.6586904 0.7524141 0 0.7731217 0.6342577 0 0.9368384 0.3497627 0 0.9368384 0.3497627 0 -0.9963108 0.08581835 0 -0.9990646 0.04324513 0 -0.9990633 0.04327559 0 -0.9416155 0.3366902 0 -0.9670007 0.2547742 0 -0.9852818 0.170938 0 -0.8702849 0.492549 0 -0.8249403 0.5652199 0 -0.9092627 0.4162228 0 -0.7160978 0.698 0 -0.6537923 0.7566741 0 -0.7733696 0.6339555 0 -0.4396655 0.8981617 0 -0.514949 0.8572209 0 -0.5864574 0.8099802 0 -0.2795827 0.9601216 0 -0.1964507 0.9805138 0 -0.3607107 0.9326778 0 -0.02609395 0.9996595 0 0.05963438 0.9982203 0 -0.1115469 0.9937592 0 0.3119671 0.9500929 0 0.2294085 0.9733303 0 0.1450863 0.9894191 0 0.4697279 0.8828114 0 0.5435512 0.8393761 0 0.3921763 0.9198901 0 0.6133827 0.7897859 0 0.6788997 0.734231 0 0.7393571 0.6733136 0 0.7943544 0.6074547 0 0.8434202 0.5372546 0 0.8862756 0.4631583 0 0.9052313 0.4249194 0 -0.7819901 -0.623291 0 -0.7457401 -0.6662372 0 -0.9439169 -0.3301832 0 -0.9010111 -0.4337964 0 -0.8468511 -0.5318303 0 -0.7819633 -0.6233245 0 -0.9937043 -0.1120359 0 -0.9749509 -0.2224204 0 -0.9937075 -0.1120057 0 -0.9984222 -0.05615454 0 -0.9984204 -0.05618494 0 -0.707107 -0.7071066 0 -0.707107 -0.7071066 0 -0.9748736 -0.2227593 0 -0.9936906 -0.1121564 0 -0.9009222 -0.4339808 0 -0.8466618 -0.5321316 0 -0.9438531 -0.3303654 0 -0.7818831 -0.6234251 0 -0.7457113 -0.6662693 0 -1 0 0 -1 -5.41561e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -5.41562e-7 0 3.05189e-5 0.309004 -0.9510608 -3.05189e-5 0.2853817 -0.958414 -3.05192e-5 0.4110625 -0.9116073 0 0.07843267 -0.9969195 0 0.1558607 -0.987779 0 0.1564108 -0.9876922 0 0.6420677 -0.7666479 0 0.7437205 -0.6684908 3.05195e-5 0.7071068 -0.7071068 3.05193e-5 0.5878015 -0.8090053 3.05194e-5 0.4539761 -0.8910139 -3.05191e-5 0.5295984 -0.8482486 0 0.9510608 -0.309004 0 0.9026917 -0.4302877 0 0.9560058 -0.293348 0 0.8910139 -0.4539761 0 0.8090303 -0.587767 0 0.8311618 -0.5560306 0 0.9888936 -0.1486254 0 0.9876874 -0.1564405 0 0.997043 -0.07684582 0 0.9969195 -0.07843267 0 0.06793481 -0.9976898 0.8655719 0.5007848 -7.4213e-5 0.8723533 0.4888761 2.26396e-6 0.8594916 0.5111501 0 0.8748543 0.4843864 -1.44521e-5 0.8752146 0.4837348 1.61431e-6 0.8654432 0.5010073 4.33636e-7 0.8712601 0.4908216 -1.04787e-5 0.8652339 0.5013685 -4.96214e-6 0.8653305 0.5012019 -2.02175e-6 0.8634088 0.5045052 0 0.8633202 0.5046567 -5.01358e-6 0.8177208 0.5756151 0 0.7944731 0.6072995 0 0.8572209 0.514949 0 0.8399876 0.5426058 0 0.7456675 0.6663184 0 0.7204078 0.6935508 0 0.7704181 0.637539 0 0.7204225 0.6935355 0 0.707534 0.7066794 0 0.8571642 0.5150432 0 0.8679411 0.4966673 -1.96608e-6 0.8672958 0.4977932 1.70372e-5 0.8667323 0.4987738 -7.43036e-5 0.8715066 0.4903839 4.78822e-7 0.8657456 0.5004844 1.708e-5 0.8722475 0.4890647 -1.04648e-5 0.8754811 0.4832525 1.56407e-6 0.8721632 0.4892151 -1.46072e-5 0.8752697 0.4836352 2.24776e-6 0.8720739 0.4893745 1.87202e-6 0.8602439 0.5098827 1.9035e-6 0.9926961 -0.1206421 0 1 0 0 0.8854585 -0.4647185 0 0.9350855 -0.3544224 0 0.9350754 -0.354449 0 0.970991 -0.239116 0 0.7488707 -0.6627162 0 0.6633309 -0.7483264 0 0.8231229 -0.5678635 0 0.4647424 -0.885446 0 0.3547297 -0.9349689 0 0.567989 -0.8230362 0 3.05194e-5 -1 0 0.1208563 -0.99267 0 0.2396693 -0.9708546 0 0.3547195 -0.9349728 0 -0.239116 -0.970991 0 -0.3541151 -0.9352019 0 3.05185e-5 -1 0 -0.120582 -0.9927035 0 -0.5680589 -0.822988 0 -0.6629913 -0.7486271 0 -0.4645976 -0.8855219 0 -0.4646216 -0.8855094 0 -0.8853633 -0.4648997 0 -0.822762 -0.5683861 0 -0.748412 -0.6632341 0 -0.9708777 -0.2395759 0 -0.9926815 -0.1207624 0 -0.9708706 -0.2396047 0 -0.934993 -0.3546662 0 -0.9926961 0.1206421 0 -0.970991 0.239116 0 -0.8231229 0.5678635 0 -0.8854585 0.4647185 0 -0.9350754 0.354449 0 -0.9350855 0.3544224 0 -0.6633309 0.7483264 0 -0.567989 0.8230362 0 -0.7488574 0.6627313 0 -0.7488707 0.6627162 0 -0.3547297 0.9349689 0 -0.2396693 0.9708546 0 -0.4647424 0.885446 0 -0.1208563 0.99267 0 0.120582 0.9927035 0 -3.05185e-5 1 0 0.239116 0.970991 0 0.3541151 0.9352019 0 0.4645976 0.8855219 0 0.5680589 0.822988 0 0.6629913 0.7486271 0 0.748412 0.6632341 0 0.822762 0.5683861 0 0.8853633 0.4648997 0 0.934993 0.3546662 0 0.9708706 0.2396047 0 0.9926815 0.1207624 0 0.4647789 -0.8854268 0 -0.7484272 -0.6632171 0 -3.05194e-5 1 0 0.6630064 0.7486138 0 0.9708777 0.2395759 0 5.96579e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.67744e-7 0 1 0 0 1 0 0 1 -4.73643e-7 0 1 4.71371e-7 0 1 -6.61359e-7 0 1 4.69121e-7 0 1 8.36161e-7 0 1 -1.65382e-7 0 1 0 0 1 0 0 1 -9.41783e-7 0 1 3.31977e-7 0 1 4.71364e-7 0 1 2.85367e-7 0 1 0 0 1 0 0 1 -1.33073e-6 0 1 0 0 1 0 0 1 0 0 1 -2.54763e-6 0 1 0 0 1 -1.38494e-7 0 1 0 0 1 -6.04846e-7 0 1 -6.33985e-7 0 1 0 0 1 -3.20942e-7 0 1 4.12294e-7 0 1 -1.49398e-7 0 1 2.03342e-7 0 1 0 0 1 -7.5338e-7 0 1 0 0 1 1.16232e-6 0 1 4.85611e-7 0 1 6.45171e-7 0 1 -5.72002e-7 0 1 1.29102e-7 0 1 2.10126e-7 0 1 2.98435e-7 0 1 0 0 1 -2.63015e-7 0 1 -3.98877e-7 0 1 0 0 1 -6.96969e-7 0 1 -2.49682e-7 0 1 -1.38494e-7 0 1 0 0 1 -1.21133e-7 0 1 1.33073e-6 0 1 -2.38227e-7 0 1 0 0 1 -2.97181e-7 0 1 0 0 1 6.35273e-7 0 1 -2.22759e-7 0 1 4.58945e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.91421e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 4.20656e-7 0 1 -4.4755e-7 0 1 1.65372e-7 0 1 0 0 1 0 0 1 1.65176e-7 0 1 -2.37152e-7 0 1 0 0 1 1.84414e-7 0 1 0 0 1 0 0 1 2.74561e-7 0 1 4.20636e-7 0 1 0 0 1 0 0 1 3.31841e-7 0 1 -3.80845e-7 0 1 -1.22725e-7 0 1 0 0 1 -4.38375e-7 0 1 5.73681e-7 0 1 -2.18309e-7 0 1 0 0 1 -2.20393e-7 0 1 0 0 1 0 0 1 0 0 1 2.42266e-7 0 1 -1.33073e-6 0 1 3.57341e-7 0 1 3.36805e-7 0 1 1.38494e-7 0 1 2.0715e-7 0 1 0 0 1 6.04128e-7 0 1 9.56463e-7 0 1 -6.35274e-7 0 1 -2.67707e-7 0 1 0 0 1 3.04599e-7 0 1 0 0 1 0 0 -1 0 0 -1 -3.0194e-6 0 -1 -9.41783e-7 0 -1 0 0 -1 0 0 -1 -4.73643e-7 0 -1 4.69121e-7 0 -1 4.71371e-7 0 -1 -1.65382e-7 0 -1 -5.86439e-7 0 -1 0 0 -1 9.38847e-7 0 -1 2.07485e-7 0 -1 0 0 -1 1.23405e-7 0 -1 2.34991e-7 0 -1 2.35681e-7 0 -1 0 0 -1 2.85367e-7 0 -1 6.04e-7 0 -1 -1.33073e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.60528e-7 0 -1 0 0 -1 6.2238e-7 0 -1 -5.30895e-7 0 -1 -3.69968e-7 0 -1 -2.2098e-7 0 -1 2.12091e-7 0 -1 -5.007e-7 0 -1 -4.19401e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -3.71217e-7 0 -1 3.44939e-7 0 -1 3.33323e-7 0 -1 6.33996e-7 0 -1 -3.16501e-7 0 -1 1.22342e-6 0 -1 -2.67268e-7 0 -1 0 0 -1 3.04593e-7 0 -1 0 0 -1 0 0 -1 -1.35049e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.84129e-7 0 -1 -1.29054e-6 0 -1 -9.27468e-7 0 -1 -1.41351e-6 0 -1 1.5372e-6 0 -1 -7.5338e-7 0 -1 0 0 -1 1.16232e-6 0 -1 4.85611e-7 0 -1 6.45171e-7 0 -1 -5.72002e-7 0 -1 1.29102e-7 0 -1 2.10126e-7 0 -1 2.98435e-7 0 -1 0 0 -1 -6.04846e-7 0 -1 -2.63015e-7 0 -1 -3.98877e-7 0 -1 -6.96969e-7 0 -1 -2.49682e-7 0 -1 -1.38494e-7 0 -1 0 0 -1 -1.21133e-7 0 -1 1.33073e-6 0 -1 -2.38227e-7 0 -1 0 0 -1 -2.97181e-7 0 -1 0 0 -1 6.35273e-7 0 -1 -2.22759e-7 0 -1 4.58945e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.91421e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 4.20656e-7 0 -1 -4.4755e-7 0 -1 1.65372e-7 0 -1 0 0 -1 0 0 -1 1.65176e-7 0 -1 -2.37152e-7 0 -1 0 0 -1 1.84414e-7 0 -1 0.9926998 -0.1206121 0 0.8854776 -0.464682 0 0.9349829 -0.3546929 0 0.9709751 -0.2391806 0 0.9926815 -0.1207624 0 0.9708706 -0.2396047 3.0519e-5 0.7484272 -0.6632171 3.05194e-5 0.7488574 -0.6627313 0 0.8853952 -0.4648393 0 0.8228004 -0.5683305 3.05193e-5 0.8230987 -0.5678985 0 0.4646216 -0.8855094 0 0.3547195 -0.9349728 -6.10375e-5 0.567989 -0.8230362 3.0519e-5 0.6629913 -0.7486271 6.10377e-5 0.5680239 -0.8230121 0 0.120582 -0.9927035 3.05194e-5 0.2391448 -0.9709839 3.05187e-5 0.2396335 -0.9708635 0 0.3541151 -0.9352019 0 -0.2396335 -0.9708635 0 -0.2391448 -0.9709839 -3.05187e-5 -3.05185e-5 -1 0 -0.1208563 -0.99267 0 -0.120582 -0.9927035 -3.05194e-5 -0.5680239 -0.8230121 -3.05192e-5 -0.567989 -0.8230362 -3.0519e-5 -0.6629913 -0.7486271 -6.10377e-5 -0.3547195 -0.9349728 6.10375e-5 -0.4647789 -0.8854268 0 -0.8853826 -0.4648633 0 -0.8228004 -0.5683305 -3.05193e-5 -0.8230987 -0.5678985 0 -0.7488574 -0.6627313 0 -0.7484272 -0.6632171 -3.05194e-5 -0.6633309 -0.7483264 0 -0.9709751 -0.2391806 0 -0.9708706 -0.2396047 -3.0519e-5 -0.8854776 -0.464682 0 -0.9350754 -0.354449 0 -0.9349829 -0.3546929 0 -0.9926998 0.1206121 0 -0.9926736 0.1208263 0 -0.9709751 0.2391806 0 -0.9926998 -0.1206121 0 -0.8231995 0.5677523 -3.05194e-5 -0.8855411 0.4645612 0 -0.8853508 0.4649236 0 -0.9349829 0.3546929 0 -0.9350513 0.3545125 0 -0.9708706 0.2396047 3.0519e-5 -0.6630064 0.7486138 0 -0.5683305 0.8228004 -3.05193e-5 -0.6632341 0.748412 0 -0.8227763 0.5683655 3.05195e-5 -0.7484272 0.6632171 0 -0.7486271 0.6629913 0 -0.3547195 0.9349728 0 -0.3545125 0.9350513 0 -0.2396047 0.9708706 -3.0519e-5 -0.4649236 0.8853508 0 -0.5677729 0.8231853 3.05189e-5 -0.4645612 0.8855411 0 -0.1203377 0.9927331 0 -0.1207962 0.9926773 0 -0.238965 0.9710283 3.05192e-5 0.1203377 0.9927331 0 6.10389e-5 1 0 0.1208263 0.9926736 0 -6.1037e-5 1 0 0.2396047 0.9708706 3.0519e-5 0.238965 0.9710283 -3.05192e-5 0.3547195 0.9349728 0 0.3544859 0.9350615 0 0.4645612 0.8855411 0 0.4649236 0.8853508 0 0.5683305 0.8228004 3.05193e-5 0.5677729 0.8231853 -3.05189e-5 0.6632171 0.7484272 0 0.7484272 0.6632171 0 0.7486271 0.6629913 0 0.8231995 0.5677523 3.05194e-5 0.8227763 0.5683655 -3.05195e-5 0.8855411 0.4645612 0 0.8853508 0.4649236 0 0.9349829 0.3546929 0 0.9350513 0.3545125 0 0.9709839 0.2391448 0 0.9708706 0.2396047 -3.0519e-5 0.9926998 0.1206121 0 0.99267 0.1208563 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + + -0.9970199 -0.0771484 5.82454e-9 -1.19545e-5 0 7.54979e-8 1 4.76399e-5 -0.0771484 0.9970199 -7.52729e-8 -1.20013e-5 0 0 0 1 + + + + + + + + + + -0.9970199 0.0771484 5.82454e-9 0.01298147 0 7.54979e-8 -1 0.004052476 -0.0771484 -0.9970199 -7.52729e-8 -0.001186203 0 0 0 1 + + + + + + + + + + + + + + \ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_ruddervator.dae b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_ruddervator.dae new file mode 100644 index 00000000..dacbe5e5 --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_ruddervator.dae @@ -0,0 +1,151 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-05T14:00:47 + 2023-07-05T14:00:47 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.498039 0.498039 0.498039 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + 0.000999987 -0.004499971 5e-4 0.000999987 -0.004499971 -5e-4 1.98119e-4 -8.91535e-4 -5e-4 1.98119e-4 -8.91535e-4 5e-4 0.0139994 -0.002500057 5e-4 0.000999987 -0.004499971 -5e-4 0.000999987 -0.004499971 5e-4 0.0139994 -0.002500057 -5e-4 -2.05869e-4 -5.07125e-4 -5e-4 0.01349997 -5e-4 -5e-4 -2.89975e-4 -5e-4 -5e-4 1.98119e-4 -8.91535e-4 -5e-4 0.01395899 -0.002202689 -5e-4 0.01390826 -0.001907825 -5e-4 -4.71754e-5 -5.62909e-4 -5e-4 -1.24159e-4 -5.28295e-4 -5e-4 2.2889e-5 -6.09979e-4 -5e-4 8.40373e-5 -6.68164e-4 -5e-4 1.34527e-4 -7.35806e-4 -5e-4 1.72919e-4 -8.10977e-4 -5e-4 0.000999987 -0.004499971 -5e-4 0.0139994 -0.002500057 -5e-4 0.01384729 -0.001615524 -5e-4 0.013776 -0.001325726 -5e-4 0.01369446 -0.001038491 -5e-4 0.01360255 -7.53803e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 -4.71754e-5 -5.62909e-4 5e-4 -1.24159e-4 -5.28295e-4 5e-4 0.01349997 -5e-4 5e-4 1.72919e-4 -8.10977e-4 5e-4 1.34527e-4 -7.35806e-4 5e-4 1.98119e-4 -8.91535e-4 5e-4 0.01360255 -7.53803e-4 5e-4 0.01369446 -0.001038491 5e-4 2.2889e-5 -6.09979e-4 5e-4 8.40373e-5 -6.68164e-4 5e-4 -2.05869e-4 -5.07125e-4 5e-4 0.01350045 -4.71615e-4 5e-4 -2.89975e-4 -5e-4 5e-4 0.013776 -0.001325726 5e-4 0.01384729 -0.001615524 5e-4 0.01390826 -0.001907825 5e-4 0.01395899 -0.002202689 5e-4 0.000999987 -0.004499971 5e-4 0.0139994 -0.002500057 5e-4 1.34527e-4 -7.35806e-4 -5e-4 1.34527e-4 -7.35806e-4 5e-4 1.72919e-4 -8.10977e-4 5e-4 1.98119e-4 -8.91535e-4 5e-4 1.98119e-4 -8.91535e-4 -5e-4 1.72919e-4 -8.10977e-4 -5e-4 2.2889e-5 -6.09979e-4 5e-4 -4.71754e-5 -5.62909e-4 -5e-4 -4.71754e-5 -5.62909e-4 5e-4 2.2889e-5 -6.09979e-4 -5e-4 8.40373e-5 -6.68164e-4 5e-4 8.40373e-5 -6.68164e-4 -5e-4 -1.24159e-4 -5.28295e-4 5e-4 -2.05869e-4 -5.07125e-4 -5e-4 -2.05869e-4 -5.07125e-4 5e-4 -1.24159e-4 -5.28295e-4 -5e-4 -2.89975e-4 -5e-4 5e-4 -2.89975e-4 -5e-4 -5e-4 0.01384729 -0.001615524 5e-4 0.013776 -0.001325726 -5e-4 0.01384729 -0.001615524 -5e-4 0.01390826 -0.001907825 -5e-4 0.01390826 -0.001907825 5e-4 0.01395899 -0.002202689 -5e-4 0.01395899 -0.002202689 5e-4 0.0139994 -0.002500057 5e-4 0.0139994 -0.002500057 -5e-4 0.013776 -0.001325726 5e-4 0.01369446 -0.001038491 -5e-4 0.01369446 -0.001038491 5e-4 0.01360255 -7.53803e-4 5e-4 0.01360255 -7.53803e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 0.01350045 -4.71615e-4 5e-4 0.01349997 -5e-4 0.004999995 -2.89975e-4 -5e-4 5e-4 -5e-4 -5e-4 0.004999995 -5e-4 -5e-4 -0.004999995 -2.89975e-4 -5e-4 -5e-4 0.01349997 -5e-4 -5e-4 0.01349997 -5e-4 -0.004999995 0.01349997 -5e-4 5e-4 0.01349997 5e-4 0.004999995 0.01349997 5e-4 -0.004999995 0.01350045 -4.71615e-4 5e-4 0.01349997 -5e-4 0.004999995 0.01349997 -5e-4 -0.004999995 0.01349997 -5e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 0.01349997 -5e-4 5e-4 -5e-4 -5e-4 0.004999995 -5e-4 5e-4 0.004999995 0.01349997 5e-4 0.004999995 0.01349997 -5e-4 0.004999995 -5e-4 -5e-4 -0.004999995 -5e-4 5e-4 -0.004999995 -5e-4 5e-4 0.004999995 -5e-4 -5e-4 0.004999995 0.01349997 5e-4 -0.004999995 -5e-4 5e-4 -0.004999995 -5e-4 -5e-4 -0.004999995 0.01349997 -5e-4 -0.004999995 -5e-4 5e-4 0.004999995 -5e-4 5e-4 -0.004999995 0 5e-4 7e-4 0 5e-4 -7e-4 0.01349997 5e-4 -0.004999995 0.01304668 5e-4 -7e-4 0.01349997 5e-4 0.004999995 0.01304668 5e-4 7e-4 0.01304525 5.02356e-4 6.69369e-4 0 5e-4 7e-4 0 5.02462e-4 6.68713e-4 0 5.38197e-4 5.82443e-4 0.01302689 5.35564e-4 5.86251e-4 0 5.21799e-4 6.09202e-4 0 5.09789e-4 6.38197e-4 0.01303517 5.20529e-4 6.11725e-4 0.01304137 5.0931e-4 6.39671e-4 0.01299178 5.97314e-4 5.28303e-4 0 5.82443e-4 5.38197e-4 0 6.09202e-4 5.21799e-4 0.0130167 5.53746e-4 5.63605e-4 0 5.58579e-4 5.58579e-4 0.01300495 5.74514e-4 5.4422e-4 0.01296305 6.47245e-4 5.07011e-4 0 6.38197e-4 5.09789e-4 0 6.68713e-4 5.02462e-4 0.01297777 6.21703e-4 5.1589e-4 0 7e-4 5e-4 0.01294785 6.73484e-4 5.01805e-4 0.01293236 7e-4 5e-4 0.01304668 5e-4 7e-4 2.21952e-4 0.01132625 5e-4 0.0115 0.002499997 -5e-4 0.0115 0.002499997 5e-4 2.21952e-4 0.01132625 -5e-4 2.90924e-7 0.01156806 -5e-4 2.90924e-7 0.01156806 5e-4 -5.45318e-5 0.01166325 5e-4 -9.8578e-5 0.01176398 5e-4 -9.8578e-5 0.01176398 -5e-4 -5.45318e-5 0.01166325 -5e-4 1.39249e-4 0.01139867 5e-4 1.39249e-4 0.01139867 -5e-4 2.21952e-4 0.01132625 -5e-4 6.52065e-5 0.01147949 5e-4 6.52065e-5 0.01147949 -5e-4 2.21952e-4 0.01132625 5e-4 -0.002154469 0.01727068 5e-4 -9.8578e-5 0.01176398 -5e-4 -9.8578e-5 0.01176398 5e-4 -0.002154469 0.01727068 -5e-4 -0.005992531 0.01667195 5e-4 -0.005999982 0.01649999 5e-4 -0.005999982 0.01649999 -5e-4 -0.005883276 0.01717305 5e-4 -0.00593388 0.01700979 5e-4 -0.00593388 0.01700979 -5e-4 -0.005970597 0.01684159 5e-4 -0.005992531 0.01667195 -5e-4 -0.005970597 0.01684159 -5e-4 -0.005740702 0.01748478 -5e-4 -0.005649507 0.01763087 5e-4 -0.005740702 0.01748478 5e-4 -0.005883276 0.01717305 -5e-4 -0.005818367 0.01733255 -5e-4 -0.005818367 0.01733255 5e-4 -0.005432128 0.01789599 5e-4 -0.005432128 0.01789599 -5e-4 -0.005307674 0.01801317 5e-4 -0.005546927 0.01776766 5e-4 -0.005649507 0.01763087 -5e-4 -0.005546927 0.01776766 -5e-4 -0.004878759 0.01829659 5e-4 -0.005030035 0.01821428 5e-4 -0.005030035 0.01821428 -5e-4 -0.005172669 0.01812005 -5e-4 -0.005172669 0.01812005 5e-4 -0.005307674 0.01801317 -5e-4 -0.00455904 0.01842015 -5e-4 -0.004392981 0.01846098 5e-4 -0.00455904 0.01842015 5e-4 -0.004878759 0.01829659 -5e-4 -0.004722118 0.01836508 -5e-4 -0.004722118 0.01836508 5e-4 -0.00405234 0.01849925 5e-4 -0.00405234 0.01849925 -5e-4 -0.003880143 0.01849639 5e-4 -0.004222869 0.01848745 5e-4 -0.004392981 0.01846098 -5e-4 -0.004222869 0.01848745 -5e-4 -0.003376424 0.01840025 5e-4 -0.003540933 0.01844656 5e-4 -0.003540933 0.01844656 -5e-4 -0.003710091 0.01847887 -5e-4 -0.003710091 0.01847887 5e-4 -0.003880143 0.01849639 -5e-4 -0.003061056 0.0182659 -5e-4 -0.00291264 0.01817846 5e-4 -0.003061056 0.0182659 5e-4 -0.003376424 0.01840025 -5e-4 -0.003215253 0.01833957 -5e-4 -0.003215253 0.01833957 5e-4 -0.002773225 0.01807957 5e-4 -0.00291264 0.01817846 -5e-4 -0.002773225 0.01807957 -5e-4 -0.002641916 0.01796817 5e-4 -0.002641916 0.01796817 -5e-4 -0.002521514 0.01784688 5e-4 -0.002411127 0.01771467 5e-4 -0.002521514 0.01784688 -5e-4 -0.002411127 0.01771467 -5e-4 -0.002313196 0.01757454 5e-4 -0.002313196 0.01757454 -5e-4 -0.002227604 0.01742655 5e-4 -0.002154469 0.01727068 5e-4 -0.002227604 0.01742655 -5e-4 -0.002154469 0.01727068 -5e-4 -0.005999982 0.008914172 5e-4 -0.005999982 0.01649999 -5e-4 -0.005999982 0.01649999 5e-4 -0.005999982 0.008914172 -5e-4 -0.005781888 0.008290827 5e-4 -0.005707085 0.008207082 5e-4 -0.005707085 0.008207082 -5e-4 -0.005943894 0.008583962 5e-4 -0.005900979 0.008480429 5e-4 -0.005900979 0.008480429 -5e-4 -0.005846798 0.00838238 5e-4 -0.005781888 0.008290827 -5e-4 -0.005846798 0.00838238 -5e-4 -0.005993664 0.008802056 -5e-4 -0.005993664 0.008802056 5e-4 -0.005974948 0.008691906 -5e-4 -0.005943894 0.008583962 -5e-4 -0.005974948 0.008691906 5e-4 -0.005999982 0.008914172 5e-4 -0.005999982 0.008914172 -5e-4 -2.92893e-4 0.002792835 5e-4 -0.005707085 0.008207082 -5e-4 -0.005707085 0.008207082 5e-4 -2.92893e-4 0.002792835 -5e-4 -2.51435e-5 0.002308547 -5e-4 -2.51435e-5 0.002308547 5e-4 -6.31239e-6 0.002197861 5e-4 0 0.002085745 5e-4 0 0.002085745 -5e-4 -6.31239e-6 0.002197861 -5e-4 -9.90717e-5 0.002519726 5e-4 -1.53405e-4 0.002617955 -5e-4 -1.53405e-4 0.002617955 5e-4 -9.90717e-5 0.002519726 -5e-4 -5.61788e-5 0.002416193 5e-4 -5.61788e-5 0.002416193 -5e-4 -2.18067e-4 0.00270909 5e-4 -2.18067e-4 0.00270909 -5e-4 -2.92893e-4 0.002792835 -5e-4 -2.92893e-4 0.002792835 5e-4 0 5.09789e-4 6.38197e-4 0 5.02462e-4 -6.68713e-4 0 5.09789e-4 -6.38197e-4 0 5e-4 -7e-4 0 5.02462e-4 6.68713e-4 0 5.38197e-4 -5.82443e-4 0 5.58579e-4 -5.58579e-4 0 5.58579e-4 5.58579e-4 0 5.21799e-4 -6.09202e-4 0 5.38197e-4 5.82443e-4 0 5.21799e-4 6.09202e-4 0 6.38197e-4 -5.09789e-4 0 6.38197e-4 5.09789e-4 0 6.09202e-4 -5.21799e-4 0 6.09202e-4 5.21799e-4 0 5.82443e-4 5.38197e-4 0 5.82443e-4 -5.38197e-4 0 6.68713e-4 -5.02462e-4 0 6.68713e-4 5.02462e-4 0 7e-4 5e-4 0 7e-4 -5e-4 0 0.002085745 -5e-4 0 0.002085745 5e-4 0 5e-4 7e-4 0 6.38197e-4 -5.09789e-4 0.01297765 6.21724e-4 -5.16018e-4 0.01296305 6.47241e-4 -5.07144e-4 0 7e-4 -5e-4 0 6.68713e-4 -5.02462e-4 0.01294785 6.73474e-4 -5.01807e-4 0.01300495 5.74515e-4 -5.44227e-4 0 5.58579e-4 -5.58579e-4 0.0130167 5.53722e-4 -5.63585e-4 0 5.82443e-4 -5.38197e-4 0.01299178 5.9735e-4 -5.28409e-4 0 6.09202e-4 -5.21799e-4 0 5.09789e-4 -6.38197e-4 0.01304137 5.09316e-4 -6.39685e-4 0.01303517 5.20533e-4 -6.11742e-4 0 5.21799e-4 -6.09202e-4 0.01302689 5.35529e-4 -5.86212e-4 0 5.38197e-4 -5.82443e-4 0 5.02462e-4 -6.68713e-4 0.01304525 5.02361e-4 -6.69377e-4 0.01304668 5e-4 -7e-4 0 5e-4 -7e-4 0.01293236 7e-4 -5e-4 0.01297765 6.21724e-4 -5.16018e-4 0.01299178 5.9735e-4 -5.28409e-4 0.01297777 6.21703e-4 5.1589e-4 0.01304137 5.0931e-4 6.39671e-4 0.01304137 5.09316e-4 -6.39685e-4 0.01304525 5.02361e-4 -6.69377e-4 0.01304668 5e-4 -7e-4 0.01304668 5e-4 7e-4 0.01304525 5.02356e-4 6.69369e-4 0.01302689 5.35564e-4 5.86251e-4 0.01302689 5.35529e-4 -5.86212e-4 0.01303517 5.20533e-4 -6.11742e-4 0.01303517 5.20529e-4 6.11725e-4 0.01299178 5.97314e-4 5.28303e-4 0.01300495 5.74515e-4 -5.44227e-4 0.01300495 5.74514e-4 5.4422e-4 0.0130167 5.53722e-4 -5.63585e-4 0.0130167 5.53746e-4 5.63605e-4 0.01296305 6.47241e-4 -5.07144e-4 0.01294785 6.73484e-4 5.01805e-4 0.01294785 6.73474e-4 -5.01807e-4 0.01296305 6.47245e-4 5.07011e-4 0.01293236 7e-4 -5e-4 0.01293236 7e-4 5e-4 0.01258188 0.001242518 -5e-4 0.01258188 0.001242518 5e-4 0.012389 0.001505315 5e-4 0.01276296 9.74095e-4 5e-4 0.01276296 9.74095e-4 -5e-4 0.01196795 0.002013921 5e-4 0.01173985 0.00225979 5e-4 0.01196795 0.002013921 -5e-4 0.01218438 0.001762449 5e-4 0.01218438 0.001762449 -5e-4 0.012389 0.001505315 -5e-4 0.01173985 0.00225979 -5e-4 0.0115 0.002499997 5e-4 0.0115 0.002499997 -5e-4 -0.004992663 0.01312065 5e-4 -0.004999995 0.01299995 -5e-4 -0.004999995 0.01299995 5e-4 -0.004885435 0.01346457 5e-4 -0.004935026 0.01335448 -5e-4 -0.004935026 0.01335448 5e-4 -0.004970967 0.01323896 5e-4 -0.004970967 0.01323896 -5e-4 -0.004992663 0.01312065 -5e-4 -0.004748642 0.01366287 -5e-4 -0.004748642 0.01366287 5e-4 -0.004663169 0.01374846 5e-4 -0.004885435 0.01346457 -5e-4 -0.004823088 0.01356774 5e-4 -0.004823088 0.01356774 -5e-4 -0.004464924 0.01388525 5e-4 -0.004354774 0.01393485 5e-4 -0.004464924 0.01388525 -5e-4 -0.004568159 0.01382285 5e-4 -0.004568159 0.01382285 -5e-4 -0.004663169 0.01374846 -5e-4 -0.004000246 0.01399999 5e-4 -0.004120767 0.01399266 -5e-4 -0.004120767 0.01399266 5e-4 -0.00423932 0.01397085 -5e-4 -0.004354774 0.01393485 -5e-4 -0.00423932 0.01397085 5e-4 -0.003760695 0.01397085 -5e-4 -0.003760695 0.01397085 5e-4 -0.003645658 0.01393508 5e-4 -0.004000246 0.01399999 -5e-4 -0.003879606 0.01399266 5e-4 -0.003879606 0.01399266 -5e-4 -0.003431975 0.01382297 5e-4 -0.003336966 0.01374858 5e-4 -0.003431975 0.01382297 -5e-4 -0.003535509 0.01388555 5e-4 -0.003535509 0.01388555 -5e-4 -0.003645658 0.01393508 -5e-4 -0.003114521 0.01346474 5e-4 -0.003177106 0.01356816 -5e-4 -0.003177106 0.01356816 5e-4 -0.003251671 0.01366329 -5e-4 -0.003336966 0.01374858 -5e-4 -0.003251671 0.01366329 5e-4 -0.003029108 0.01323956 -5e-4 -0.003029108 0.01323956 5e-4 -0.003007292 0.01312065 5e-4 -0.003114521 0.01346474 -5e-4 -0.003065049 0.01335477 5e-4 -0.003065049 0.01335477 -5e-4 -0.003007292 0.01287925 5e-4 -0.003028988 0.01276099 5e-4 -0.003007292 0.01287925 -5e-4 -0.002999961 0.01299995 5e-4 -0.002999961 0.01299995 -5e-4 -0.003007292 0.01312065 -5e-4 -0.003176867 0.01243215 5e-4 -0.003114461 0.01253539 -5e-4 -0.003114461 0.01253539 5e-4 -0.00306493 0.01264548 -5e-4 -0.003028988 0.01276099 -5e-4 -0.00306493 0.01264548 5e-4 -0.003336787 0.01225149 -5e-4 -0.003336787 0.01225149 5e-4 -0.003431797 0.01217705 5e-4 -0.003176867 0.01243215 -5e-4 -0.003251314 0.01233708 5e-4 -0.003251314 0.01233708 -5e-4 -0.003645181 0.01206505 5e-4 -0.003760635 0.01202905 5e-4 -0.003645181 0.01206505 -5e-4 -0.003534972 0.0121147 5e-4 -0.003534972 0.0121147 -5e-4 -0.003431797 0.01217705 -5e-4 -0.003879189 0.01200729 -5e-4 -0.003760635 0.01202905 -5e-4 -0.003879189 0.01200729 5e-4 -0.004120349 0.01200729 5e-4 -0.004120349 0.01200729 -5e-4 -0.00399971 0.01199996 -5e-4 -0.00399971 0.01199996 5e-4 -0.004239201 0.01202905 5e-4 -0.004239201 0.01202905 -5e-4 -0.004354298 0.01206487 -5e-4 -0.004354298 0.01206487 5e-4 -0.004464447 0.01211434 5e-4 -0.004464447 0.01211434 -5e-4 -0.004567921 0.01217699 5e-4 -0.004567921 0.01217699 -5e-4 -0.00466299 0.01225137 -5e-4 -0.00466299 0.01225137 5e-4 -0.004748284 0.01233667 5e-4 -0.004748284 0.01233667 -5e-4 -0.00482285 0.0124318 5e-4 -0.00482285 0.0124318 -5e-4 -0.004885375 0.01253515 -5e-4 -0.004885375 0.01253515 5e-4 -0.004934906 0.01264518 5e-4 -0.004934906 0.01264518 -5e-4 -0.004970848 0.0127604 5e-4 -0.004970848 0.0127604 -5e-4 -0.004992663 0.01287925 -5e-4 -0.004992663 0.01287925 5e-4 -0.004992663 0.01662069 5e-4 -0.004999995 0.01649999 -5e-4 -0.004999995 0.01649999 5e-4 -0.004885435 0.01696455 5e-4 -0.004935026 0.01685446 -5e-4 -0.004935026 0.01685446 5e-4 -0.004970967 0.01673895 5e-4 -0.004970967 0.01673895 -5e-4 -0.004992663 0.01662069 -5e-4 -0.004748642 0.01716285 -5e-4 -0.004748642 0.01716285 5e-4 -0.004663169 0.01724845 5e-4 -0.004885435 0.01696455 -5e-4 -0.004823088 0.01706779 5e-4 -0.004823088 0.01706779 -5e-4 -0.004464924 0.0173853 5e-4 -0.004354774 0.01743489 5e-4 -0.004464924 0.0173853 -5e-4 -0.004568159 0.01732289 5e-4 -0.004568159 0.01732289 -5e-4 -0.004663169 0.01724845 -5e-4 -0.004000246 0.01749998 5e-4 -0.004120767 0.01749265 -5e-4 -0.004120767 0.01749265 5e-4 -0.00423932 0.01747089 -5e-4 -0.004354774 0.01743489 -5e-4 -0.00423932 0.01747089 5e-4 -0.003760695 0.01747089 -5e-4 -0.003760695 0.01747089 5e-4 -0.003645658 0.01743507 5e-4 -0.004000246 0.01749998 -5e-4 -0.003879606 0.01749265 5e-4 -0.003879606 0.01749265 -5e-4 -0.003431975 0.01732295 5e-4 -0.003336966 0.01724857 5e-4 -0.003431975 0.01732295 -5e-4 -0.003535509 0.0173856 5e-4 -0.003535509 0.0173856 -5e-4 -0.003645658 0.01743507 -5e-4 -0.003114521 0.01696479 5e-4 -0.003177106 0.01706814 -5e-4 -0.003177106 0.01706814 5e-4 -0.003251671 0.01716327 -5e-4 -0.003336966 0.01724857 -5e-4 -0.003251671 0.01716327 5e-4 -0.003029108 0.01673954 -5e-4 -0.003029108 0.01673954 5e-4 -0.003007292 0.01662069 5e-4 -0.003114521 0.01696479 -5e-4 -0.003065049 0.01685476 5e-4 -0.003065049 0.01685476 -5e-4 -0.003007292 0.01637929 5e-4 -0.003028988 0.01626098 5e-4 -0.003007292 0.01637929 -5e-4 -0.002999961 0.01649999 5e-4 -0.002999961 0.01649999 -5e-4 -0.003007292 0.01662069 -5e-4 -0.003176867 0.0159322 5e-4 -0.003114461 0.01603537 -5e-4 -0.003114461 0.01603537 5e-4 -0.00306493 0.01614546 -5e-4 -0.003028988 0.01626098 -5e-4 -0.00306493 0.01614546 5e-4 -0.003336787 0.01575148 -5e-4 -0.003336787 0.01575148 5e-4 -0.003431797 0.01567709 5e-4 -0.003176867 0.0159322 -5e-4 -0.003251314 0.01583707 5e-4 -0.003251314 0.01583707 -5e-4 -0.003645181 0.01556509 5e-4 -0.003760635 0.01552909 5e-4 -0.003645181 0.01556509 -5e-4 -0.003534972 0.01561468 5e-4 -0.003534972 0.01561468 -5e-4 -0.003431797 0.01567709 -5e-4 -0.003879189 0.01550728 -5e-4 -0.003760635 0.01552909 -5e-4 -0.003879189 0.01550728 5e-4 -0.004120349 0.01550728 5e-4 -0.004120349 0.01550728 -5e-4 -0.00399971 0.01549994 -5e-4 -0.00399971 0.01549994 5e-4 -0.004239201 0.01552909 5e-4 -0.004239201 0.01552909 -5e-4 -0.004354298 0.01556485 -5e-4 -0.004354298 0.01556485 5e-4 -0.004464447 0.01561439 5e-4 -0.004464447 0.01561439 -5e-4 -0.004567921 0.01567697 5e-4 -0.004567921 0.01567697 -5e-4 -0.00466299 0.01575136 -5e-4 -0.00466299 0.01575136 5e-4 -0.004748284 0.01583665 5e-4 -0.004748284 0.01583665 -5e-4 -0.00482285 0.01593178 5e-4 -0.00482285 0.01593178 -5e-4 -0.004885375 0.01603519 -5e-4 -0.004885375 0.01603519 5e-4 -0.004934906 0.01614516 5e-4 -0.004934906 0.01614516 -5e-4 -0.004970848 0.01626038 5e-4 -0.004970848 0.01626038 -5e-4 -0.004992663 0.01637929 -5e-4 -0.004992663 0.01637929 5e-4 -0.003999948 0.008499979 5e-4 -0.005707085 0.008207082 5e-4 -0.004120171 0.008507251 5e-4 0 0.002085745 5e-4 -6.31239e-6 0.002197861 5e-4 0.0115 0.002499997 5e-4 -0.005030035 0.01821428 5e-4 -0.004464924 0.0173853 5e-4 -0.005172669 0.01812005 5e-4 0 7e-4 5e-4 0.01173985 0.00225979 5e-4 0.01218438 0.001762449 5e-4 0.01196795 0.002013921 5e-4 0.012389 0.001505315 5e-4 0.01258188 0.001242518 5e-4 0.01276296 9.74095e-4 5e-4 0.01293236 7e-4 5e-4 -2.51435e-5 0.002308547 5e-4 -5.61788e-5 0.002416193 5e-4 -9.90717e-5 0.002519726 5e-4 -1.53405e-4 0.002617955 5e-4 -2.18067e-4 0.00270909 5e-4 2.21952e-4 0.01132625 5e-4 -2.92893e-4 0.002792835 5e-4 6.52065e-5 0.01147949 5e-4 -0.003114521 0.009964764 5e-4 2.90924e-7 0.01156806 5e-4 -0.003065049 0.009854733 5e-4 1.39249e-4 0.01139867 5e-4 -0.003029108 0.009739577 5e-4 -0.003114461 0.01253539 5e-4 -0.00306493 0.01264548 5e-4 -9.8578e-5 0.01176398 5e-4 -0.003431797 0.01217705 5e-4 -0.003336787 0.01225149 5e-4 -0.003336966 0.0102486 5e-4 -0.003028988 0.01276099 5e-4 -0.003007292 0.01287925 5e-4 -0.002999961 0.01299995 5e-4 -0.004354774 0.01743489 5e-4 -0.004722118 0.01836508 5e-4 -0.00423932 0.01747089 5e-4 -0.004970967 0.01673895 5e-4 -0.00593388 0.01700979 5e-4 -0.004935026 0.01685446 5e-4 -0.00455904 0.01842015 5e-4 -0.004392981 0.01846098 5e-4 -0.004878759 0.01829659 5e-4 -0.004568159 0.01732289 5e-4 -0.004120767 0.01749265 5e-4 -0.004000246 0.01749998 5e-4 -0.004222869 0.01848745 5e-4 -0.004663169 0.01724845 5e-4 -0.005307674 0.01801317 5e-4 -0.003880143 0.01849639 5e-4 -0.00405234 0.01849925 5e-4 -0.004748642 0.01716285 5e-4 -0.005432128 0.01789599 5e-4 -0.003879606 0.01749265 5e-4 -0.005546927 0.01776766 5e-4 -0.003710091 0.01847887 5e-4 -0.003540933 0.01844656 5e-4 -0.005649507 0.01763087 5e-4 -0.004823088 0.01706779 5e-4 -0.003760695 0.01747089 5e-4 -0.003376424 0.01840025 5e-4 -0.003645658 0.01743507 5e-4 -0.004885435 0.01696455 5e-4 -0.005740702 0.01748478 5e-4 -0.003061056 0.0182659 5e-4 -0.003215253 0.01833957 5e-4 -0.005818367 0.01733255 5e-4 -0.003535509 0.0173856 5e-4 -0.00291264 0.01817846 5e-4 -0.003431975 0.01732295 5e-4 -0.005883276 0.01717305 5e-4 -0.002641916 0.01796817 5e-4 -0.002773225 0.01807957 5e-4 -0.003336966 0.01724857 5e-4 -0.002521514 0.01784688 5e-4 -0.003251671 0.01716327 5e-4 -0.004992663 0.01662069 5e-4 -0.005970597 0.01684159 5e-4 -0.004999995 0.01649999 5e-4 -0.005999982 0.01649999 5e-4 -0.005992531 0.01667195 5e-4 -0.004934906 0.01614516 5e-4 -0.004885375 0.01603519 5e-4 -0.004992663 0.01637929 5e-4 -0.004970848 0.01626038 5e-4 -0.004748284 0.01583665 5e-4 -0.004748642 0.01366287 5e-4 -0.00482285 0.01593178 5e-4 -0.00466299 0.01575136 5e-4 -0.004663169 0.01374846 5e-4 -5.45318e-5 0.01166325 5e-4 -0.003177106 0.01006817 5e-4 -0.004464447 0.00861442 5e-4 -0.004354536 0.008564949 5e-4 -0.004567742 0.008676826 5e-4 -0.004239022 0.008528947 5e-4 -0.005999982 0.008914172 5e-4 -0.004999995 0.01299995 5e-4 -0.004992663 0.01287925 5e-4 -0.003114521 0.01346474 5e-4 -0.003114461 0.01603537 5e-4 -0.003176867 0.01243215 5e-4 -0.003645181 0.01206505 5e-4 -0.003535509 0.01038557 5e-4 -0.003645658 0.0104351 5e-4 -0.003534972 0.0121147 5e-4 -0.003431975 0.01032298 5e-4 -0.003251314 0.01233708 5e-4 -0.003760695 0.01047086 5e-4 -0.003760635 0.01202905 5e-4 -0.003251671 0.01016324 5e-4 -0.004000246 0.01049995 5e-4 -0.004120767 0.01049268 5e-4 -0.004120349 0.01200729 5e-4 -0.003879189 0.01200729 5e-4 -0.003879606 0.01049268 5e-4 -0.00399971 0.01199996 5e-4 -0.004567921 0.01217699 5e-4 -0.004464924 0.01038527 5e-4 -0.004568159 0.01032286 5e-4 -0.004354298 0.01206487 5e-4 -0.00423932 0.01047086 5e-4 -0.004354774 0.01043486 5e-4 -0.00466299 0.01225137 5e-4 -0.004748344 0.008836686 5e-4 -0.004822731 0.008931636 5e-4 -0.004663169 0.01024848 5e-4 -0.004885315 0.00903511 5e-4 -0.005900979 0.008480429 5e-4 -0.004970788 0.009260356 5e-4 -0.004934906 0.009145259 5e-4 -0.004999995 0.009499967 5e-4 -0.004992663 0.009620666 5e-4 -0.004934906 0.01264518 5e-4 -0.004885375 0.01253515 5e-4 -0.004885435 0.009964585 5e-4 -0.004935026 0.009854435 5e-4 -0.004970848 0.0127604 5e-4 -0.004970967 0.01323896 5e-4 -0.004992663 0.01312065 5e-4 -0.004567921 0.01567697 5e-4 -0.004568159 0.01382285 5e-4 -0.004885435 0.01346457 5e-4 -0.004935026 0.01335448 5e-4 -0.004823088 0.01356774 5e-4 -0.00423932 0.01397085 5e-4 -0.004239201 0.01552909 5e-4 -0.004120767 0.01399266 5e-4 -0.004464924 0.01388525 5e-4 -0.004464447 0.01561439 5e-4 -0.004354774 0.01393485 5e-4 -0.003760635 0.01552909 5e-4 -0.003760695 0.01397085 5e-4 -0.003879189 0.01550728 5e-4 -0.00399971 0.01549994 5e-4 -0.004000246 0.01399999 5e-4 -0.004120349 0.01550728 5e-4 -0.003431797 0.01567709 5e-4 -0.003431975 0.01382297 5e-4 -0.003534972 0.01561468 5e-4 -0.003535509 0.01388555 5e-4 -0.003645181 0.01556509 5e-4 -0.003336966 0.01374858 5e-4 -0.003336787 0.01575148 5e-4 -0.002313196 0.01757454 5e-4 -0.003177106 0.01706814 5e-4 -0.002411127 0.01771467 5e-4 -0.003251314 0.01583707 5e-4 -0.003177106 0.01356816 5e-4 -0.003251671 0.01366329 5e-4 -0.003176867 0.0159322 5e-4 -0.00306493 0.01614546 5e-4 -0.002154469 0.01727068 5e-4 -0.003007292 0.01637929 5e-4 -0.002999961 0.01649999 5e-4 -0.003028988 0.01626098 5e-4 -0.003065049 0.01335477 5e-4 -0.003007292 0.01312065 5e-4 -0.003029108 0.01323956 5e-4 -0.003645658 0.01393508 5e-4 -0.003879606 0.01399266 5e-4 -0.004354298 0.01556485 5e-4 -0.002227604 0.01742655 5e-4 -0.003114521 0.01696479 5e-4 -0.003029108 0.01673954 5e-4 -0.003065049 0.01685476 5e-4 -0.003007292 0.01662069 5e-4 -0.003028988 0.009260952 5e-4 -0.003007292 0.009379208 5e-4 -0.002999961 0.009499967 5e-4 -0.005781888 0.008290827 5e-4 -0.005846798 0.00838238 5e-4 -0.003114402 0.009035527 5e-4 -0.00306493 0.009145438 5e-4 -0.003176808 0.008932173 5e-4 -0.003336727 0.00875163 5e-4 -0.003251373 0.008836925 5e-4 -0.003535091 0.008614599 5e-4 -0.003431618 0.008677184 5e-4 -0.003760337 0.008529126 5e-4 -0.003645241 0.008565008 5e-4 -0.003879189 0.008507311 5e-4 -0.00466299 0.008751392 5e-4 -0.004464447 0.01211434 5e-4 -0.004748284 0.01233667 5e-4 -0.004748642 0.01016288 5e-4 -0.005943894 0.008583962 5e-4 -0.005974948 0.008691906 5e-4 -0.00482285 0.0124318 5e-4 -0.005993664 0.008802056 5e-4 -0.004823088 0.01006776 5e-4 -0.004992663 0.009379208 5e-4 -0.004970967 0.009739041 5e-4 -0.004239201 0.01202905 5e-4 -0.003007292 0.009620666 5e-4 -0.005707085 0.008207082 -5e-4 -0.004464864 0.008614599 -5e-4 -0.004568278 0.008677184 -5e-4 -5.61788e-5 0.002416193 -5e-4 -2.51435e-5 0.002308547 -5e-4 0.0115 0.002499997 -5e-4 -6.31239e-6 0.002197861 -5e-4 -9.90717e-5 0.002519726 -5e-4 -1.53405e-4 0.002617955 -5e-4 2.21952e-4 0.01132625 -5e-4 -2.18067e-4 0.00270909 -5e-4 -0.004120767 0.008507311 -5e-4 -0.004239618 0.008529126 -5e-4 -0.003999948 0.008499979 -5e-4 -0.00482285 0.01593178 -5e-4 -0.004885375 0.01603519 -5e-4 -0.005999982 0.01649999 -5e-4 -0.004992663 0.01287925 -5e-4 -0.004999995 0.01299995 -5e-4 -0.005999982 0.008914172 -5e-4 -0.003760695 0.01747089 -5e-4 -0.003645658 0.01743507 -5e-4 -0.003376424 0.01840025 -5e-4 -0.005970597 0.01684159 -5e-4 -0.004992663 0.01662069 -5e-4 -0.004970967 0.01673895 -5e-4 -0.004000246 0.01749998 -5e-4 -0.004222869 0.01848745 -5e-4 -0.004120767 0.01749265 -5e-4 -0.004722118 0.01836508 -5e-4 -0.004354774 0.01743489 -5e-4 -0.00423932 0.01747089 -5e-4 -0.005030035 0.01821428 -5e-4 -0.005172669 0.01812005 -5e-4 -0.004464924 0.0173853 -5e-4 -0.004392981 0.01846098 -5e-4 -0.00455904 0.01842015 -5e-4 -0.004878759 0.01829659 -5e-4 -0.004568159 0.01732289 -5e-4 -0.004663169 0.01724845 -5e-4 -0.005432128 0.01789599 -5e-4 -0.004748642 0.01716285 -5e-4 -0.005307674 0.01801317 -5e-4 -0.005546927 0.01776766 -5e-4 -0.003880143 0.01849639 -5e-4 -0.00405234 0.01849925 -5e-4 -0.005649507 0.01763087 -5e-4 -0.004823088 0.01706779 -5e-4 -0.003879606 0.01749265 -5e-4 -0.005740702 0.01748478 -5e-4 -0.004885435 0.01696455 -5e-4 -0.003710091 0.01847887 -5e-4 -0.003540933 0.01844656 -5e-4 -0.003061056 0.0182659 -5e-4 -0.003215253 0.01833957 -5e-4 -0.004935026 0.01685446 -5e-4 -0.005818367 0.01733255 -5e-4 -0.00291264 0.01817846 -5e-4 -0.003535509 0.0173856 -5e-4 -0.003431975 0.01732295 -5e-4 -0.005883276 0.01717305 -5e-4 -0.002641916 0.01796817 -5e-4 -0.002773225 0.01807957 -5e-4 -0.00593388 0.01700979 -5e-4 -0.002521514 0.01784688 -5e-4 -0.003336966 0.01724857 -5e-4 -0.003251671 0.01716327 -5e-4 -0.004999995 0.01649999 -5e-4 -0.005992531 0.01667195 -5e-4 -0.004934906 0.01614516 -5e-4 -0.004992663 0.01637929 -5e-4 -0.004970848 0.01626038 -5e-4 -0.004748642 0.01366287 -5e-4 -0.004748284 0.01583665 -5e-4 -0.003645181 0.01206505 -5e-4 -0.003760635 0.01202905 -5e-4 -0.003645181 0.01043486 -5e-4 -0.004663169 0.01374846 -5e-4 -0.00466299 0.01575136 -5e-4 -0.004934906 0.009854733 -5e-4 -0.004970848 0.009739577 -5e-4 -0.004885554 0.009035527 -5e-4 -0.005993664 0.008802056 -5e-4 -0.003251314 0.01233708 -5e-4 -0.003251314 0.01016288 -5e-4 -9.8578e-5 0.01176398 -5e-4 -0.004354655 0.008565008 -5e-4 -2.92893e-4 0.002792835 -5e-4 -5.45318e-5 0.01166325 -5e-4 -0.003176867 0.01006776 -5e-4 -0.004823148 0.008932173 -5e-4 -0.004748582 0.008836925 -5e-4 -0.005781888 0.008290827 -5e-4 -0.005846798 0.00838238 -5e-4 2.90924e-7 0.01156806 -5e-4 -0.003114461 0.009964585 -5e-4 6.52065e-5 0.01147949 -5e-4 0 0.002085745 -5e-4 0 7e-4 -5e-4 0.01196795 0.002013921 -5e-4 0.01173985 0.00225979 -5e-4 0.01218438 0.001762449 -5e-4 0.012389 0.001505315 -5e-4 0.01276296 9.74095e-4 -5e-4 0.01258188 0.001242518 -5e-4 0.01293236 7e-4 -5e-4 -0.002999961 0.009499967 -5e-4 -0.003007292 0.009379208 -5e-4 -0.003028988 0.009739041 -5e-4 1.39249e-4 0.01139867 -5e-4 -0.00306493 0.009854435 -5e-4 -0.003029167 0.009260356 -5e-4 -0.00306499 0.009145259 -5e-4 -0.003114581 0.00903511 -5e-4 -0.003251612 0.008836686 -5e-4 -0.003177225 0.008931636 -5e-4 -0.003432154 0.008676826 -5e-4 -0.003336966 0.008751392 -5e-4 -0.00364542 0.008564949 -5e-4 -0.003535509 0.00861442 -5e-4 -0.003879725 0.008507251 -5e-4 -0.003760933 0.008528947 -5e-4 -0.004663228 0.00875163 -5e-4 -0.005900979 0.008480429 -5e-4 -0.005974948 0.008691906 -5e-4 -0.005943894 0.008583962 -5e-4 -0.004992663 0.009620666 -5e-4 -0.004999995 0.009499967 -5e-4 -0.004970967 0.009260952 -5e-4 -0.004935026 0.009145438 -5e-4 -0.004992663 0.009379208 -5e-4 -0.003431797 0.01032286 -5e-4 -0.003431797 0.01217705 -5e-4 -0.003534972 0.0121147 -5e-4 -0.004748284 0.01233667 -5e-4 -0.004748284 0.01016324 -5e-4 -0.00466299 0.0102486 -5e-4 -0.004885375 0.009964764 -5e-4 -0.004464447 0.01038557 -5e-4 -0.004354298 0.0104351 -5e-4 -0.004464447 0.01211434 -5e-4 -0.004567921 0.01217699 -5e-4 -0.004567921 0.01032298 -5e-4 -0.00399971 0.01199996 -5e-4 -0.004120349 0.01200729 -5e-4 -0.00399971 0.01049995 -5e-4 -0.004239201 0.01202905 -5e-4 -0.004354298 0.01206487 -5e-4 -0.004239201 0.01047086 -5e-4 -0.003534972 0.01038527 -5e-4 -0.003879189 0.01200729 -5e-4 -0.003760635 0.01047086 -5e-4 -0.003879189 0.01049268 -5e-4 -0.003336787 0.01024848 -5e-4 -0.003336787 0.01225149 -5e-4 -0.003114461 0.01253539 -5e-4 -0.003176867 0.01243215 -5e-4 -0.003028988 0.01276099 -5e-4 -0.00306493 0.01264548 -5e-4 -0.003007292 0.009620666 -5e-4 -0.003114461 0.01603537 -5e-4 -0.003114521 0.01346474 -5e-4 -0.003007292 0.01287925 -5e-4 -0.002999961 0.01299995 -5e-4 -0.004120349 0.01049268 -5e-4 -0.00466299 0.01225137 -5e-4 -0.00482285 0.0124318 -5e-4 -0.00482285 0.01006817 -5e-4 -0.004885375 0.01253515 -5e-4 -0.004934906 0.01264518 -5e-4 -0.004970848 0.0127604 -5e-4 -0.004970967 0.01323896 -5e-4 -0.004992663 0.01312065 -5e-4 -0.004568159 0.01382285 -5e-4 -0.004567921 0.01567697 -5e-4 -0.004885435 0.01346457 -5e-4 -0.004935026 0.01335448 -5e-4 -0.004823088 0.01356774 -5e-4 -0.00423932 0.01397085 -5e-4 -0.004120767 0.01399266 -5e-4 -0.004239201 0.01552909 -5e-4 -0.004464924 0.01388525 -5e-4 -0.004354774 0.01393485 -5e-4 -0.004464447 0.01561439 -5e-4 -0.003760635 0.01552909 -5e-4 -0.003879189 0.01550728 -5e-4 -0.003760695 0.01397085 -5e-4 -0.00399971 0.01549994 -5e-4 -0.004120349 0.01550728 -5e-4 -0.004000246 0.01399999 -5e-4 -0.003431797 0.01567709 -5e-4 -0.003534972 0.01561468 -5e-4 -0.003431975 0.01382297 -5e-4 -0.003535509 0.01388555 -5e-4 -0.003645181 0.01556509 -5e-4 -0.003336966 0.01374858 -5e-4 -0.003336787 0.01575148 -5e-4 -0.003251314 0.01583707 -5e-4 -0.003251671 0.01366329 -5e-4 -0.003177106 0.01356816 -5e-4 -0.003176867 0.0159322 -5e-4 -0.003007292 0.01637929 -5e-4 -0.002154469 0.01727068 -5e-4 -0.002999961 0.01649999 -5e-4 -0.003028988 0.01626098 -5e-4 -0.00306493 0.01614546 -5e-4 -0.003065049 0.01335477 -5e-4 -0.003007292 0.01312065 -5e-4 -0.003029108 0.01323956 -5e-4 -0.003177106 0.01706814 -5e-4 -0.002313196 0.01757454 -5e-4 -0.002411127 0.01771467 -5e-4 -0.003645658 0.01393508 -5e-4 -0.003879606 0.01399266 -5e-4 -0.004354298 0.01556485 -5e-4 -0.002227604 0.01742655 -5e-4 -0.003114521 0.01696479 -5e-4 -0.003029108 0.01673954 -5e-4 -0.003065049 0.01685476 -5e-4 -0.003007292 0.01662069 -5e-4 -0.004992663 0.009620666 5e-4 -0.004999995 0.009499967 -5e-4 -0.004999995 0.009499967 5e-4 -0.004885435 0.009964585 5e-4 -0.004934906 0.009854733 -5e-4 -0.004935026 0.009854435 5e-4 -0.004970967 0.009739041 5e-4 -0.004970848 0.009739577 -5e-4 -0.004992663 0.009620666 -5e-4 -0.004748284 0.01016324 -5e-4 -0.004748642 0.01016288 5e-4 -0.004663169 0.01024848 5e-4 -0.004885375 0.009964764 -5e-4 -0.004823088 0.01006776 5e-4 -0.00482285 0.01006817 -5e-4 -0.004464924 0.01038527 5e-4 -0.004354774 0.01043486 5e-4 -0.004464447 0.01038557 -5e-4 -0.004568159 0.01032286 5e-4 -0.004567921 0.01032298 -5e-4 -0.00466299 0.0102486 -5e-4 -0.004000246 0.01049995 5e-4 -0.004120349 0.01049268 -5e-4 -0.004120767 0.01049268 5e-4 -0.004239201 0.01047086 -5e-4 -0.004354298 0.0104351 -5e-4 -0.00423932 0.01047086 5e-4 -0.003760635 0.01047086 -5e-4 -0.003760695 0.01047086 5e-4 -0.003645658 0.0104351 5e-4 -0.00399971 0.01049995 -5e-4 -0.003879606 0.01049268 5e-4 -0.003879189 0.01049268 -5e-4 -0.003431975 0.01032298 5e-4 -0.003336966 0.0102486 5e-4 -0.003431797 0.01032286 -5e-4 -0.003535509 0.01038557 5e-4 -0.003534972 0.01038527 -5e-4 -0.003645181 0.01043486 -5e-4 -0.003114521 0.009964764 5e-4 -0.003176867 0.01006776 -5e-4 -0.003177106 0.01006817 5e-4 -0.003251314 0.01016288 -5e-4 -0.003336787 0.01024848 -5e-4 -0.003251671 0.01016324 5e-4 -0.003028988 0.009739041 -5e-4 -0.003029108 0.009739577 5e-4 -0.003007292 0.009620666 5e-4 -0.003114461 0.009964585 -5e-4 -0.003065049 0.009854733 5e-4 -0.00306493 0.009854435 -5e-4 -0.003007292 0.009379208 5e-4 -0.003028988 0.009260952 5e-4 -0.003007292 0.009379208 -5e-4 -0.002999961 0.009499967 5e-4 -0.002999961 0.009499967 -5e-4 -0.003007292 0.009620666 -5e-4 -0.003176808 0.008932173 5e-4 -0.003114581 0.00903511 -5e-4 -0.003114402 0.009035527 5e-4 -0.00306499 0.009145259 -5e-4 -0.003029167 0.009260356 -5e-4 -0.00306493 0.009145438 5e-4 -0.003336966 0.008751392 -5e-4 -0.003336727 0.00875163 5e-4 -0.003431618 0.008677184 5e-4 -0.003177225 0.008931636 -5e-4 -0.003251373 0.008836925 5e-4 -0.003251612 0.008836686 -5e-4 -0.003645241 0.008565008 5e-4 -0.003760337 0.008529126 5e-4 -0.00364542 0.008564949 -5e-4 -0.003535091 0.008614599 5e-4 -0.003535509 0.00861442 -5e-4 -0.003432154 0.008676826 -5e-4 -0.003879725 0.008507251 -5e-4 -0.003760933 0.008528947 -5e-4 -0.003879189 0.008507311 5e-4 -0.004120171 0.008507251 5e-4 -0.004120767 0.008507311 -5e-4 -0.003999948 0.008499979 -5e-4 -0.003999948 0.008499979 5e-4 -0.004239022 0.008528947 5e-4 -0.004239618 0.008529126 -5e-4 -0.004354655 0.008565008 -5e-4 -0.004354536 0.008564949 5e-4 -0.004464447 0.00861442 5e-4 -0.004464864 0.008614599 -5e-4 -0.004567742 0.008676826 5e-4 -0.004568278 0.008677184 -5e-4 -0.004663228 0.00875163 -5e-4 -0.00466299 0.008751392 5e-4 -0.004748344 0.008836686 5e-4 -0.004748582 0.008836925 -5e-4 -0.004822731 0.008931636 5e-4 -0.004823148 0.008932173 -5e-4 -0.004885554 0.009035527 -5e-4 -0.004885315 0.00903511 5e-4 -0.004934906 0.009145259 5e-4 -0.004935026 0.009145438 -5e-4 -0.004970788 0.009260356 5e-4 -0.004970967 0.009260952 -5e-4 -0.004992663 0.009379208 -5e-4 -0.004992663 0.009379208 5e-4 + + + + + + + + + + -0.9761871 -0.2169305 0 0.1520573 -0.9883717 0 0.1520573 -0.9883717 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 1.16884e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.84901 -0.5283767 0 -0.9257904 -0.3780374 0 -0.9543975 -0.2985392 0 -0.6257329 -0.7800375 0 -0.4855885 -0.8741875 0 -0.7480252 -0.6636703 0 -0.3316226 -0.9434123 0 -0.1681886 -0.9857548 0 -0.08438402 -0.9964334 0 0.9751317 0.2216264 0 0.9666868 0.2559622 0 0.9823791 0.1868989 0 0.9883732 0.152048 0 0.9909014 0.1345902 0 0.9570001 0.2900879 0 0.9461448 0.3237438 0 0.9403447 0.3402234 0 0 -1 0 0 -1 0 1 5.1521e-4 0 1 0 1.11345e-4 0.9998442 -0.01765561 0 1 0 -1.11345e-4 0.9999999 5.09219e-4 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 0.9889115 0.1485061 0 0.9876874 0.1564405 0 0.9969195 0.07843267 0 0.8090303 0.587767 0 0.8910139 0.4539761 0 0.8306108 0.5568535 0 0.9510608 0.309004 0 0.9560143 0.2933201 0 0.9023097 0.4310883 -3.05192e-5 0.5316439 0.846968 3.05194e-5 0.4539761 0.8910139 3.05193e-5 0.5878015 0.8090053 0 0.7443419 0.6677988 0 0.6437109 0.7652688 3.05195e-5 0.7071068 0.7071068 0 0.2837984 0.958884 3.05192e-5 0.1564108 0.9876922 3.05189e-5 0.309004 0.9510608 0 0.4113112 0.911495 0 0.07843267 0.9969195 0 0.152658 0.9882791 0 0.06790441 0.9976919 0 0.997057 0.07666379 0.6163083 0.787505 0 0.8378868 0.5458441 0 0.8927485 0.4505554 0 0.9161881 0.4007484 0 0.6990348 0.7150877 0 0.6586904 0.7524141 0 0.7731217 0.6342577 0 0.9368384 0.3497627 0 0.9368384 0.3497627 0 -0.9963108 0.08581835 0 -0.9990646 0.04324513 0 -0.9990633 0.04327559 0 -0.9416155 0.3366902 0 -0.9670007 0.2547742 0 -0.9852818 0.170938 0 -0.8702849 0.492549 0 -0.8249403 0.5652199 0 -0.9092627 0.4162228 0 -0.7160978 0.698 0 -0.6537923 0.7566741 0 -0.7733696 0.6339555 0 -0.4396655 0.8981617 0 -0.514949 0.8572209 0 -0.5864574 0.8099802 0 -0.2795827 0.9601216 0 -0.1964507 0.9805138 0 -0.3607107 0.9326778 0 -0.02609395 0.9996595 0 0.05963438 0.9982203 0 -0.1115469 0.9937592 0 0.3119671 0.9500929 0 0.2294085 0.9733303 0 0.1450863 0.9894191 0 0.4697279 0.8828114 0 0.5435512 0.8393761 0 0.3921763 0.9198901 0 0.6133827 0.7897859 0 0.6788997 0.734231 0 0.7393571 0.6733136 0 0.7943544 0.6074547 0 0.8434202 0.5372546 0 0.8862756 0.4631583 0 0.9052313 0.4249194 0 -0.7819901 -0.623291 0 -0.7457401 -0.6662372 0 -0.9439169 -0.3301832 0 -0.9010111 -0.4337964 0 -0.8468511 -0.5318303 0 -0.7819633 -0.6233245 0 -0.9937043 -0.1120359 0 -0.9749509 -0.2224204 0 -0.9937075 -0.1120057 0 -0.9984222 -0.05615454 0 -0.9984204 -0.05618494 0 -0.707107 -0.7071066 0 -0.707107 -0.7071066 0 -0.9748736 -0.2227593 0 -0.9936906 -0.1121564 0 -0.9009222 -0.4339808 0 -0.8466618 -0.5321316 0 -0.9438531 -0.3303654 0 -0.7818831 -0.6234251 0 -0.7457113 -0.6662693 0 -1 0 0 -1 -5.41561e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -5.41562e-7 0 3.05189e-5 0.309004 -0.9510608 -3.05189e-5 0.2853817 -0.958414 -3.05192e-5 0.4110625 -0.9116073 0 0.07843267 -0.9969195 0 0.1558607 -0.987779 0 0.1564108 -0.9876922 0 0.6420677 -0.7666479 0 0.7437205 -0.6684908 3.05195e-5 0.7071068 -0.7071068 3.05193e-5 0.5878015 -0.8090053 3.05194e-5 0.4539761 -0.8910139 -3.05191e-5 0.5295984 -0.8482486 0 0.9510608 -0.309004 0 0.9026917 -0.4302877 0 0.9560058 -0.293348 0 0.8910139 -0.4539761 0 0.8090303 -0.587767 0 0.8311618 -0.5560306 0 0.9888936 -0.1486254 0 0.9876874 -0.1564405 0 0.997043 -0.07684582 0 0.9969195 -0.07843267 0 0.06793481 -0.9976898 0.8655719 0.5007848 -7.4213e-5 0.8723533 0.4888761 2.26396e-6 0.8594916 0.5111501 0 0.8748543 0.4843864 -1.44521e-5 0.8752146 0.4837348 1.61431e-6 0.8654432 0.5010073 4.33636e-7 0.8712601 0.4908216 -1.04787e-5 0.8652339 0.5013685 -4.96214e-6 0.8653305 0.5012019 -2.02175e-6 0.8634088 0.5045052 0 0.8633202 0.5046567 -5.01358e-6 0.8177208 0.5756151 0 0.7944731 0.6072995 0 0.8572209 0.514949 0 0.8399876 0.5426058 0 0.7456675 0.6663184 0 0.7204078 0.6935508 0 0.7704181 0.637539 0 0.7204225 0.6935355 0 0.707534 0.7066794 0 0.8571642 0.5150432 0 0.8679411 0.4966673 -1.96608e-6 0.8672958 0.4977932 1.70372e-5 0.8667323 0.4987738 -7.43036e-5 0.8715066 0.4903839 4.78822e-7 0.8657456 0.5004844 1.708e-5 0.8722475 0.4890647 -1.04648e-5 0.8754811 0.4832525 1.56407e-6 0.8721632 0.4892151 -1.46072e-5 0.8752697 0.4836352 2.24776e-6 0.8720739 0.4893745 1.87202e-6 0.8602439 0.5098827 1.9035e-6 0.9926961 -0.1206421 0 1 0 0 0.8854585 -0.4647185 0 0.9350855 -0.3544224 0 0.9350754 -0.354449 0 0.970991 -0.239116 0 0.7488707 -0.6627162 0 0.6633309 -0.7483264 0 0.8231229 -0.5678635 0 0.4647424 -0.885446 0 0.3547297 -0.9349689 0 0.567989 -0.8230362 0 3.05194e-5 -1 0 0.1208563 -0.99267 0 0.2396693 -0.9708546 0 0.3547195 -0.9349728 0 -0.239116 -0.970991 0 -0.3541151 -0.9352019 0 3.05185e-5 -1 0 -0.120582 -0.9927035 0 -0.5680589 -0.822988 0 -0.6629913 -0.7486271 0 -0.4645976 -0.8855219 0 -0.4646216 -0.8855094 0 -0.8853633 -0.4648997 0 -0.822762 -0.5683861 0 -0.748412 -0.6632341 0 -0.9708777 -0.2395759 0 -0.9926815 -0.1207624 0 -0.9708706 -0.2396047 0 -0.934993 -0.3546662 0 -0.9926961 0.1206421 0 -0.970991 0.239116 0 -0.8231229 0.5678635 0 -0.8854585 0.4647185 0 -0.9350754 0.354449 0 -0.9350855 0.3544224 0 -0.6633309 0.7483264 0 -0.567989 0.8230362 0 -0.7488574 0.6627313 0 -0.7488707 0.6627162 0 -0.3547297 0.9349689 0 -0.2396693 0.9708546 0 -0.4647424 0.885446 0 -0.1208563 0.99267 0 0.120582 0.9927035 0 -3.05185e-5 1 0 0.239116 0.970991 0 0.3541151 0.9352019 0 0.4645976 0.8855219 0 0.5680589 0.822988 0 0.6629913 0.7486271 0 0.748412 0.6632341 0 0.822762 0.5683861 0 0.8853633 0.4648997 0 0.934993 0.3546662 0 0.9708706 0.2396047 0 0.9926815 0.1207624 0 0.4647789 -0.8854268 0 -0.7484272 -0.6632171 0 -3.05194e-5 1 0 0.6630064 0.7486138 0 0.9708777 0.2395759 0 5.96579e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.67744e-7 0 1 0 0 1 0 0 1 -4.73643e-7 0 1 4.71371e-7 0 1 -6.61359e-7 0 1 4.69121e-7 0 1 8.36161e-7 0 1 -1.65382e-7 0 1 0 0 1 0 0 1 -9.41783e-7 0 1 3.31977e-7 0 1 4.71364e-7 0 1 2.85367e-7 0 1 0 0 1 0 0 1 -1.33073e-6 0 1 0 0 1 0 0 1 0 0 1 -2.54763e-6 0 1 0 0 1 -1.38494e-7 0 1 0 0 1 -6.04846e-7 0 1 -6.33985e-7 0 1 0 0 1 -3.20942e-7 0 1 4.12294e-7 0 1 -1.49398e-7 0 1 2.03342e-7 0 1 0 0 1 -7.5338e-7 0 1 0 0 1 1.16232e-6 0 1 4.85611e-7 0 1 6.45171e-7 0 1 -5.72002e-7 0 1 1.29102e-7 0 1 2.10126e-7 0 1 2.98435e-7 0 1 0 0 1 -2.63015e-7 0 1 -3.98877e-7 0 1 0 0 1 -6.96969e-7 0 1 -2.49682e-7 0 1 -1.38494e-7 0 1 0 0 1 -1.21133e-7 0 1 1.33073e-6 0 1 -2.38227e-7 0 1 0 0 1 -2.97181e-7 0 1 0 0 1 6.35273e-7 0 1 -2.22759e-7 0 1 4.58945e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.91421e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 4.20656e-7 0 1 -4.4755e-7 0 1 1.65372e-7 0 1 0 0 1 0 0 1 1.65176e-7 0 1 -2.37152e-7 0 1 0 0 1 1.84414e-7 0 1 0 0 1 0 0 1 2.74561e-7 0 1 4.20636e-7 0 1 0 0 1 0 0 1 3.31841e-7 0 1 -3.80845e-7 0 1 -1.22725e-7 0 1 0 0 1 -4.38375e-7 0 1 5.73681e-7 0 1 -2.18309e-7 0 1 0 0 1 -2.20393e-7 0 1 0 0 1 0 0 1 0 0 1 2.42266e-7 0 1 -1.33073e-6 0 1 3.57341e-7 0 1 3.36805e-7 0 1 1.38494e-7 0 1 2.0715e-7 0 1 0 0 1 6.04128e-7 0 1 9.56463e-7 0 1 -6.35274e-7 0 1 -2.67707e-7 0 1 0 0 1 3.04599e-7 0 1 0 0 1 0 0 -1 0 0 -1 -3.0194e-6 0 -1 -9.41783e-7 0 -1 0 0 -1 0 0 -1 -4.73643e-7 0 -1 4.69121e-7 0 -1 4.71371e-7 0 -1 -1.65382e-7 0 -1 -5.86439e-7 0 -1 0 0 -1 9.38847e-7 0 -1 2.07485e-7 0 -1 0 0 -1 1.23405e-7 0 -1 2.34991e-7 0 -1 2.35681e-7 0 -1 0 0 -1 2.85367e-7 0 -1 6.04e-7 0 -1 -1.33073e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.60528e-7 0 -1 0 0 -1 6.2238e-7 0 -1 -5.30895e-7 0 -1 -3.69968e-7 0 -1 -2.2098e-7 0 -1 2.12091e-7 0 -1 -5.007e-7 0 -1 -4.19401e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -3.71217e-7 0 -1 3.44939e-7 0 -1 3.33323e-7 0 -1 6.33996e-7 0 -1 -3.16501e-7 0 -1 1.22342e-6 0 -1 -2.67268e-7 0 -1 0 0 -1 3.04593e-7 0 -1 0 0 -1 0 0 -1 -1.35049e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.84129e-7 0 -1 -1.29054e-6 0 -1 -9.27468e-7 0 -1 -1.41351e-6 0 -1 1.5372e-6 0 -1 -7.5338e-7 0 -1 0 0 -1 1.16232e-6 0 -1 4.85611e-7 0 -1 6.45171e-7 0 -1 -5.72002e-7 0 -1 1.29102e-7 0 -1 2.10126e-7 0 -1 2.98435e-7 0 -1 0 0 -1 -6.04846e-7 0 -1 -2.63015e-7 0 -1 -3.98877e-7 0 -1 -6.96969e-7 0 -1 -2.49682e-7 0 -1 -1.38494e-7 0 -1 0 0 -1 -1.21133e-7 0 -1 1.33073e-6 0 -1 -2.38227e-7 0 -1 0 0 -1 -2.97181e-7 0 -1 0 0 -1 6.35273e-7 0 -1 -2.22759e-7 0 -1 4.58945e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.91421e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 4.20656e-7 0 -1 -4.4755e-7 0 -1 1.65372e-7 0 -1 0 0 -1 0 0 -1 1.65176e-7 0 -1 -2.37152e-7 0 -1 0 0 -1 1.84414e-7 0 -1 0.9926998 -0.1206121 0 0.8854776 -0.464682 0 0.9349829 -0.3546929 0 0.9709751 -0.2391806 0 0.9926815 -0.1207624 0 0.9708706 -0.2396047 3.0519e-5 0.7484272 -0.6632171 3.05194e-5 0.7488574 -0.6627313 0 0.8853952 -0.4648393 0 0.8228004 -0.5683305 3.05193e-5 0.8230987 -0.5678985 0 0.4646216 -0.8855094 0 0.3547195 -0.9349728 -6.10375e-5 0.567989 -0.8230362 3.0519e-5 0.6629913 -0.7486271 6.10377e-5 0.5680239 -0.8230121 0 0.120582 -0.9927035 3.05194e-5 0.2391448 -0.9709839 3.05187e-5 0.2396335 -0.9708635 0 0.3541151 -0.9352019 0 -0.2396335 -0.9708635 0 -0.2391448 -0.9709839 -3.05187e-5 -3.05185e-5 -1 0 -0.1208563 -0.99267 0 -0.120582 -0.9927035 -3.05194e-5 -0.5680239 -0.8230121 -3.05192e-5 -0.567989 -0.8230362 -3.0519e-5 -0.6629913 -0.7486271 -6.10377e-5 -0.3547195 -0.9349728 6.10375e-5 -0.4647789 -0.8854268 0 -0.8853826 -0.4648633 0 -0.8228004 -0.5683305 -3.05193e-5 -0.8230987 -0.5678985 0 -0.7488574 -0.6627313 0 -0.7484272 -0.6632171 -3.05194e-5 -0.6633309 -0.7483264 0 -0.9709751 -0.2391806 0 -0.9708706 -0.2396047 -3.0519e-5 -0.8854776 -0.464682 0 -0.9350754 -0.354449 0 -0.9349829 -0.3546929 0 -0.9926998 0.1206121 0 -0.9926736 0.1208263 0 -0.9709751 0.2391806 0 -0.9926998 -0.1206121 0 -0.8231995 0.5677523 -3.05194e-5 -0.8855411 0.4645612 0 -0.8853508 0.4649236 0 -0.9349829 0.3546929 0 -0.9350513 0.3545125 0 -0.9708706 0.2396047 3.0519e-5 -0.6630064 0.7486138 0 -0.5683305 0.8228004 -3.05193e-5 -0.6632341 0.748412 0 -0.8227763 0.5683655 3.05195e-5 -0.7484272 0.6632171 0 -0.7486271 0.6629913 0 -0.3547195 0.9349728 0 -0.3545125 0.9350513 0 -0.2396047 0.9708706 -3.0519e-5 -0.4649236 0.8853508 0 -0.5677729 0.8231853 3.05189e-5 -0.4645612 0.8855411 0 -0.1203377 0.9927331 0 -0.1207962 0.9926773 0 -0.238965 0.9710283 3.05192e-5 0.1203377 0.9927331 0 6.10389e-5 1 0 0.1208263 0.9926736 0 -6.1037e-5 1 0 0.2396047 0.9708706 3.0519e-5 0.238965 0.9710283 -3.05192e-5 0.3547195 0.9349728 0 0.3544859 0.9350615 0 0.4645612 0.8855411 0 0.4649236 0.8853508 0 0.5683305 0.8228004 3.05193e-5 0.5677729 0.8231853 -3.05189e-5 0.6632171 0.7484272 0 0.7484272 0.6632171 0 0.7486271 0.6629913 0 0.8231995 0.5677523 3.05194e-5 0.8227763 0.5683655 -3.05195e-5 0.8855411 0.4645612 0 0.8853508 0.4649236 0 0.9349829 0.3546929 0 0.9350513 0.3545125 0 0.9709839 0.2391448 0 0.9708706 0.2396047 -3.0519e-5 0.9926998 0.1206121 0 0.99267 0.1208563 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.004964292 -0.001511335 -0.004751265 -0.009439647 -0.001511335 -0.001792192 0.004478335 -0.001511335 -2.77713e-4 -0.008952617 -0.001511335 -0.006265759 -0.008952617 4.88657e-4 -0.006265759 0.004964292 -0.001511335 -0.004751265 0.004964292 4.88657e-4 -0.004751265 -0.008952617 -0.001511335 -0.006265759 0.005073308 4.88657e-4 -0.00574541 -0.008952617 4.88657e-4 -0.006265759 0.004964292 4.88657e-4 -0.004751265 -0.008844614 4.88657e-4 -0.007259905 0.005073308 4.88657e-4 -0.00574541 -0.008844614 -0.001511335 -0.007259905 -0.008844614 4.88657e-4 -0.007259905 0.005073308 -0.001511335 -0.00574541 -0.008844614 -0.001511335 -0.007259905 0.005073308 -0.001511335 -0.00574541 0.005559325 -0.001511335 -0.01021897 -0.008357644 -0.001511335 -0.01173347 -0.008357644 -0.001511335 -0.01173347 0.005559325 -0.001694858 -0.01021897 -0.001367628 -0.002211272 -0.01097285 -0.008357644 -0.002696812 -0.01173347 0.005559325 -0.001511335 -0.01021897 -0.008357644 -0.001511335 -0.01173347 -0.008357644 -0.002696812 -0.01173347 -0.008844614 -0.001511335 -0.007259905 -0.009439647 -0.002822101 -0.001792192 -0.008952617 -0.001511335 -0.006265759 -0.008952617 4.88657e-4 -0.006265759 -0.008844614 4.88657e-4 -0.007259905 -0.009439647 -0.001511335 -0.001792192 -0.002448618 -0.002351522 -0.001031398 -0.009439647 -0.001511335 -0.001792192 -0.009439647 -0.002822101 -0.001792192 0.004478335 -0.001511335 -2.77713e-4 0.004478335 -0.001849651 -2.77713e-4 0.004478335 -0.001849651 -2.77713e-4 0.005073308 -0.001511335 -0.00574541 0.004964292 -0.001511335 -0.004751265 0.004478335 -0.001511335 -2.77713e-4 0.005559325 -0.001694858 -0.01021897 0.005073308 4.88657e-4 -0.00574541 0.004964292 4.88657e-4 -0.004751265 0.005559325 -0.001511335 -0.01021897 0.03381931 6.25399e-5 0.08415514 0.0184803 1.04533e-4 -0.06505787 0.03381931 -8.57044e-5 0.08415514 0.0184803 -1.27115e-4 -0.06505787 0.0210793 -0.001171767 0.08328413 0.0210793 0.001148641 0.08328413 0.02745133 6.26337e-4 0.08372014 0.008326292 0.002068817 0.08241313 -1.00657e-4 7.01903e-4 0.08183616 0.00194633 0.002466678 0.08197617 0.02745133 -6.49503e-4 0.08372014 0.03381931 6.25399e-5 0.08415514 0.01470428 -0.001652598 0.08284914 0.03381931 -8.57044e-5 0.08415514 0.008326292 -0.002091884 0.08241313 -1.00657e-4 -7.24974e-4 0.08183616 0.01470428 0.001629471 0.08284914 0.001945316 -0.002489745 0.08197617 0.001945316 -0.002489745 0.08197617 -0.02625584 -0.001676619 -0.06992608 -1.00657e-4 -7.24974e-4 0.08183616 -0.02418464 -0.00344032 -0.06970071 0.007928311 -0.001057207 -0.06620609 -0.002699613 -0.001919448 -0.06736266 0.0210793 -0.001171767 0.08328413 -0.009439647 -0.002822101 -0.001792192 0.001945316 -0.002489745 0.08197617 0.008326292 -0.002091884 0.08241313 0.02745133 -6.49503e-4 0.08372014 0.03381931 -8.57044e-5 0.08415514 0.0184803 -1.27115e-4 -0.06505787 0.004478335 -0.001849651 -2.77713e-4 0.01470428 -0.001652598 0.08284914 -0.002448618 -0.002351522 -0.001031398 0.005559325 -0.001694858 -0.01021897 -0.001367628 -0.002211272 -0.01097285 -0.02418464 -0.00344032 -0.06970071 -0.01340365 -0.002713799 -0.06852751 -0.008357644 -0.002696812 -0.01173347 -0.002698659 0.001896798 -0.0673626 0.0210793 0.001148641 0.08328413 0.01470428 0.001629471 0.08284914 0.02745133 6.26337e-4 0.08372014 0.007929325 0.001034557 -0.06620609 0.0184803 1.04533e-4 -0.06505787 0.03381931 6.25399e-5 0.08415514 0.008326292 0.002068817 0.08241313 -0.01340365 0.002691149 -0.06852751 -0.02418464 0.00341773 -0.06970071 0.00194633 0.002466678 0.08197617 -0.02625584 0.001653969 -0.06992608 0.00194633 0.002466678 0.08197617 -1.00657e-4 7.01903e-4 0.08183616 -0.02418464 0.00341773 -0.06970071 -0.02625584 -0.001676619 -0.06992608 -1.00657e-4 7.01903e-4 0.08183616 -1.00657e-4 -7.24974e-4 0.08183616 -0.02625584 0.001653969 -0.06992608 -0.02213162 -7.47185e-4 -0.06556308 -0.02200365 -8.48615e-4 -0.06558519 -0.02186065 -9.27194e-4 -0.06560987 -0.02186065 9.04454e-4 -0.06560981 -0.02200365 8.25847e-4 -0.06558519 -0.02049261 -1.7596e-4 -0.0658456 -0.02170664 -9.80778e-4 -0.06563639 -0.02224266 -6.2567e-4 -0.065544 -0.02154564 -0.001007854 -0.06566411 -0.02233165 -4.87386e-4 -0.06552869 -0.02239662 -3.36106e-4 -0.06551736 -0.02138262 -0.001007795 -0.06569206 -0.02243661 -1.7596e-4 -0.06551051 -0.02122265 -9.80611e-4 -0.06571978 -0.02245062 -1.13193e-5 -0.06550818 -0.02106863 -9.26933e-4 -0.0657463 -0.02092564 -8.48287e-4 -0.06577098 -0.02243661 1.53275e-4 -0.06551051 -0.02059763 -4.87065e-4 -0.06582736 -0.02224266 6.02893e-4 -0.065544 -0.02068662 -6.25309e-4 -0.06581211 -0.02233165 4.64628e-4 -0.06552869 -0.02239662 3.1338e-4 -0.06551736 -0.02079665 -7.46822e-4 -0.06579309 -0.02047961 -1.13193e-5 -0.06584787 -0.02213263 7.24404e-4 -0.06556296 -0.0205326 -3.35865e-4 -0.06583869 -0.0205326 3.1338e-4 -0.06583869 -0.02059763 4.64628e-4 -0.06582736 -0.02138364 9.85265e-4 -0.06569206 -0.02049261 1.53275e-4 -0.0658456 -0.02154666 9.85265e-4 -0.06566399 -0.02170664 9.5808e-4 -0.06563639 -0.02106863 9.04454e-4 -0.0657463 -0.02079761 7.24404e-4 -0.06579309 -0.02092564 8.25847e-4 -0.06577086 -0.02068662 6.02893e-4 -0.06581211 -0.02122265 9.58081e-4 -0.06571966 -0.002698659 0.001896798 -0.0673626 -0.02109962 1.53275e-4 -0.0693649 -0.02108561 -1.13193e-5 -0.06936341 -0.02625584 -0.001676619 -0.06992608 -0.02418464 -0.00344032 -0.06970071 -0.01340365 -0.002713799 -0.06852751 -0.01340365 0.002691149 -0.06852751 -0.02155363 8.25847e-4 -0.06941437 0.0184803 -1.27115e-4 -0.06505787 0.0184803 1.04533e-4 -0.06505787 0.007929325 0.001034557 -0.06620609 0.007928311 -0.001057207 -0.06620609 -0.002699613 -0.001919448 -0.06736266 -0.02141863 7.24404e-4 -0.06939971 -0.02625584 0.001653969 -0.06992608 -0.02220463 9.85265e-4 -0.06948518 -0.02203363 9.85265e-4 -0.06946659 -0.02418464 0.00341773 -0.06970071 -0.02315366 -1.13193e-5 -0.06958848 -0.02109962 -1.75914e-4 -0.0693649 -0.02309763 3.1338e-4 -0.0695824 -0.02313965 1.53275e-4 -0.06958687 -0.02170366 9.04454e-4 -0.0694307 -0.02293562 6.02893e-4 -0.0695647 -0.02302861 4.64628e-4 -0.06957489 -0.0218656 9.58081e-4 -0.06944829 -0.02268463 8.25847e-4 -0.06953752 -0.02281963 7.24404e-4 -0.06955206 -0.02237361 9.58081e-4 -0.0695036 -0.0225346 9.04454e-4 -0.06952106 -0.02130365 6.02893e-4 -0.06938707 -0.02120965 4.64628e-4 -0.069377 -0.02114164 3.1338e-4 -0.06936949 -0.02203363 -0.001007854 -0.06946659 -0.02114164 -3.36019e-4 -0.06936949 -0.02120965 -4.87267e-4 -0.069377 -0.02130365 -6.25532e-4 -0.06938707 -0.02141863 -7.47044e-4 -0.06939971 -0.02155363 -8.48486e-4 -0.06941437 -0.0218656 -9.8072e-4 -0.06944829 -0.02170366 -9.27093e-4 -0.0694307 -0.02237361 -9.8072e-4 -0.0695036 -0.02220463 -0.001007854 -0.06948518 -0.02268463 -8.48486e-4 -0.06953752 -0.0225346 -9.27093e-4 -0.06952106 -0.02293562 -6.25532e-4 -0.0695647 -0.02281963 -7.47044e-4 -0.06955206 -0.02309763 -3.36019e-4 -0.0695824 -0.02302861 -4.87267e-4 -0.06957489 -0.02313965 -1.75914e-4 -0.06958687 -0.02243661 1.53275e-4 -0.06551051 -0.02315366 -1.13193e-5 -0.06958848 -0.02245062 -1.13193e-5 -0.06550818 -0.02224266 6.02893e-4 -0.065544 -0.02302861 4.64628e-4 -0.06957489 -0.02233165 4.64628e-4 -0.06552869 -0.02239662 3.1338e-4 -0.06551736 -0.02309763 3.1338e-4 -0.0695824 -0.02313965 1.53275e-4 -0.06958687 -0.02268463 8.25847e-4 -0.06953752 -0.02200365 8.25847e-4 -0.06558519 -0.02186065 9.04454e-4 -0.06560981 -0.02293562 6.02893e-4 -0.0695647 -0.02213263 7.24404e-4 -0.06556296 -0.02281963 7.24404e-4 -0.06955206 -0.02154666 9.85265e-4 -0.06566399 -0.02138364 9.85265e-4 -0.06569206 -0.02220463 9.85265e-4 -0.06948518 -0.02170664 9.5808e-4 -0.06563639 -0.02237361 9.58081e-4 -0.0695036 -0.0225346 9.04454e-4 -0.06952106 -0.02092564 8.25847e-4 -0.06577086 -0.02170366 9.04454e-4 -0.0694307 -0.02106863 9.04454e-4 -0.0657463 -0.0218656 9.58081e-4 -0.06944829 -0.02203363 9.85265e-4 -0.06946659 -0.02122265 9.58081e-4 -0.06571966 -0.02130365 6.02893e-4 -0.06938707 -0.02068662 6.02893e-4 -0.06581211 -0.02059763 4.64628e-4 -0.06582736 -0.02155363 8.25847e-4 -0.06941437 -0.02079761 7.24404e-4 -0.06579309 -0.02141863 7.24404e-4 -0.06939971 -0.02049261 1.53275e-4 -0.0658456 -0.02047961 -1.13193e-5 -0.06584787 -0.02109962 1.53275e-4 -0.0693649 -0.0205326 3.1338e-4 -0.06583869 -0.02114164 3.1338e-4 -0.06936949 -0.02120965 4.64628e-4 -0.069377 -0.02059763 -4.87065e-4 -0.06582736 -0.02114164 -3.36019e-4 -0.06936949 -0.0205326 -3.35865e-4 -0.06583869 -0.02109962 -1.75914e-4 -0.0693649 -0.02108561 -1.13193e-5 -0.06936341 -0.02049261 -1.7596e-4 -0.0658456 -0.02141863 -7.47044e-4 -0.06939971 -0.02079665 -7.46822e-4 -0.06579309 -0.02092564 -8.48287e-4 -0.06577098 -0.02120965 -4.87267e-4 -0.069377 -0.02068662 -6.25309e-4 -0.06581211 -0.02130365 -6.25532e-4 -0.06938707 -0.02122265 -9.80611e-4 -0.06571978 -0.02138262 -0.001007795 -0.06569206 -0.0218656 -9.8072e-4 -0.06944829 -0.02106863 -9.26933e-4 -0.0657463 -0.02170366 -9.27093e-4 -0.0694307 -0.02155363 -8.48486e-4 -0.06941437 -0.02154564 -0.001007854 -0.06566411 -0.02170664 -9.80778e-4 -0.06563639 -0.02220463 -0.001007854 -0.06948518 -0.02203363 -0.001007854 -0.06946659 -0.02237361 -9.8072e-4 -0.0695036 -0.02186065 -9.27194e-4 -0.06560987 -0.02200365 -8.48615e-4 -0.06558519 -0.0225346 -9.27093e-4 -0.06952106 -0.02213162 -7.47185e-4 -0.06556308 -0.02268463 -8.48486e-4 -0.06953752 -0.02281963 -7.47044e-4 -0.06955206 -0.02224266 -6.2567e-4 -0.065544 -0.02233165 -4.87386e-4 -0.06552869 -0.02293562 -6.25532e-4 -0.0695647 -0.02239662 -3.36106e-4 -0.06551736 -0.02302861 -4.87267e-4 -0.06957489 -0.02309763 -3.36019e-4 -0.0695824 -0.02243661 -1.7596e-4 -0.06551051 -0.02313965 -1.75914e-4 -0.06958687 + + + + + + + + + + 0 -1 0 0 -1 0 0.1081851 0 -0.9941308 0.1081852 0 -0.9941308 0 -1 0 -0.1081774 0 0.9941317 -0.1081776 0 0.9941317 0 -1 0 0 -1 0 -0.1081869 -1.29321e-4 0.9941306 -0.1081741 0 0.9941321 -0.108185 0 0.9941309 0.9941268 0 0.1082215 0.9941291 7.79236e-5 0.1082012 0.9941498 -7.36912e-4 0.1080089 0.9941499 0 0.1080089 0.99415 0 0.108009 0.9941269 0 0.1082214 0.108186 0 -0.9941307 0.1081678 0 -0.9941327 0.108177 -7.61686e-5 -0.9941318 -0.9939545 -0.01329302 -0.1089857 -0.9941506 0 -0.1080023 -0.9941413 0.001777291 -0.1080741 -0.9940423 0 -0.1089955 -0.9940422 0 -0.1089956 -0.9941507 0 -0.1080023 0.9947577 0 -0.1022604 0.9947577 0 -0.1022604 -0.06826639 0 0.9976671 -0.06832802 1.11253e-4 0.997663 -0.06815034 0 0.9976751 -0.06826585 0 0.9976672 -0.06807529 0 0.9976802 -0.06815016 0 0.9976751 -0.06823438 4.64986e-4 0.9976692 -0.06807535 0 0.9976803 -0.06831693 -6.29656e-5 0.9976637 -0.06826305 0 0.9976674 -0.06826263 0 0.9976674 -0.06823331 -4.64983e-4 0.9976693 -0.653237 -0.7480167 0.1172716 -0.6512295 -0.7498247 0.1168892 0.08468919 -0.9963726 -0.008331537 0.07941055 -0.9968136 -0.007538199 0.07766991 -0.9969521 -0.007354974 0.06454718 -0.9979027 -0.004913508 0.06634789 -0.9977827 -0.005279719 0.06253343 -0.9980327 -0.00451678 0.08591139 -0.996267 -0.008453786 0.08877921 -0.996012 -0.008850455 0.08874899 -0.996015 -0.008819937 0.07287859 -0.9973199 -0.006469905 0.07531994 -0.9971355 -0.006927728 0.06988799 -0.9975368 -0.006012141 0.0766642 -0.9970314 -0.00714147 0.07300221 -0.9973106 -0.006500601 0.06762993 -0.9976944 -0.005676507 0.06993436 -0.9975341 -0.00591433 0.07068175 -0.9974797 -0.006195306 0.07682073 -0.9970192 -0.007173597 0.07732743 -0.9969794 -0.007257938 0.06645005 -0.9977754 -0.00534451 0.06778186 -0.9976848 -0.005554378 0.07763957 0.9969547 -0.007324457 0.07287853 0.9973196 -0.006500422 0.07941055 0.9968136 -0.007538199 0.08591139 0.996267 -0.008453786 0.08468925 0.9963729 -0.008301019 0.08877921 0.9960123 -0.008819937 0.08874899 0.996015 -0.008819937 0.07065141 0.9974822 -0.006134271 0.06637829 0.9977806 -0.005279719 0.06766033 0.9976927 -0.005615472 0.06253343 0.9980327 -0.00451678 -0.6530588 0.7481765 0.117244 -0.6512315 0.749822 0.1168959 -0.9854718 0 0.1698393 -0.1700992 -2.77117e-4 -0.9854269 -0.1696572 2.46277e-4 -0.9855031 -0.1694387 9.3212e-4 -0.9855403 -0.1707752 -0.001314699 -0.9853091 -0.1696266 4.0886e-4 -0.9855083 -0.1700715 -5.69154e-4 -0.9854316 -0.1691776 9.58842e-4 -0.9855852 -0.1697909 5.4771e-5 -0.9854801 -0.1692433 7.73186e-4 -0.985574 -0.1703736 -7.03238e-4 -0.9853793 -0.1704465 -8.58436e-4 -0.9853666 -0.170072 -2.97544e-4 -0.9854317 -0.1696121 2.33258e-4 -0.9855109 -0.1697432 1.49188e-4 -0.9854884 -0.1700995 -5.18877e-4 -0.9854269 -0.1700986 -3.4308e-4 -0.9854271 -0.1697395 1.34857e-4 -0.985489 -0.1689922 9.64496e-4 -0.9856169 -0.1699711 -1.82136e-4 -0.9854491 -0.1662682 0.005725502 -0.986064 -0.1705417 -0.001035869 -0.9853499 -0.1701117 -4.99569e-4 -0.9854247 -0.1726045 -0.003529548 -0.984985 -0.1699004 -1.92325e-4 -0.9854612 -0.1686731 0.001471102 -0.985671 -0.1695021 3.88158e-4 -0.9855298 -0.1697393 5.95437e-5 -0.985489 -0.1698853 -3.50003e-5 -0.9854639 -0.1701904 -3.021e-4 -0.9854112 -0.1699574 -2.41035e-4 -0.9854514 -0.1700694 -4.83225e-4 -0.985432 -0.1695588 1.82333e-4 -0.9855201 -0.1693353 6.86447e-4 -0.9855583 -0.1700282 -2.46287e-4 -0.9854392 -0.1693718 6.20925e-4 -0.9855521 -0.1699568 -1.58921e-5 -0.9854515 0.1081633 1.5458e-4 -0.9941332 0.1081828 -6.34514e-6 -0.994131 0.1081812 1.08049e-5 -0.9941312 0.1081917 0 -0.9941301 0.1081752 -5.16279e-5 -0.9941319 0.108178 -5.16967e-5 -0.9941316 0.1081879 -3.28816e-6 -0.9941306 0.1081913 -1.23057e-5 -0.9941301 0.1081632 -4.84284e-4 -0.9941331 0.1081825 6.3451e-6 -0.9941312 0.1081872 0 -0.9941306 0.1081622 -1.54003e-4 -0.9941333 0.1079962 -3.92597e-4 -0.9941512 0.1084443 4.5466e-4 -0.9941025 0.108133 1.84675e-4 -0.9941365 0.1083359 4.09182e-4 -0.9941143 0.1081802 -3.7959e-5 -0.9941313 0.1082618 -3.99424e-4 -0.9941223 0.1080263 -7.05681e-4 -0.9941478 0.1081511 -1.24342e-4 -0.9941346 0.1081709 -2.48461e-4 -0.9941323 0.1083413 6.71635e-4 -0.9941136 0.108164 1.84614e-4 -0.9941331 0.108186 -3.14997e-5 -0.9941307 0.1080834 3.3973e-4 -0.9941418 0.1081091 9.11291e-4 -0.9941387 0.1082201 -7.12962e-4 -0.9941268 0.1081984 -1.62684e-4 -0.9941294 0.1082307 -6.52879e-4 -0.9941256 0.1081772 -3.28454e-6 -0.9941317 0.1081869 3.14998e-5 -0.9941307 0.1082395 6.52504e-4 -0.9941247 0.108184 1.62913e-4 -0.9941309 0.108224 7.11609e-4 -0.9941263 0.1081113 -9.11578e-4 -0.9941385 0.1081815 -6.83904e-6 -0.9941312 0.1081839 1.05483e-5 -0.994131 0.108044 -3.3973e-4 -0.9941461 0.1081642 -1.84245e-4 -0.9941331 0.1082771 3.99423e-4 -0.9941207 0.1081685 -1.86386e-4 -0.9941326 0.1081646 4.8429e-4 -0.9941329 0.1083502 -6.69821e-4 -0.9941126 0.1081613 2.46168e-4 -0.9941334 0.108188 1.23911e-4 -0.9941305 0.1080047 7.04139e-4 -0.9941502 0.1081616 3.80583e-5 -0.9941334 0.1083198 -4.08625e-4 -0.9941161 0.108458 -4.53828e-4 -0.9941009 0.1080185 3.93903e-4 -0.9941489 0.9717411 -0.1663313 -0.167491 0.9854665 -6.10385e-5 -0.1698701 0.9854665 -3.05192e-5 -0.1698701 0.77805 -0.613736 -0.1340392 0.8672019 -0.4750002 -0.1494523 0.8699696 -0.4697762 -0.1498779 0.9323529 -0.3238362 -0.1607736 0.9724413 -0.1619667 -0.1677044 0.9332752 -0.3211224 -0.1608663 0.549074 -0.8304016 -0.09461003 0.3959832 -0.9157209 -0.06820982 0.5383235 -0.8376226 -0.09271651 0.783596 -0.6064285 -0.134989 0.6745352 -0.7290425 -0.1161866 0.6670576 -0.7360919 -0.1149047 0.08163791 -0.9965628 -0.01406913 0.0954343 -0.9953004 -0.01641947 -0.08115047 -0.9966039 0.01397776 0.2421377 -0.9693446 -0.04171943 0.4087426 -0.9099275 -0.07043808 0.2559338 -0.9656879 -0.04410016 -0.5398235 -0.8366227 0.09302246 -0.3959825 -0.915719 0.06824022 -0.3834715 -0.9211862 0.06607365 -0.2282258 -0.9728132 0.03933978 -0.2416503 -0.9694702 0.04162806 -0.06717282 -0.9976744 0.01156675 -0.772403 -0.6209987 0.1332455 -0.8671659 -0.4750277 0.1495734 -0.7767682 -0.6153839 0.1339171 -0.5288701 -0.8437993 0.09110027 -0.6601219 -0.7424921 0.1137741 -0.6667748 -0.7363577 0.1148422 -0.9722077 -0.1633978 0.1676704 -0.9716421 -0.1668794 0.1675202 -0.9854614 -3.05191e-5 0.1698997 -0.9323621 -0.3238089 0.1607752 -0.8633326 -0.4821759 0.1488736 -0.9310313 -0.3277196 0.1605637 -0.8671612 0.4750556 0.1495116 -0.9322857 0.3240278 0.1607778 -0.9310265 0.3277484 0.1605323 -0.9716271 0.1669073 0.1675787 -0.9721869 0.1635825 0.167611 -0.660169 0.7424498 0.113777 -0.5384838 0.8375126 0.09277886 -0.667144 0.7359946 0.1150258 -0.8633619 0.4821141 0.1489039 -0.7723554 0.6210706 0.1331868 -0.7779573 0.6138267 0.1341611 -0.2424103 0.9692751 0.04174959 -0.228219 0.9728149 0.03933858 -0.08197385 0.9965348 0.01409971 -0.3962326 0.9156107 0.06824123 -0.5288345 0.8438218 0.09109938 -0.3834975 0.9211754 0.06607288 0.08078426 0.9966346 -0.01391673 0.09543424 0.9952998 -0.01644992 0.2413489 0.9695464 -0.0415982 -0.06720322 0.9976723 0.01156675 0.2559056 0.9656967 -0.04407006 0.3958325 0.9157861 -0.06821012 0.5397695 0.8366641 -0.09296268 0.4087688 0.9099181 -0.07040685 0.5490937 0.8303853 -0.0946387 0.6667532 0.7363675 -0.1149048 0.6745621 0.729008 -0.1162469 0.776718 0.6154537 -0.1338884 0.8672711 0.4748826 -0.1494232 0.7835552 0.6064816 -0.1349873 0.8700064 0.4696881 -0.14994 0.9323667 0.323841 -0.1606844 0.9332529 0.3211557 -0.1609288 0.9717311 0.1663296 -0.1675503 0.9724483 0.1620239 -0.1676087 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + -0.9601456 -0.05477498 -0.2740819 0.007225291 0.2747378 -0.004677266 -0.9615078 -0.007263926 0.05138463 -0.9984879 0.0195396 -0.00190423 0 0 0 1 + + + + + + + + + + -0.9854742 -0.01500859 0.1691611 5.08577e-5 0.1691091 0.004677443 0.985586 7.78201e-4 -0.0155835 0.9998766 -0.002071409 -3.76854e-5 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_tail.dae b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_tail.dae new file mode 100644 index 00000000..7e34de1a --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_tail.dae @@ -0,0 +1,89 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-04T12:03:10 + 2023-07-04T12:03:10 + + Z_UP + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + + + + + + + 0.08226525 4.95108e-4 -0.01223278 0.123 0.00789982 -0.004828035 0.09605729 7.29759e-4 -0.01199817 0.123 0.001535832 -0.01119196 0.109531 0.001092731 -0.01163518 0.07598859 3.45395e-4 -0.01238244 0.08193796 4.9169e-4 -0.01223617 0.0816062 4.36688e-4 -0.01229119 0.08257967 4.46923e-4 -0.012281 0.06479138 4.53538e-4 -0.01227438 0.05921179 6.52974e-4 -0.01207488 0.05364477 9.4932e-4 -0.01177859 0.04809057 0.001342535 -0.01138526 0.07038366 3.51011e-4 -0.0123769 0.04254889 0.001832723 -0.01089519 0.03701996 0.002419769 -0.01030808 0.03150355 0.003103792 -0.009624063 0.02599996 0.003884673 -0.008843183 0.02599996 0.009541511 -0.003186345 0.123 0.001535832 -0.01119196 0.123 0.001535832 0.001535832 0.123 -0.004828035 -0.004828035 0.123 0.00789982 -0.004828035 0.123 0.00789982 -0.004828035 0.02599996 0.003177583 0.003177583 0.123 0.001535832 0.001535832 0.02599996 0.009541511 -0.003186345 0.02599996 0.003884673 -0.008843183 0.02599996 0.003177583 0.003177583 0.02599996 0.009541511 -0.003186345 0.02599996 -0.002479314 -0.002479314 0.07270276 -0.01568585 0.003790259 0.06763356 -0.0158149 0.004027724 0.06940633 -0.005920052 -0.005920052 0.08285719 -0.01527398 0.003445982 0.07777726 -0.01550555 0.003596365 0.08120369 -0.005931198 -0.005931198 0.0755304 -0.005957067 -0.005957067 0.07046556 0 -0.01186239 0.07598859 3.45395e-4 -0.01238244 0.0755304 -0.005957067 -0.005957067 0.06995576 0 -0.01185148 0.06889736 -0.005912601 -0.005912601 0.06606036 -0.005867898 -0.005867898 0.04254889 0.001832723 -0.01089519 0.04809057 0.001342535 -0.01138526 0.04638159 -0.004930853 -0.004930853 0.07038366 3.51011e-4 -0.0123769 0.05921179 6.52974e-4 -0.01207488 0.06479138 4.53538e-4 -0.01227438 0.06322497 -0.0058012 -0.0058012 0.05364477 9.4932e-4 -0.01177859 0.05755895 -0.005601882 -0.005601882 0.05472844 -0.005469202 -0.005469202 0.06039118 -0.005712509 -0.005712509 0.04913818 -0.005136549 -0.005136549 0.05189955 -0.005314588 -0.005314588 0.04088276 -0.004436671 -0.004436671 0.03701996 0.002419769 -0.01030808 0.04362988 -0.004697561 -0.004697561 0.03814059 -0.004148244 -0.004148244 0.03508955 -0.003790676 -0.003790676 0.03150355 0.003103792 -0.009624063 0.03204917 -0.003393292 -0.003393292 0.02901929 -0.002956151 -0.002956151 0.02599996 -0.002479314 -0.002479314 0.02599996 0.003884673 -0.008843183 0.08081007 -3.61046e-5 -0.01183295 0.08102297 1.56754e-4 -0.01202219 0.0806396 -2.6004e-4 -0.01161199 0.08130007 3.24464e-4 -0.01218479 0.0816062 4.36688e-4 -0.01229119 0.08051687 -4.97558e-4 -0.0113765 0.0804392 -7.37688e-4 -0.01113748 0.08039671 -9.94467e-4 -0.01088148 0.08039116 -0.00122863 -0.01064729 0.08120369 -0.005931198 -0.005931198 0.08042007 -0.00149995 -0.01037555 0.06940633 -0.005920112 -0.005920112 0.1175 4.93169e-4 0.187444 0.08257967 4.46923e-4 -0.012281 0.11782 4.38801e-4 0.187388 0.08292835 3.41142e-4 -0.01216715 0.118128 3.31547e-4 0.187333 0.118414 1.74333e-4 0.187283 0.08325839 1.84333e-4 -0.01200246 0.08354598 -3.50795e-6 -0.0118075 0.118671 -2.85522e-5 0.187238 0.08379757 -2.19936e-4 -0.01158469 0.118891 -2.71575e-4 0.1871989 0.119069 -5.48105e-4 0.187167 0.08401006 -4.52826e-4 -0.01134616 0.0841853 -6.99527e-4 -0.01109474 0.1192 -8.50601e-4 0.187144 0.0843265 -9.60859e-4 -0.01082956 0.11928 -0.001170754 0.18713 0.119307 -0.00149995 0.187125 0.08443045 -0.001227676 -0.01055997 0.08449757 -0.00149995 -0.01028579 0.08226525 4.95108e-4 -0.01223278 0.117174 4.93169e-4 0.187501 0.08193796 4.9169e-4 -0.01223617 0.1168529 4.38801e-4 0.1875579 0.116546 3.31547e-4 0.1876119 0.0816062 4.36688e-4 -0.01229119 0.11626 1.74333e-4 0.187663 0.08130007 3.24464e-4 -0.01218479 0.08102297 1.56754e-4 -0.01202219 0.116003 -2.85522e-5 0.187708 0.08081007 -3.61046e-5 -0.01183295 0.0806396 -2.6004e-4 -0.01161199 0.115783 -2.71575e-4 0.187747 0.08051687 -4.97558e-4 -0.0113765 0.0804392 -7.37688e-4 -0.01113748 0.1156049 -5.48105e-4 0.1877779 0.115474 -8.50601e-4 0.187801 0.08039671 -9.94467e-4 -0.01088148 0.1153939 -0.001170754 0.187815 0.08039116 -0.00122863 -0.01064729 0.115367 -0.00149995 0.18782 0.08042007 -0.00149995 -0.01037555 0.08449757 -0.00149995 -0.01028579 0.08443045 -0.001227676 -0.01055997 0.08825486 -0.005831599 -0.005831599 0.1130365 -0.00513786 -0.00513786 0.109531 0.001092731 -0.01163518 0.08527415 -0.005881667 -0.005881667 0.08379757 -2.19936e-4 -0.01158469 0.09605729 7.29759e-4 -0.01199817 0.08401006 -4.52826e-4 -0.01134616 0.0843265 -9.60859e-4 -0.01082956 0.0841853 -6.99527e-4 -0.01109474 0.08354598 -3.50795e-6 -0.0118075 0.08325839 1.84333e-4 -0.01200246 0.08292835 3.41142e-4 -0.01216715 0.08257967 4.46923e-4 -0.012281 0.123 -0.004827976 -0.004827976 0.123 0.001535832 -0.01119196 0.1061799 -0.00535798 -0.00535798 0.09722799 -0.005623161 -0.005623161 0.132 -0.01198929 0.002796888 0.1229871 -0.004828393 -0.004828393 0.132 -0.004596173 -0.004596173 0.116969 -0.01304346 0.00296247 0.0869019 -0.01506096 0.003349661 0.08527415 -0.005881667 -0.005881667 0.08826309 -0.00583142 -0.00583142 0.101936 -0.01406735 0.003146767 0.09722799 -0.005623161 -0.005623161 0.1074453 -0.005317926 -0.005317926 0.1130535 -0.005137324 -0.005137324 0.132 0.001060605 0.001060605 0.132 -0.005750834 0.006243407 0.132 -0.006847023 0.005714952 0.132 -0.004632115 0.006753444 0.132 -0.007920563 0.005168139 0.132 -0.008971571 0.004602909 0.132 -0.004596173 -0.004596173 0.132 -0.01000005 0.00401932 0.132 -0.01100599 0.003417253 0.132 -0.01198929 0.002796888 0.15 -0.003775954 0.005897283 0.132 -0.004632115 0.006753444 0.132 0.001060605 0.001060605 0.15 0.001060605 0.001060605 0.15 0.001060605 0.001060605 0.15 -0.00194931 0.00642246 0.15 -0.002864181 0.006189346 0.15 -0.003775954 0.005897283 0.15 -1.13866e-4 0.006694197 0.15 -0.001031577 0.006595313 0.15 8.02572e-4 0.006712794 0.15 0.002624571 0.006475806 0.15 0.001716077 0.006643414 0.15 0.004419744 0.00581336 0.15 0.00352621 0.006201148 0.15 0.005303263 0.005303263 0.123 0.001535832 0.001535832 0.132 0.001060605 0.001060605 0.123 -0.004828035 -0.004828035 0.132 -0.004596173 -0.004596173 0.02599996 0.003177583 0.003177583 0.01037317 0.001278638 0.001278638 0.009019315 0.00183773 0.00183773 0.003281533 0.005428493 0.005428493 0.004254221 0.004600465 0.004600465 0.005312263 0.003833591 0.003833591 0.02430069 -0.002195179 -0.002195179 0.02599996 -0.002479314 -0.002479314 0.02103918 -0.001599788 -0.001599788 0.02264708 -0.001902043 -0.001902043 0.0179072 -9.43381e-4 -9.43381e-4 0.01946467 -0.001282751 -0.001282751 0.01474249 -1.51029e-4 -1.51029e-4 0.0163365 -5.67648e-4 -5.67648e-4 0.01177388 7.65823e-4 7.65823e-4 0.0132305 2.91863e-4 2.91863e-4 0.007700562 0.002456068 0.002456068 0.006461381 0.003121912 0.003121912 0.15 0.005303263 0.005303263 0.002379536 0.006354153 0.006354153 0.001582026 0.007346689 0.007346689 9.27661e-4 0.008381068 0.008381068 4.00312e-4 0.009467661 0.009467661 0 0.01060658 0.01060658 0.15 0.001060605 0.001060605 0 0.007587611 0.01362556 0 0.009620606 0.01175534 0 0.01060658 0.01060658 0 0.008614301 0.01276177 0.05755895 -0.005601882 -0.005601882 0.06002151 -0.01588833 0.004490137 0.0576049 -0.01587748 0.004667103 0.03696936 -0.01493495 0.006905555 0.03814059 -0.004148244 -0.004148244 0.03821587 -0.01504236 0.006729125 0.06039118 -0.005712509 -0.005712509 0.06322497 -0.0058012 -0.0058012 0.06263691 -0.01588076 0.004315674 0.06522911 -0.01585477 0.004159092 0.06606036 -0.005867898 -0.005867898 0.06889736 -0.005912601 -0.005912601 0.0671209 -0.01582449 0.004054784 0.05472844 -0.005469202 -0.005469202 0.0557757 -0.01585686 0.004811942 0.05325818 -0.0158118 0.005025982 0.05451667 -0.01583695 0.004916667 0.05200016 -0.01578116 0.005139946 0.05189955 -0.005314588 -0.005314588 0.05074286 -0.0157451 0.005258738 0.04913818 -0.005136549 -0.005136549 0.0494861 -0.01570308 0.005382418 0.04823029 -0.01565527 0.005511045 0.04697579 -0.01560139 0.005644798 0.04638159 -0.004930853 -0.004930853 0.04446685 -0.01547479 0.005927979 0.04572087 -0.01554125 0.005783796 0.04321449 -0.01540189 0.006077408 0.04362988 -0.004697561 -0.004697561 0.0419631 -0.01532226 0.006232202 0.04088276 -0.004436671 -0.004436671 0.04071277 -0.01523596 0.006392478 0.03946369 -0.01514267 0.00655806 0.03323894 -0.01456886 0.00746715 0.03508955 -0.003790676 -0.003790676 0.03448098 -0.01469838 0.007274627 0.0357244 -0.01482039 0.007087409 0.03075975 -0.01428729 0.007867872 0.03204917 -0.003393292 -0.003393292 0.03199839 -0.01443189 0.007664978 0.02901929 -0.002956151 -0.002956151 0.0270552 -0.0138064 0.008507013 0.02599996 -0.002479314 -0.002479314 0.02952289 -0.01413488 0.008075952 0.0233677 -0.01325255 0.009189426 0.02264708 -0.001902043 -0.001902043 0.02430069 -0.002195179 -0.002195179 0.02459448 -0.01344585 0.008957147 0.01970845 -0.01259726 0.009928524 0.01946467 -0.001282751 -0.001282751 0.02092415 -0.01283007 0.009674131 0.02103918 -0.001599788 -0.001599788 0.02214407 -0.01304775 0.009428203 0.0163365 -5.67648e-4 -5.67648e-4 0.01729625 -0.01207309 0.01046866 0.01610195 -0.0117774 0.01075595 0.01849889 -0.01234555 0.01019316 0.0179072 -9.43381e-4 -9.43381e-4 0.01374679 -0.01110064 0.01137089 0.01259028 -0.01071298 0.01170009 0.0132305 2.91863e-4 2.91863e-4 0.01474249 -1.51029e-4 -1.51029e-4 0.01491796 -0.0114547 0.01105636 0.009244382 -0.009299874 0.01277679 0.01037317 0.001278638 0.001278638 0.01033467 -0.009817421 0.01240307 0.01177388 7.65823e-4 7.65823e-4 0.01145094 -0.01028728 0.01204395 0.006461381 0.003121912 0.003121912 0.007700562 0.002456068 0.002456068 0.007165789 -0.008098244 0.01356124 0.009019315 0.00183773 0.00183773 0.008185565 -0.008728981 0.01316416 0.005266547 -0.006642222 0.01437109 0.005312263 0.003833591 0.003833591 0.006189823 -0.007404744 0.01396524 0.003281533 0.005428493 0.005428493 0.002903163 -0.003910183 0.01548987 0.002379536 0.006354153 0.006354153 0.004407107 -0.00580585 0.01476675 0.00361669 -0.004895448 0.01514387 0.004254221 0.004600465 0.004600465 0.001279532 -5.62079e-4 0.01614165 9.27661e-4 0.008381068 0.008381068 0.001582026 0.007346689 0.007346689 0.001733124 -0.00173527 0.01600545 0.002274751 -0.002854168 0.01578247 4.00312e-4 0.009467661 0.009467661 3.98852e-4 0.003095448 0.01583576 2.36992e-4 0.004294872 0.01546669 9.10958e-4 6.46742e-4 0.01616656 6.19498e-4 0.001870989 0.01606708 0 0.01060658 0.01060658 1.21023e-4 0.005448818 0.01496905 4.53345e-5 0.006550371 0.01435059 0 0.007587611 0.01362556 0.02582389 -0.01363027 0.008729696 0.02828794 -0.01397466 0.008289039 0.06005698 0 0.0607869 0.05559265 0 0.06303846 0.05611908 0 0.06008499 0.05953055 0 0.06374025 0.06995576 0 -0.01185148 0.07046556 0 -0.01186239 0.06075406 0 0.04262745 0.06616878 0 0.04359245 0.06546688 0 0.04753041 0.05956 0 0.04647767 0.152292 2.12614e-4 0.21 0.152097 1.23414e-4 0.21 0.152396 2.42565e-4 0.21 0.1540496 -4.58963e-4 0.21 0.1540588 4.595e-4 0.21 0.152191 1.75355e-4 0.21 0.1520169 4.97867e-5 0.21 0.1520169 -4.93683e-5 0.21 0.152096 -1.23097e-4 0.21 0.152191 -1.75129e-4 0.21 0.152292 -2.12479e-4 0.21 0.152396 -2.42397e-4 0.21 0.152501 2.69383e-4 0.21 0.1525 -2.69211e-4 0.21 0.152606 2.93221e-4 0.21 0.152712 3.14337e-4 0.21 0.1526049 -2.93154e-4 0.21 0.152711 -3.14326e-4 0.21 0.152818 3.33046e-4 0.21 0.152818 -3.32934e-4 0.21 0.152925 3.49728e-4 0.21 0.153032 3.64774e-4 0.21 0.152924 -3.49559e-4 0.21 0.153031 -3.64695e-4 0.21 0.1531389 3.7857e-4 0.21 0.153138 -3.78578e-4 0.21 0.153246 3.91339e-4 0.21 0.153353 4.03122e-4 0.21 0.153245 -3.91356e-4 0.21 0.153353 -4.03103e-4 0.21 0.153461 4.13953e-4 0.21 0.15346 -4.13893e-4 0.21 0.1536097 4.2757e-4 0.21 0.153567 -4.23794e-4 0.21 0.153675 -4.32871e-4 0.21 0.1538286 4.44607e-4 0.21 0.1538415 -4.45519e-4 0.21 0.1542657 4.70627e-4 0.21 0.1542724 -4.70946e-4 0.21 0.1544777 4.80004e-4 0.21 0.154481 -4.80152e-4 0.21 0.1546937 4.87762e-4 0.21 0.1546971 -4.87854e-4 0.21 0.1549139 4.93916e-4 0.21 0.1549134 -4.93894e-4 0.21 0.1551291 4.98386e-4 0.21 0.1551328 -4.98445e-4 0.21 0.155345 5.01426e-4 0.21 0.155344 -5.0142e-4 0.21 0.1555612 5.03165e-4 0.21 0.1555602 -5.03164e-4 0.21 0.155724 5.0365e-4 0.21 0.155724 -5.03651e-4 0.21 0.1617258 2.40584e-4 0.2072946 0.1618072 -2.35608e-4 0.2072131 0.1615999 -2.51977e-4 0.20744 0.161568 2.53097e-4 0.207467 0.1613758 2.68044e-4 0.2076617 0.1613997 -2.67271e-4 0.2076408 0.1610877 2.89423e-4 0.2079241 0.1610007 -2.97096e-4 0.2080042 0.1607224 3.15746e-4 0.2082311 0.1606371 -3.23154e-4 0.2083075 0.1602838 -3.47349e-4 0.2085733 0.160398 3.38696e-4 0.208485 0.1601949 3.52669e-4 0.208635 0.160022 -3.64896e-4 0.208746 0.160015 3.64429e-4 0.208756 0.1597926 -3.79557e-4 0.2088868 0.1595583 3.92894e-4 0.2090296 0.1594048 -4.02712e-4 0.2091026 0.159837 3.75798e-4 0.208869 0.159232 4.12019e-4 0.2091926 0.1590284 -4.23578e-4 0.2092861 0.158954 4.26746e-4 0.20932 0.1587769 -4.36663e-4 0.209394 0.1581489 -4.64119e-4 0.2096243 0.158529 -4.48431e-4 0.2094921 0.1583164 4.56788e-4 0.2095701 0.1586639 4.41096e-4 0.2094422 0.157867 -4.74261e-4 0.209709 0.158049 4.67639e-4 0.209655 0.1577693 4.77094e-4 0.2097351 0.157683 -4.80133e-4 0.209758 0.1572129 4.9174e-4 0.2098606 0.157117 -4.93909e-4 0.209878 0.157307 -4.89957e-4 0.209843 0.157491 4.85003e-4 0.209803 0.155724 5.0365e-4 0.21 0.15593 -5.0418e-4 0.209996 0.15593 5.04181e-4 0.209996 0.156532 5.01922e-4 0.209958 0.156333 5.03316e-4 0.209975 0.156532 -5.01925e-4 0.209958 0.156729 -4.99893e-4 0.209936 0.156729 4.99886e-4 0.209936 0.156334 -5.03317e-4 0.209975 0.156924 -4.97221e-4 0.209909 0.156924 4.97209e-4 0.209909 0.1561329 -5.04068e-4 0.2099879 0.1561329 5.04069e-4 0.2099879 0.157496 -4.85365e-4 0.209803 0.155724 -5.03651e-4 0.21 0.1619713 -2.22002e-4 0.2070099 0.1619684 2.20705e-4 0.2070037 0.1622424 -1.9862e-4 0.2066349 0.162138 2.06309e-4 0.206782 0.1623138 1.90961e-4 0.2065393 0.1623922 -1.8555e-4 0.2064151 0.1625169 1.72729e-4 0.2062281 0.1634653 -7.97906e-5 0.2040222 0.1635564 -6.90624e-5 0.2036311 0.163551 6.80043e-5 0.2036612 0.1637208 4.39725e-5 0.2022695 0.1637212 -4.54026e-5 0.2022435 0.163609 -6.26591e-5 0.203355 0.1636238 5.898e-5 0.2032637 0.1626116 -1.65733e-4 0.2060673 0.1634574 7.87436e-5 0.2040527 0.1633502 -9.24736e-5 0.2044203 0.163697 -5.02894e-5 0.2026618 0.1636962 4.87216e-5 0.2026706 0.1633491 9.06683e-5 0.2044237 0.1632519 -1.02768e-4 0.204707 0.163108 1.15838e-4 0.205079 0.1631303 -1.15552e-4 0.2050237 0.1636557 -5.64712e-5 0.2030463 0.163666 5.33374e-5 0.2029629 0.1627246 1.53626e-4 0.205874 0.1627965 -1.48402e-4 0.2057398 0.162855 1.40904e-4 0.2056249 0.1629878 1.27823e-4 0.2053515 0.1629692 -1.31741e-4 0.2053905 0.1632193 1.04391e-4 0.2047973 0.1637238 4.10956e-5 0.2018797 0.163725 -4.33201e-5 0.201964 0.1637173 -4.1943e-5 0.2016507 0.1637083 3.98959e-5 0.2014881 0.163682 4.02175e-5 0.201182 0.1637 -4.17867e-5 0.201377 0.163682 -4.21712e-5 0.201182 0.162419 -6.55736e-5 0.1888909 0.1630499 4.95738e-5 0.1950359 0.1630499 -5.54564e-5 0.1950359 0.159891 -7.43633e-5 0.1643069 0.1605229 7.20172e-5 0.170453 0.161155 6.86537e-5 0.176599 0.159892 7.38819e-5 0.1643069 0.161787 6.37919e-5 0.182745 0.1605229 -7.69168e-5 0.170453 0.161155 -7.63038e-5 0.176599 0.162419 5.7432e-5 0.1888909 0.161787 -7.25227e-5 0.182745 0.163682 4.02175e-5 0.201182 0.163682 -4.21712e-5 0.201182 0.1443549 0.001375854 0.163245 0.1443549 -0.001376271 0.163245 0.142942 0.001482009 0.1631489 0.138701 -0.001788556 0.162859 0.137287 0.001886129 0.162762 0.138701 0.001788139 0.162859 0.145768 0.001267671 0.1633419 0.145768 -0.001268148 0.1633419 0.147181 -0.001157939 0.163439 0.147181 0.001157462 0.163439 0.148594 0.001045227 0.1635349 0.148594 -0.001045703 0.1635349 0.150007 9.30969e-4 0.163632 0.150007 -9.31439e-4 0.163632 0.151419 -8.15118e-4 0.1637279 0.151419 8.14645e-4 0.1637279 0.152832 6.96282e-4 0.163825 0.152832 -6.96757e-4 0.163825 0.154244 5.7588e-4 0.1639209 0.154244 -5.76357e-4 0.1639209 0.155656 -4.53917e-4 0.164018 0.155656 4.53439e-4 0.164018 0.157068 3.28959e-4 0.1641139 0.157068 -3.29438e-4 0.1641139 0.1584799 2.0244e-4 0.164211 0.1584799 -2.0292e-4 0.164211 0.159891 -7.43633e-5 0.1643069 0.159892 7.38819e-5 0.1643069 0.142942 -0.001482427 0.1631489 0.141528 0.001586079 0.163052 0.141528 -0.001586496 0.163052 0.140115 0.001688122 0.162955 0.140115 -0.001688539 0.162955 0.137287 -0.001886546 0.162762 0.135873 0.001982033 0.162665 0.135873 -0.00198245 0.162665 0.134459 -0.002076327 0.162569 0.134459 0.00207597 0.162569 0.133045 -0.002168178 0.162472 0.133045 0.002167761 0.162472 0.13163 0.002257585 0.162375 0.13163 -0.002258002 0.162375 0.130215 -0.0023458 0.162279 0.130215 0.002345383 0.162279 0.128801 -0.002431511 0.162182 0.128801 0.002431154 0.162182 0.127386 0.002514839 0.1620849 0.127386 -0.002515196 0.1620849 0.125971 -0.002596855 0.161988 0.125971 0.002596497 0.161988 0.05956 0 0.04647767 0.05956 -0.005091607 0.04647767 0.0602352 -0.005132377 0.04268896 0.06590175 -0.005235195 0.01089489 0.06995576 0 -0.01185148 0.06516766 -0.005244076 0.01501345 0.06889736 -0.005912601 -0.005912601 0.06693899 -0.01456588 0.005075156 0.0671209 -0.01582449 0.004054784 0.06676429 -0.01329129 0.006055355 0.06091779 -0.005166947 0.03885895 0.06160765 -0.005195319 0.03498774 0.06230497 -0.005217432 0.03107535 0.06300967 -0.005233407 0.02712178 0.06444096 -0.005246698 0.01909077 0.06372165 -0.005243182 0.0231269 0.06643646 -0.01069384 0.007895052 0.0665968 -0.01200056 0.00699532 0.06614279 -0.008021175 0.00954312 0.06628328 -0.009371161 0.008754551 0.06601619 -0.006641268 0.01025295 0.06251347 0 0.0470041 0.06251347 -0.005069613 0.0470041 0.06103897 -0.005082726 0.04674124 0.05956 -0.005091607 0.04647767 0.05956 0 0.04647767 0.05611908 0 0.06008499 0.05611908 -0.004845321 0.06008499 0.05809628 -0.004871487 0.06043738 0.06005698 -0.004887282 0.0607869 0.06005698 0 0.0607869 0.06546688 0 0.04753035 0.06616878 0 0.04359245 0.06616878 -0.005053043 0.04359245 0.06546688 -0.005031526 0.04753035 0.06075406 0 0.04262745 0.06075406 -0.005131006 0.04262745 0.06256425 -0.005110561 0.04295009 0.0643692 -0.005084574 0.04327178 0.06616878 -0.005053043 0.04359245 0.06616878 0 0.04359245 0.0621252 -0.005188345 0.03493446 0.06075406 0 0.04262745 0.06282168 -0.005208194 0.0310263 0.06423676 -0.005230069 0.02308624 0.06352555 -0.005222082 0.0270769 0.06568127 -0.00522834 0.01498144 0.06495535 -0.005232155 0.01905447 0.07046556 0 -0.01186239 0.06641459 -0.005218565 0.01086735 0.06694525 -0.01069355 0.007890045 0.06940639 -0.005919158 -0.005919158 0.06716507 -0.01242417 0.006656467 0.06143599 -0.005162656 0.03880155 0.06656998 -0.007090806 0.00999546 0.06674689 -0.008915781 0.009003043 0.06763356 -0.0158149 0.004027724 0.067393 -0.01413428 0.005377411 0.06075406 -0.005131006 0.04262745 0.07969707 -0.004680156 0.01019245 0.08386659 -0.006376504 0.009170413 0.08182489 -0.004577577 0.01008975 0.06813937 -0.005160927 0.01077568 0.06641459 -0.005218565 0.01086735 0.06656998 -0.007090806 0.00999546 0.07814496 -0.00851494 0.008451342 0.0840103 -0.00446856 0.009985446 0.07365906 -0.00494939 0.01049119 0.07561415 -0.004866063 0.0103932 0.07762688 -0.004776298 0.0102936 0.08370089 -0.008234858 0.008230865 0.08351325 -0.01004356 0.007166802 0.0717616 -0.00502634 0.01058757 0.07227981 -0.008737385 0.008725643 0.06674689 -0.008915781 0.009003043 0.06694525 -0.01069355 0.007890045 0.07227981 -0.01254075 0.006214201 0.06992167 -0.005096852 0.0106824 0.07814496 -0.01222497 0.006034672 0.07777726 -0.01550555 0.003596365 0.06716507 -0.01242417 0.006656467 0.067393 -0.01413428 0.005377411 0.07270276 -0.01568585 0.003790259 0.06763356 -0.0158149 0.004027724 0.08330368 -0.01180267 0.005978107 0.0830866 -0.0135504 0.004746973 0.08285719 -0.01527398 0.003445982 0.115367 -0.00149995 0.18782 0.1137765 -0.00313878 0.1787979 0.1116942 -0.003243923 0.1669891 0.115367 -0.003057122 0.18782 0.1096074 -0.003347516 0.1551541 0.108051 -0.003423511 0.146326 0.1064715 -0.003499686 0.1373727 0.1043993 -0.003598034 0.1256164 0.102825 -0.003671407 0.1166869 0.1012526 -0.003743767 0.1077729 0.09915816 -0.003838539 0.0958935 0.08042007 -0.00149995 -0.01037555 0.09709209 -0.003930151 0.08417612 0.09550786 -0.003999173 0.07519185 0.09392291 -0.004067242 0.06620305 0.09183341 -0.004155278 0.05435258 0.09028166 -0.004219412 0.04555267 0.08871471 -0.004283249 0.03666579 0.08714598 -0.004346072 0.02776908 0.08557808 -0.004407882 0.01887702 0.0840103 -0.00446856 0.009985446 0.08351325 -0.01004356 0.007166802 0.08330368 -0.01180267 0.005978107 0.08120369 -0.005931198 -0.005931198 0.08386659 -0.006376504 0.009170413 0.08370089 -0.008234858 0.008230865 0.08285719 -0.01527398 0.003445982 0.0830866 -0.0135504 0.004746973 0.119307 -0.00149995 0.187125 0.118325 -0.003010272 0.187299 0.117341 -0.003030478 0.187472 0.116355 -0.003046095 0.187646 0.115367 -0.00149995 0.18782 0.119307 -0.002985537 0.187125 0.115367 -0.003057122 0.18782 0.1153939 -0.001170754 0.187815 0.115474 -8.50601e-4 0.187801 0.118414 1.74333e-4 0.187283 0.118671 -2.85522e-5 0.187238 0.116003 -2.85522e-5 0.187708 0.1156049 -5.48105e-4 0.1877779 0.11782 4.38801e-4 0.187388 0.118128 3.31547e-4 0.187333 0.116546 3.31547e-4 0.1876119 0.11626 1.74333e-4 0.187663 0.1168529 4.38801e-4 0.1875579 0.1175 4.93169e-4 0.187444 0.117174 4.93169e-4 0.187501 0.115783 -2.71575e-4 0.187747 0.118891 -2.71575e-4 0.1871989 0.119069 -5.48105e-4 0.187167 0.1192 -8.50601e-4 0.187144 0.11928 -0.001170754 0.18713 0.08784627 -0.006786167 0.008706092 0.08527415 -0.005881667 -0.005881667 0.08773547 -0.008018076 0.008077621 0.08761489 -0.009227395 0.007393479 0.08794736 -0.005531787 0.009278893 0.08803856 -0.004254937 0.009795963 0.08449757 -0.00149995 -0.01028579 0.08748435 -0.0104143 0.006653606 0.08734416 -0.01157855 0.005858004 0.08720237 -0.01274806 0.005053997 0.08705496 -0.01390886 0.004217863 0.09424352 -0.004008948 0.04498606 0.09064555 -0.00415194 0.02458107 0.09736949 -0.003883898 0.06271415 0.1016833 -0.00371021 0.08717924 0.119307 -0.00149995 0.187125 0.1068651 -0.003499627 0.1165668 0.1115296 -0.003308236 0.143021 0.1156507 -0.003137826 0.1663932 0.1193066 -0.002985537 0.187125 0.0869019 -0.01506096 0.003349661 0.02828794 -0.01397466 0.008289039 0.02952289 -0.01413488 0.008075952 0.06643646 -0.01069384 0.007895052 0.02214407 -0.01304775 0.009428203 0.0233677 -0.01325255 0.009189426 0.02999997 -0.01296764 0.008917152 0.02092415 -0.01283007 0.009674131 0.02999997 -0.01131558 0.01007246 0.02459448 -0.01344585 0.008957147 0.02582389 -0.01363027 0.008729696 0.01970845 -0.01259726 0.009928524 0.0270552 -0.0138064 0.008507013 0.01849889 -0.01234555 0.01019316 0.0665968 -0.01200056 0.00699532 0.03448098 -0.01469838 0.007274627 0.0357244 -0.01482039 0.007087409 0.06676429 -0.01329129 0.006055355 0.03821587 -0.01504236 0.006729125 0.04697579 -0.01560139 0.005644798 0.04572087 -0.01554125 0.005783796 0.04321449 -0.01540189 0.006077408 0.0419631 -0.01532226 0.006232202 0.05200016 -0.01578116 0.005139946 0.06693899 -0.01456588 0.005075156 0.05074286 -0.0157451 0.005258738 0.05451667 -0.01583695 0.004916667 0.0557757 -0.01585686 0.004811942 0.05703508 -0.01587176 0.004711627 0.05955475 -0.01588678 0.004523754 0.0645982 -0.01586216 0.004196286 0.06333696 -0.01587486 0.004272401 0.06207609 -0.01588326 0.004352331 0.06081539 -0.01588726 0.004436075 0.06585949 -0.01584535 0.004123747 0.0671209 -0.01582449 0.004054784 0.05829489 -0.01588165 0.004615604 0.05325818 -0.0158118 0.005025982 0.0494861 -0.01570308 0.005382418 0.04823029 -0.01565527 0.005511045 0.04071277 -0.01523596 0.006392478 0.04446685 -0.01547479 0.005927979 0.03946369 -0.01514267 0.00655806 0.03696936 -0.01493495 0.006905555 0.03075975 -0.01428729 0.007867872 0.03199839 -0.01443189 0.007664978 0.03323894 -0.01456886 0.00746715 0.01610195 -0.0117774 0.01075595 0.01729625 -0.01207309 0.01046866 0.02999997 -0.00961709 0.01114559 0.01491796 -0.0114547 0.01105636 0.01259028 -0.01071298 0.01170009 0.01374679 -0.01110064 0.01137089 0.01033467 -0.009817421 0.01240307 0.01145094 -0.01028728 0.01204395 0.02999997 -0.007881104 0.01210868 0.06601619 -0.006641268 0.01025295 0.06177777 -0.005355894 0.01112145 0.06383979 -0.005298554 0.01100695 0.0576536 -0.005451381 0.01135808 0.05559158 -0.005488693 0.01148068 0.04528319 -0.005553722 0.01214247 0.02999997 -0.006116867 0.01293367 0.009244382 -0.009299874 0.01277679 0.008185565 -0.008728981 0.01316416 0.02881407 -0.00507003 0.01342159 0.02676069 -0.004935443 0.01360535 0.005266547 -0.006642222 0.01437109 0.03498357 -0.005359709 0.0129047 0.03292578 -0.005280196 0.01307159 0.002903163 -0.003910183 0.01548987 0.01653319 -0.003833174 0.01462316 0.01484388 -0.003547906 0.01480948 0.00361669 -0.004895448 0.01514387 0.004407107 -0.00580585 0.01476675 0.02163338 -0.004488945 0.01409327 0.001733124 -0.00173527 0.01600545 0.009227335 -0.002071201 0.01547986 0.008917033 -0.001934409 0.01552075 0.002274751 -0.002854168 0.01578247 0.009864449 -0.002304494 0.01540029 0.009543836 -0.002193391 0.01543974 0.001279532 -5.62079e-4 0.01614165 0.007061958 -4.96618e-4 0.01577818 0.006933748 -1.81767e-4 0.01579636 0.08999997 0.0048334 0.009374976 0.08878618 0.004213809 0.009760379 0.09090298 0.004094839 0.009677052 9.10958e-4 6.46742e-4 0.01616656 0.00774157 0.001218795 0.01569527 0.008015811 0.001418888 0.0156576 0.007051467 4.74925e-4 0.01578515 0.007247209 7.53366e-4 0.01576077 0.1266109 -0.001612603 0.007986247 0.1244699 -0.001785576 0.008094012 0.15 -0.001031577 0.006595313 0.009844005 0.002296566 0.0154109 6.19498e-4 0.001870989 0.01606708 0.009523868 0.002184689 0.01545178 0.008596062 0.0017699 0.01557677 0.008898377 0.001923263 0.01553499 0.08734416 -0.01157855 0.005858004 0.132 -0.008971571 0.004602909 0.12 -0.008702039 0.005516886 2.36992e-4 0.004294872 0.01546669 0.01854056 0.004126131 0.01434308 0.02030837 0.004346787 0.01414287 0.01502108 0.003582775 0.01475787 3.98852e-4 0.003095448 0.01583576 0.01327645 0.003231525 0.01497405 0.08748435 -0.0104143 0.006653606 0.107334 -0.003058433 0.008925437 0.105191 -0.00320369 0.009025514 0.12 -0.002934932 0.008121252 1.21023e-4 0.005448818 0.01496905 0.02951908 0.005116939 0.01319408 0.02999997 0.006267666 0.01250159 0.02208 0.004540205 0.0139479 0.007757246 -0.001234829 0.01568126 0.008032381 -0.001433551 0.0156427 0.05352956 -0.005518555 0.01160615 0.05146777 -0.00554037 0.01173496 0.04940599 -0.005553841 0.01186728 0.0473445 -0.00555849 0.012003 0.007165789 -0.008098244 0.01356124 0.04322218 -0.00553888 0.01228594 0.04116165 -0.005513012 0.01243364 0.0391016 -0.005475163 0.01258587 0.0370422 -0.00542438 0.01274287 0.006189823 -0.007404744 0.01396524 0.0308693 -0.005184292 0.01324379 0.02504956 -0.004805564 0.01376336 0.02334028 -0.004657506 0.01392596 0.01992946 -0.004297375 0.01426529 0.01822906 -0.004080116 0.01444196 0.01316618 -0.003205239 0.01500284 0.01150506 -0.002792239 0.01520168 0.008614003 -0.001782238 0.01556187 0.008318781 -0.001615285 0.01560276 0.007497787 -0.001015782 0.01571756 0.007260322 -7.7269e-4 0.01575058 0.00692898 1.57392e-4 0.01579898 0.007483124 9.9829e-4 0.01573008 0.008301556 0.001601815 0.01561784 0.009208023 0.002061307 0.01549309 0.01154947 0.002804458 0.01519435 0.01677745 0.003874182 0.01454806 0.02385467 0.004709422 0.01375848 0.0256319 0.004857063 0.01357489 0.02741116 0.004985868 0.01339715 0.03162896 0.005227088 0.01299887 0.15 -0.002864181 0.006189346 0.15 -0.00194931 0.00642246 0.03585314 0.005393683 0.01263117 0.03374046 0.005318701 0.0128113 0.03796708 0.005453467 0.0124582 0.04219734 0.00553137 0.01213335 0.04008179 0.005499005 0.01229226 0.04643028 0.005560755 0.01183485 0.04431354 0.005551636 0.01198095 4.53345e-5 0.006550371 0.01435059 0.06 0.005550503 0.01093828 0.06 0.007039189 0.009875178 0.05066478 0.005549132 0.01155996 0.04854738 0.005559742 0.01169466 0.05278247 0.005529582 0.01143068 0.05490046 0.005501389 0.01130646 0.06337326 0.00531286 0.01085436 0.06125497 0.005370438 0.01096135 0.05701845 0.005465209 0.01118695 0.05913668 0.0054214 0.01107209 0.06549149 0.005248904 0.01075088 0.08999997 0.006145119 0.008532106 0.06760978 0.005178928 0.01065069 0.06972789 0.005103349 0.0105533 0.08999997 0.007424592 0.007424592 0.07396399 0.004936575 0.0103662 0.071846 0.005022466 0.01045858 0.07819968 0.004751086 0.01018685 0.07608187 0.004846036 0.01027566 0.08243477 0.004548192 0.0100134 0.0845521 0.004440605 0.009928166 0.08031725 0.004651725 0.01009947 0.08666926 0.004329085 0.009843885 0.12 0.005251049 0.007189035 0.12 0.006363928 0.006363928 0.12 0.004116237 0.007811665 0.0930196 0.003972291 0.009593665 0.09513598 0.003846406 0.009510219 0.09725207 0.003717184 0.009426414 0.15 0.004419744 0.00581336 0.15 0.005303263 0.005303263 0.101484 0.003449261 0.009256958 0.103599 0.003310799 0.00917083 0.09936809 0.003584802 0.009342074 0.105714 0.003169357 0.009083569 0.12 0.002963423 0.008246481 0.15 0.00352621 0.006201148 0.107829 0.003025054 0.008994936 0.109944 0.002877891 0.008904635 0.114173 0.00257492 0.008718848 0.116287 0.002419054 0.008623003 0.15 0.002624571 0.006475806 0.1184 0.002260208 0.008524894 0.120513 0.002098381 0.008424341 0.122626 0.001933634 0.008321106 0.15 0.001716077 0.006643414 0.124739 0.001766085 0.008215069 0.128962 0.001422643 0.007993876 0.126851 0.001595795 0.008106052 0.133185 0.001066625 0.007759451 0.135295 8.83088e-4 0.007636845 0.131074 0.001246392 0.007878422 0.137404 6.95626e-4 0.007510304 0.15 8.02572e-4 0.006712794 0.141622 3.12258e-4 0.007244884 0.139514 5.05054e-4 0.00737971 0.1437309 1.18122e-4 0.007105708 0.15 -1.13866e-4 0.006694197 0.1373119 -7.01619e-4 0.007434844 0.132 -0.01198929 0.002796888 0.132 -0.01100599 0.003417253 0.116969 -0.01304346 0.00296247 0.128751 -0.001436531 0.007877647 0.11162 -0.002758681 0.008722662 0.109477 -0.002910077 0.008824467 0.103048 -0.003345847 0.009124815 0.132 -0.004632115 0.006753444 0.15 -0.003775954 0.005897283 0.08761489 -0.009227395 0.007393479 0.132 -0.005750834 0.006243407 0.08773547 -0.008018076 0.008077621 0.132 -0.006847023 0.005714952 0.100905 -0.003484964 0.009223222 0.08784627 -0.006786167 0.008706092 0.09876078 -0.003620982 0.009320795 0.08794736 -0.005531787 0.009278893 0.0966168 -0.00375396 0.009417533 0.09447258 -0.003883779 0.009513437 0.09232819 -0.004010558 0.009608447 0.12 -0.004114389 0.007739663 0.09018349 -0.004134297 0.009702622 0.08803856 -0.004254937 0.009795963 0.132 -0.01000005 0.00401932 0.08705496 -0.01390886 0.004217863 0.101936 -0.01406735 0.003146767 0.130892 -0.001257419 0.007768213 0.135172 -8.89976e-4 0.007546842 0.133032 -0.001075208 0.007657945 0.113762 -0.002604186 0.008620023 0.115904 -0.002446591 0.00851649 0.118046 -0.002285957 0.008412122 0.120187 -0.002122223 0.00830692 0.1223289 -0.001955449 0.008200883 0.139451 -5.10183e-4 0.007322013 0.1415899 -3.15669e-4 0.007208347 0.143729 -1.18076e-4 0.007093846 0.02999997 0.007933318 0.01121824 0.02999997 0.009545922 0.009545922 0 0.008614301 0.01276177 0 0.007587611 0.01362556 0 0.01060658 0.01060658 0 0.009620606 0.01175534 0.0869019 -0.01506096 0.003349661 0.08720237 -0.01274806 0.005053997 0.132 -0.007920563 0.005168139 0.06628328 -0.009371161 0.008754551 0.06614279 -0.008021175 0.00954312 0.06590175 -0.005235195 0.01089489 0.05971568 -0.005406975 0.01123845 0.1120589 0.002727866 0.008812725 0.06 0.008485257 0.008485257 0.1437288 -1.18076e-4 0.007093846 0.1437309 1.18122e-4 0.007105708 0.1445518 1.15876e-4 0.01509386 0.1445519 -1.15772e-4 0.01509386 0.05746024 0.004534006 0.0753569 0.05689865 0.004428625 0.0785076 0.05689865 -0.004428625 0.0785076 0.05860078 0.004714727 0.06895768 0.05802756 0.004629373 0.07217359 0.05802756 -0.004629373 0.07217359 0.05746024 -0.004534006 0.0753569 0.05860078 -0.004714727 0.06895768 0.05917966 -0.004790067 0.06570929 0.05917966 0.004790127 0.06570929 0.05722147 0.004759609 0.0653603 0.05917966 0.004790127 0.06570929 0.05917966 -0.004790067 0.06570929 0.05722135 -0.00475955 0.0653603 0.05524176 0.00471723 0.06500738 0.05524176 -0.004717171 0.06500738 0.05559265 0 0.06303846 0.05559265 0.004771351 0.06303846 0.05524176 0.00471723 0.06500738 0.05611908 0 0.06008499 0.05567878 -0.004783987 0.06255561 0.05524176 -0.004717171 0.06500738 0.05611908 -0.004845321 0.06008499 0.05757117 0.004806995 0.06339108 0.05559265 0.004771351 0.06303846 0.05559265 0 0.06303846 0.05953055 0 0.06374025 0.05953055 0.004831373 0.06374025 0.06127297 -0.004992246 0.05396419 0.06251347 0 0.0470041 0.06005698 0 0.0607869 0.05953055 0.004831373 0.06374025 0.05953055 0 0.06374025 0.06011557 0.004892647 0.06045836 0.06189018 -0.005034387 0.05050128 0.06070625 0.004947066 0.05714374 0.0613029 0.00499475 0.05379647 0.06190526 0.005035638 0.05041658 0.06251347 0.005069732 0.0470041 0.06251347 -0.005069613 0.0470041 0.06005698 -0.004887282 0.0607869 0.06066185 -0.004943192 0.05739265 0.07929217 -0.004672944 0.04999446 0.07903838 0.004683434 0.04994916 0.07732927 -0.004739344 0.04964458 0.06459575 0.005041599 0.0473752 0.06251347 0.005069732 0.0470041 0.06251347 0 0.0470041 0.06546688 0 0.04753035 0.08125108 -0.004601478 0.05034357 0.08108258 0.004609227 0.05031347 0.06667327 0.005007684 0.04774534 0.07081395 0.004922628 0.04848337 0.06874597 0.004967987 0.04811477 0.07493567 0.004814505 0.04921799 0.07287728 0.004871428 0.04885107 0.07698935 0.004751861 0.04958397 0.08515667 0.004443585 0.05103969 0.08312195 0.004529297 0.050677 0.08320587 -0.004525005 0.05069196 0.08515667 -0.004443466 0.05103969 0.07339137 -0.004856944 0.0489428 0.07536238 -0.004800677 0.04929405 0.06943726 -0.004954338 0.04823809 0.07141625 -0.004908144 0.04859077 0.06546688 -0.005031526 0.04753035 0.06745409 -0.004995465 0.04788458 0.08439755 -0.004471004 0.05529856 0.08364737 0.004493713 0.05950754 0.08439755 0.004471123 0.05529856 0.08290618 0.004511356 0.06366676 0.08364737 -0.004493594 0.05950754 0.08515667 -0.004443466 0.05103969 0.08515667 0.004443585 0.05103969 0.08290618 -0.004511237 0.0636667 0.08217376 -0.004523932 0.0677759 0.08217376 0.004524052 0.0677759 0.08414477 0.004457592 0.06812715 0.08217376 0.004524052 0.0677759 0.08217376 -0.004523932 0.0677759 0.08414477 -0.004457473 0.06812715 0.08611178 0.004386305 0.0684778 0.08611178 -0.004386186 0.0684778 0.08576077 0.004395365 0.07044678 0.08611178 0.004386305 0.0684778 0.08611178 -0.004386186 0.0684778 0.08576077 -0.004395246 0.07044678 0.08379387 0.004464268 0.07009619 0.08576077 0.004395365 0.07044678 0.08576077 -0.004395246 0.07044678 0.08379387 -0.004464149 0.07009619 0.08182287 0.004528164 0.06974488 0.08182287 -0.004528105 0.06974488 0.08124488 -0.004532098 0.07298755 0.08067208 0.004532217 0.07620155 0.08124488 0.004532158 0.07298755 0.08010441 0.004528224 0.07938677 0.08067208 -0.004532098 0.07620155 0.08182287 -0.004528105 0.06974488 0.08182287 0.004528164 0.06974488 0.08010441 -0.004528164 0.07938677 0.07954186 -0.004520237 0.08254319 0.07954186 0.004520297 0.08254319 0.06938207 0.004635214 0.08073246 0.06938207 -0.004635214 0.08073246 0.06747436 0.004631996 0.08039247 0.06747448 -0.004631936 0.08039247 0.0656082 0.004619956 0.08005988 0.0713312 0.004629731 0.0810799 0.0713312 -0.004629671 0.0810799 0.0733217 -0.004615485 0.0814346 0.0733217 0.004615485 0.0814346 0.07535368 0.004592537 0.08179676 0.07535368 -0.004592478 0.08179676 0.07742708 0.004560768 0.08216625 0.07742708 -0.004560708 0.08216625 0.07954186 -0.004520237 0.08254319 0.07954186 0.004520297 0.08254319 0.06560826 -0.004619896 0.08005988 0.06378346 0.004599213 0.07973468 0.06378346 -0.004599153 0.07973468 0.06200009 -0.004569649 0.07941681 0.06200009 0.004569709 0.07941681 0.06025815 -0.004531383 0.07910639 0.06025815 0.004531383 0.07910639 0.05855768 0.004484415 0.0788033 0.05855774 -0.004484355 0.0788033 0.05689865 -0.004428625 0.0785076 0.05689865 0.004428625 0.0785076 0.1139492 0.003044784 0.09223544 0.1159037 -0.002972424 0.1035757 0.1113998 -0.003138542 0.07744354 0.1189793 0.00285834 0.1214211 0.1199367 -0.002822637 0.126976 0.1234387 0.002691686 0.1472952 0.1234927 -0.002689898 0.1476085 0.125971 -0.002596855 0.161988 0.125971 0.002596497 0.161988 0.1093624 0.003213465 0.06562167 0.1071399 -0.003294587 0.05272591 0.1064403 0.003320276 0.04866486 0.1034291 -0.00342971 0.03118962 0.1032505 0.003436326 0.03015339 0.09981584 0.003560543 0.01022565 0.09981584 -0.003560483 0.01022565 0.09483313 -0.003863096 0.009497344 0.09261924 -0.003994405 0.009595572 0.1005955 -0.0037539 0.08100914 0.105183 -0.003544509 0.09362852 0.09846299 0.003642082 0.009378314 0.122626 0.001933634 0.008321106 0.120513 0.002098381 0.008424341 0.1200523 0.00216335 0.01242774 0.1222194 -0.001998126 0.01266366 0.118046 -0.002285957 0.008412122 0.120187 -0.002122223 0.00830692 0.1166467 -0.002416074 0.01205724 0.1223289 -0.001955449 0.008200883 0.1244699 -0.001785576 0.008094012 0.1280419 -0.001538813 0.0132972 0.1266109 -0.001612603 0.007986247 0.130892 -0.001257419 0.007768213 0.128751 -0.001436531 0.007877647 0.131273 -0.001274049 0.01364886 0.133032 -0.001075208 0.007657945 0.1334519 -0.001088142 0.0130617 0.1348407 -9.74998e-4 0.01403707 0.135172 -8.89976e-4 0.007546842 0.139451 -5.10183e-4 0.007322013 0.1393075 -5.87669e-4 0.01452314 0.1373119 -7.01619e-4 0.007434844 0.1415899 -3.15669e-4 0.007208347 0.1445521 -1.16575e-4 0.01509386 0.14414 -1.16924e-4 0.01109385 0.09212255 -0.004093289 0.03295773 0.09655201 -0.00387454 0.04178166 0.131003 -0.002242505 0.198017 0.13977 -0.001467525 0.203417 0.139097 -0.001483738 0.203395 0.115904 -0.002446591 0.00851649 0.1121986 -0.002736032 0.01157313 0.113762 -0.002604186 0.008620023 0.11162 -0.002758681 0.008722662 0.109477 -0.002910077 0.008824467 0.1076939 -0.003047168 0.011083 0.107334 -0.003058433 0.008925437 0.1032333 -0.003342807 0.01059758 0.105191 -0.00320369 0.009025514 0.103048 -0.003345847 0.009124815 0.09981584 -0.003560602 0.01022565 0.100905 -0.003484964 0.009223222 0.09693455 -0.003735184 0.009403228 0.09876078 -0.003620982 0.009320795 0.09615707 -0.003932535 0.05583852 0.08543872 -0.004433095 0.04588443 0.07170736 -0.005027532 0.01059031 0.07375472 -0.00494492 0.01048636 0.08428913 -0.004474163 0.05590689 0.08515667 -0.004443049 0.05103969 0.1012257 -0.003695547 0.06975734 0.09937798 -0.003803074 0.07410532 0.08868187 -0.004242002 0.09139102 0.09045511 -0.004184007 0.0913909 0.06465411 -0.00339961 0.1200926 0.06610298 -0.003545522 0.11967 0.07716679 -0.002858519 0.1551746 0.0861811 -0.004188716 0.111379 0.08451241 -0.004209876 0.111374 0.08477801 -0.003950357 0.1315907 0.0832135 -0.003934144 0.131572 0.128424 -0.002307474 0.1980119 0.129285 -0.002288937 0.198014 0.1374359 -0.001518845 0.2033134 0.07993417 -0.004526019 0.08034181 0.08063781 -0.004531741 0.07639396 0.08940362 -0.004163205 0.1054931 0.1160891 -0.003105282 0.1796714 0.1142387 -0.003154039 0.1742246 0.1162216 -0.003081738 0.1739585 0.118956 -0.003001391 0.1800945 0.1216537 -0.002914667 0.1860126 0.1297128 -0.002517938 0.192 0.1274024 -0.002657651 0.1860377 0.1313289 -0.002438187 0.19201 0.121476 -0.002896547 0.1801005 0.1239321 -0.002821385 0.1860237 0.148531 -0.001120507 0.203716 0.142147 -0.001713156 0.19804 0.143007 -0.001659631 0.198042 0.140429 -0.001815438 0.198037 0.146515 -0.001219451 0.203648 0.139572 -0.001864075 0.198035 0.162443 -1.3725e-4 0.198064 0.163485 -7.75293e-5 0.203943 0.163434 -8.32916e-5 0.204136 0.163531 -7.2132e-5 0.203747 0.163572 -6.71297e-5 0.2035509 0.163609 -6.26591e-5 0.203355 0.163682 -4.21712e-5 0.201182 0.163666 -5.49714e-5 0.202959 0.16364 -5.86064e-5 0.203157 0.163688 -5.17542e-5 0.202759 0.163704 -4.89548e-5 0.2025589 0.163725 -4.33201e-5 0.201964 0.163723 -4.47269e-5 0.20216 0.163716 -4.65815e-5 0.2023569 0.163721 -4.23612e-5 0.201768 0.1637 -4.17867e-5 0.201377 0.163713 -4.185e-5 0.201572 0.1632519 -1.02768e-4 0.204707 0.1631799 -1.10339e-4 0.204897 0.162452 -1.70133e-4 0.2040269 0.163318 -9.59109e-5 0.204518 0.156358 -5.38559e-4 0.180159 0.155421 -6.76464e-4 0.186124 0.15443 -7.0491e-4 0.1801584 0.157934 -3.70002e-4 0.1771759 0.1549135 -6.08164e-4 0.174189 0.1608405 -7.69222e-5 0.1735411 0.1586264 -1.89194e-4 0.164221 0.159891 -7.43633e-5 0.1643069 0.159967 -3.22881e-4 0.1920955 0.161073 -2.62193e-4 0.198064 0.16294 -1.34635e-4 0.205452 0.1631039 -1.18252e-4 0.2050859 0.162761 -1.5176e-4 0.205805 0.162852 -1.43104e-4 0.205631 0.159063 -3.53317e-4 0.1861275 0.1625609 -1.70371e-4 0.2061499 0.161216 -2.76318e-4 0.204017 0.162457 -1.79769e-4 0.206315 0.159259 -4.2436e-4 0.198063 0.1571465 -5.76315e-4 0.1920954 0.157907 -5.41772e-4 0.198062 0.160279 -3.53204e-4 0.204007 0.161842 -2.32796e-4 0.207172 0.159305 -4.30157e-4 0.2038331 0.15701 -6.17956e-4 0.198062 0.1537602 -8.66865e-4 0.1920757 0.156116 -6.92776e-4 0.198061 0.151866 -9.19366e-4 0.1801559 0.152247 -8.32989e-4 0.174185 0.1580556 -5.24921e-4 0.2038817 0.1552259 -7.66362e-4 0.19806 0.1493095 -0.001126408 0.1801534 0.14958 -0.001049458 0.1741794 0.1511245 -0.001085102 0.1920709 0.153454 -9.09775e-4 0.198058 0.154338 -8.38708e-4 0.198059 0.146759 -0.001326382 0.18015 0.146912 -0.001258671 0.1741729 0.157099 -5.94215e-4 0.203953 0.152571 -9.7952e-4 0.1980569 0.1490795 -0.00124973 0.1920708 0.155805 -6.84698e-4 0.203924 0.151692 -0.001047909 0.198056 0.150815 -0.001114964 0.198055 0.155154 -7.28627e-4 0.203909 0.1442145 -0.001518845 0.1801469 0.1442425 -0.001460433 0.174166 0.154501 -7.71701e-4 0.2038919 0.14994 -0.001180708 0.198054 0.1416749 -0.001703917 0.1801425 0.1415725 -0.001654505 0.174157 0.148196 -0.001308381 0.198051 0.149067 -0.001245141 0.198052 0.153187 -8.55342e-4 0.203857 0.153845 -8.13935e-4 0.203875 0.147328 -0.00137031 0.19805 0.152527 -8.9591e-4 0.203839 0.139141 -0.001881837 0.1801379 0.138902 -0.001841068 0.1741474 0.151865 -9.35622e-4 0.203819 0.146461 -0.001430928 0.1980479 0.1408064 -0.001863956 0.1920443 0.138339 -0.002001643 0.186079 0.1428691 -0.001718938 0.1920537 0.140004 -0.001886904 0.1860928 0.1387863 -0.001999855 0.1920373 0.1365603 -0.002120852 0.1860786 0.13661 -0.002052426 0.1801335 0.134083 -0.002215385 0.1801285 0.1492 -0.00108546 0.203737 0.143869 -0.001604616 0.198043 0.13488 -0.002229034 0.186066 0.1367549 -0.002129912 0.19203 0.1330927 -0.002340078 0.1860647 0.1290365 -0.002516508 0.1801174 0.1315585 -0.002370297 0.180123 0.1347337 -0.002251863 0.1920216 0.1327394 -0.002364158 0.1920136 0.1296843 -0.00253719 0.1860479 0.131435 -0.002438127 0.186052 0.131862 -0.002215027 0.198019 0.126516 -0.00265336 0.180112 0.1139675 -0.003208279 0.1568481 0.112011 -0.003288388 0.145749 0.1114157 -0.00329709 0.1497899 0.1277214 -0.002607047 0.1919921 0.0827583 -0.004371523 0.0951218 0.08008527 -0.003874003 0.1315357 0.08164918 -0.003908932 0.1315534 0.06605058 -0.002927184 0.131419 0.08250385 -0.003202855 0.1579095 0.08473467 -0.002663016 0.1739456 0.089145 -0.002593934 0.180042 0.08786767 -0.002439379 0.18004 0.05768889 -0.005367338 0.02201294 0.05559158 -0.005488693 0.01148068 0.0534079 -0.005412817 0.02201288 0.05699837 -0.005334198 0.02648872 0.0602101 -0.005131781 0.04282975 0.0531643 -0.00516951 0.03991621 0.05115449 -0.005340933 0.02798056 0.04693675 -0.005308389 0.02798056 0.07693928 -9.59593e-4 0.17392 0.08160966 -9.3382e-4 0.180038 0.08077538 0 0.180037 0.05825877 -0.004872798 0.06046634 0.06840002 0.00286895 0.1371802 0.07710272 0.002859473 0.1550281 0.03978812 0.001986384 0.08448016 0.07696354 -0.002168059 0.1648428 0.08208668 -0.00231868 0.1739386 0.08077096 -0.002097308 0.173923 0.04646319 0.003898859 0.07441025 0.05587518 0.003842949 0.09363061 0.05319821 -0.004583537 0.06752073 0.05746024 -0.004534006 0.0753569 0.06167083 0.004012107 0.09959262 0.06114989 0.004176855 0.09363043 0.06920146 0.004042923 0.1105381 0.07561182 0.004038393 0.1191449 0.103776 0.003044426 0.1859419 0.10495 0.003080427 0.185946 0.09807777 0.003190159 0.1800529 0.08321338 0.003934085 0.1315722 0.0515207 0.004331171 0.07306402 0.0497772 0.004210054 0.07338118 0.1026 0.002999544 0.185939 0.09680426 0.003143012 0.180051 0.08634269 0.003958165 0.1316111 0.08477795 0.003950238 0.1315914 0.05439609 0.00439769 0.07572889 0.05347532 0.00457406 0.0682668 0.04502785 0.004157364 0.06602883 0.03090465 0.00307995 0.05489557 0.111931 0.003141641 0.18597 0.1130869 0.003130853 0.185974 0.106962 0.0032925 0.180069 0.0448687 0.003702819 0.07505029 0.103935 0.003478288 0.162921 0.1053365 0.003450155 0.1629475 0.09260231 0.003918528 0.1316957 0.1053145 0.003477394 0.1583405 0.106742 0.003439366 0.158374 0.09573221 0.003861188 0.1317408 0.1004264 0.003736019 0.1318106 0.09886193 0.00378257 0.1317871 0.108169 0.003397047 0.1584075 0.1051197 0.003570377 0.1318821 0.1035553 0.003629684 0.1318582 0.1019909 0.003684937 0.1318341 0.1153035 0.003128647 0.1585775 0.1138765 0.003189146 0.1585435 0.106684 0.003507375 0.1319061 0.1208631 0.002886176 0.1740077 0.1167305 0.003065109 0.158612 0.109812 0.003371 0.131954 0.1082478 0.003440856 0.1319301 0.04810482 0.005030453 0.04290032 0.04750108 0.005390644 0.02350479 0.06016397 0.004897296 0.06018668 0.1042205 0.003400444 0.03578156 0.1030598 0.003504097 0.04364657 0.05959069 0.005287528 0.02798062 0.05748164 0.00531423 0.02798062 0.06380856 0.00521022 0.02798062 0.06840687 0.005013823 0.0429002 0.07255589 0.004880309 0.04879379 0.0663765 0.005054652 0.0429002 0.06169968 0.005252659 0.02798062 0.0696153 0.005107223 0.01055836 0.0674749 0.005183339 0.01065695 0.1031122 0.003592967 0.06975728 0.1087025 0.003355801 0.09362846 0.09550261 0.003942668 0.04588449 0.08460038 0.004437685 0.009926259 0.08325374 0.004523038 0.05070048 0.08515667 0.004443466 0.05103969 0.1069078 0.003303706 0.05137979 0.1152112 0.002998232 0.09955793 0.06434607 0.00508821 0.0429002 0.1077182 0.003342747 0.0734874 0.1135502 0.003099501 0.0995869 0.1241272 0.002665877 0.1512902 0.1185197 0.002916038 0.1291372 0.125971 0.002596318 0.161988 0.1249495 0.002658307 0.1633392 0.128881 0.002472519 0.174107 0.1185726 0.002873837 0.119061 0.1407929 0.001852333 0.1920544 0.1365721 0.002110362 0.1860748 0.1342721 0.0022583 0.1860657 0.1309249 0.002404212 0.180122 0.139771 0.001833736 0.180139 0.137567 0.001931428 0.174143 0.1364539 0.00200802 0.1744295 0.1428449 0.001707494 0.1920613 0.1388859 0.001954197 0.1860806 0.142942 0.001607537 0.180145 0.1402375 0.001748561 0.1741524 0.141039 0.001744687 0.180142 0.153849 8.1239e-4 0.203877 0.149063 0.001238882 0.198052 0.148192 0.001302182 0.198051 0.1442425 0.001460254 0.174166 0.145484 0.00141865 0.180149 0.150811 0.001108407 0.198055 0.155809 6.83062e-4 0.203926 0.151688 0.001041233 0.198056 0.146912 0.001258492 0.1741735 0.1480315 0.001222193 0.1801519 0.1556034 7.28091e-4 0.1980808 0.1586968 4.75178e-4 0.2039168 0.1505849 0.001018524 0.180155 0.1520425 8.7466e-4 0.1771705 0.14958 0.00104922 0.1741794 0.1573446 5.82406e-4 0.1980735 0.159967 3.76368e-4 0.2040035 0.156679 6.00638e-4 0.1920925 0.154519 7.86626e-4 0.192089 0.1482565 0.001257777 0.1861104 0.1458666 0.001444756 0.1860986 0.1592569 4.16992e-4 0.1980634 0.1588635 4.06921e-4 0.1920945 0.1533505 7.65975e-4 0.177172 0.154659 6.5512e-4 0.1771734 0.161072 2.54752e-4 0.198064 0.1622511 1.96337e-4 0.2066277 0.1584867 2.01706e-4 0.1642115 0.1605229 7.20172e-5 0.170453 0.1630654 4.91919e-5 0.1951863 0.162443 1.29779e-4 0.198064 0.1635299 7.04707e-5 0.203755 0.163571 6.5587e-5 0.2035599 0.1590614 3.40703e-4 0.1861275 0.1624215 5.72386e-5 0.1889162 0.1595805 2.43898e-4 0.1801609 0.1615323 6.61667e-5 0.1802683 0.163639 5.69831e-5 0.203162 0.163666 5.33374e-5 0.2029629 0.163716 4.5026e-5 0.202368 0.163682 4.02175e-5 0.201182 0.163713 4.007e-5 0.201577 0.163721 4.06527e-5 0.201774 0.1637 3.9925e-5 0.201379 0.16276 1.4126e-4 0.204029 0.1632519 1.00985e-4 0.204707 0.163704 4.73589e-5 0.202566 0.163687 5.01294e-5 0.202764 0.163723 4.31306e-5 0.20217 0.163724 4.16729e-5 0.201972 0.163607 6.10662e-5 0.20336 0.163378 8.75461e-5 0.20433 0.163433 8.14431e-5 0.20414 0.163317 9.40602e-5 0.204519 0.15891 2.53342e-4 0.1741924 0.1618379 2.2193e-4 0.2040235 0.162944 1.32172e-4 0.205444 0.163028 1.23816e-4 0.205262 0.157278 4.26089e-4 0.1771755 0.1571074 3.25495e-4 0.1641167 0.162666 1.59092e-4 0.205977 0.159892 7.38819e-5 0.1643069 0.1559685 5.41857e-4 0.177175 0.1515493 0.001035511 0.1920989 0.15345 9.0289e-4 0.198058 0.157432 5.69015e-4 0.2039242 0.154335 8.31727e-4 0.198059 0.152568 9.72739e-4 0.1980569 0.156457 6.38234e-4 0.20394 0.142241 0.001606762 0.17416 0.149936 0.001174271 0.198054 0.154505 7.70123e-4 0.203894 0.155158 7.2702e-4 0.2039099 0.1448951 0.00155723 0.1920697 0.1372399 0.002006411 0.180135 0.135975 0.002089917 0.180132 0.134712 0.002171516 0.18013 0.139411 0.00194633 0.192045 0.129664 0.002477467 0.180119 0.1269808 0.002578377 0.1739723 0.132187 0.002328753 0.1801249 0.0747683 0.004819214 0.04918813 0.06591725 0.00516057 0.02798068 0.0738995 0.004939198 0.01036894 0.08464461 0.004468262 0.0429005 0.07855665 0.004713177 0.04290026 0.07174104 0.00502634 0.01046323 0.07652705 0.004785001 0.04290026 0.1018725 0.003589212 0.04737651 0.105852 0.003341734 0.04524785 0.0833773 0.004501283 0.06102329 0.08217382 0.004525721 0.0677759 0.08611178 0.004386305 0.0684778 0.06251347 0.00507003 0.0470041 0.116846 0.002962172 0.114423 0.115195 0.003058016 0.114416 0.1063872 0.003507018 0.1055187 0.1061944 0.003525257 0.1114385 0.05881118 0.005191564 0.03842425 0.11114 0.003228425 0.09660202 0.09981584 0.003560662 0.01022565 0.05326342 0.00534141 0.02798056 0.09546589 0.003826379 0.009497165 0.1413308 4.08072e-4 0.01474338 0.1445519 1.15876e-4 0.01509386 0.144141 1.16999e-4 0.01109975 0.141622 3.12258e-4 0.007244884 0.1437309 1.18122e-4 0.007105708 0.1278124 0.001557171 0.01327228 0.1322819 0.001190662 0.01375865 0.128962 0.001422643 0.007993876 0.126851 0.001595795 0.008106052 0.124739 0.001766085 0.008215069 0.124588 0.001813113 0.01292145 0.1184 0.002260208 0.008524894 0.116287 0.002419054 0.008623003 0.1144854 0.002573192 0.01182204 0.114173 0.00257492 0.008718848 0.1120589 0.002727866 0.008812725 0.109944 0.002877891 0.008904635 0.1099498 0.002892971 0.01132851 0.107829 0.003025054 0.008994936 0.105714 0.003169357 0.009083569 0.106613 0.003119647 0.01096534 0.103599 0.003310799 0.00917083 0.1034076 0.003331482 0.0106166 0.101484 0.003449261 0.009256958 0.09331375 0.003954827 0.009582042 0.05115437 0.005340993 0.02798056 0.1160656 0.003060042 0.1320483 0.1145021 0.003142297 0.1320251 0.112939 0.003221631 0.1320016 0.1181565 0.00299865 0.158646 0.1195825 0.00292927 0.15868 0.04279708 0.00508809 0.03394824 0.05860078 0.004714727 0.06895768 0.05722147 0.004759609 0.0653603 0.05524176 0.00471723 0.06500738 0.11245 0.003246426 0.1585094 0.07985353 -0.004673242 0.01018488 0.07770913 -0.004772901 0.01028954 0.109596 0.003350615 0.1584415 0.1155103 0.003107905 0.1739699 0.111023 0.003300309 0.158475 0.04404735 0.004898011 0.04290032 0.05154162 0.004777669 0.05782109 0.07435077 -0.004897713 0.02798074 0.09416723 0.003892719 0.131718 0.09729701 0.003824412 0.1317636 0.06104999 -0.005328238 0.01902908 0.05971568 -0.005406975 0.01123845 0.06385022 -0.005243718 0.02240544 0.09103733 0.003938317 0.1316738 0.105696 0.003298163 0.180066 0.110774 0.003147125 0.185965 0.08790749 0.003958523 0.1316316 0.07398223 -0.002496302 0.1543438 0.08947241 0.003951728 0.1316524 0.06169742 -0.005199134 0.03448438 0.05126744 -0.005422055 0.02201288 0.05956 -0.005091428 0.04647767 0.05611908 -0.004844665 0.06008493 0.05553203 -0.004761934 0.06337893 0.03642457 0.003641307 0.05890423 0.06069242 0.004329204 0.087668 0.04293853 -0.004936158 0.03991609 0.06156772 -0.005014121 0.05231064 0.06080913 -0.004955828 0.05656653 0.09144604 0.003171145 0.173978 0.09552967 0.003085613 0.180049 0.0799576 0.002586483 0.1654769 0.07869446 0.002392411 0.1657254 0.05994379 0.003903388 0.09959262 0.04398155 -0.004387497 0.05842906 0.02877718 -0.005067408 0.01342481 0.0382623 -1.53905e-7 0.08745706 0.03887951 -0.001290738 0.08622747 0.08015805 0.003659784 0.1401522 0.02868038 -0.002671957 0.05417776 0.03376442 -0.00206685 0.07044899 0.09786158 0.002709567 0.185928 0.09042251 0.002726078 0.180043 0.09666895 0.002601802 0.185925 0.0891447 0.002593755 0.180042 0.0954737 0.002475559 0.185923 0.08341437 0.002506673 0.173927 0.08786737 0.0024392 0.18004 0.03110831 -0.003771185 0.04588413 0.08659148 0.002258479 0.18004 0.0820896 0.002320945 0.173925 0.05802756 -0.004629373 0.07217359 0.05524176 -0.004717171 0.06500738 0.05722135 -0.00475955 0.0653603 0.093077 -0.00215584 0.18592 0.09187787 -0.001948118 0.185919 0.08659178 -0.002258598 0.18004 0.06103897 -0.005082726 0.04674124 0.06251347 -0.005069613 0.0470041 0.06174874 -0.002473592 0.1285052 0.105667 -0.002460241 0.191916 0.1045989 -0.00236231 0.191914 0.09786236 -0.002710282 0.185928 0.06374907 -0.005301535 0.01101195 0.06477111 -0.005246937 0.01723837 0.08784967 -0.004161119 0.111383 0.08790755 -0.003958582 0.1316306 0.08634275 -0.003958284 0.1316103 0.108884 -0.003416895 0.1280159 0.1097999 -0.003371894 0.1319269 0.109926 -0.003374159 0.133927 0.1143593 -0.003166377 0.1437633 0.08781254 -0.004310548 0.07572692 0.06590175 -0.005235195 0.01089489 0.08611178 -0.004386186 0.0684778 0.08335369 -0.00450164 0.06115537 0.08002316 -0.002584218 0.1656488 0.07588046 -0.001872599 0.1654718 0.06801307 -0.005165398 0.01078236 0.06641459 -0.005218565 0.01086735 0.09068387 -0.001686751 0.185918 0.08531945 -0.002040982 0.180039 0.06502479 -0.005231201 0.01866501 0.06576013 -0.005227208 0.01453894 0.07326805 -1.30527e-7 0.1674692 0.06427371 -0.005230009 0.022879 0.0635358 -0.005222141 0.02701961 0.0756855 0.001875579 0.1650152 0.07681697 0.002171099 0.164491 0.06688272 0.0026564 0.1371715 0.08280515 0.001429378 0.180038 0.08949899 0.00136429 0.185917 0.09068357 0.001686573 0.185918 0.03281933 -0.003409624 0.05483704 0.04006296 -0.002899885 0.07674849 0.05146586 -0.004333019 0.07291692 0.03855115 0.00129342 0.08547163 0.04455053 0.002812802 0.08745241 0.04461318 0.003149449 0.08333504 0.07517683 -0.001506984 0.1669289 0.05917966 -0.004790067 0.06570929 0.05860078 -0.004714727 0.06895768 0.08836311 8.9122e-4 0.185916 0.08160948 9.33714e-4 0.180038 0.09905099 0.002801299 0.18593 0.10673 0.002542614 0.191919 0.107789 0.002613246 0.1919209 0.06908112 -0.005024194 0.03842437 0.07031494 -0.004935503 0.0483945 0.08757531 -0.004266619 0.09362953 0.06362557 -0.005096673 0.04313921 0.06182765 -0.005178749 0.0366038 0.0812748 -0.00453186 0.07281947 0.08182287 -0.004528224 0.06974488 0.1069427 -0.003451704 0.09362864 0.110968 -0.003331303 0.139838 0.109773 -0.003373503 0.1377996 0.109822 -0.003368556 0.143609 0.06616878 -0.005053341 0.04359245 0.09566301 -0.003987014 0.08468252 0.08370214 -0.004504561 0.05078041 0.07426792 -0.004832923 0.04909902 0.07470619 -0.004864513 0.03655946 0.07297015 -0.004917621 0.03767842 0.0880385 -0.004255056 0.009795963 0.06281548 -0.005208313 0.03106093 0.06745409 -0.004995465 0.04788458 0.06546688 -0.005031526 0.04753035 0.07855665 -0.004713058 0.04290026 0.0840103 -0.00446856 0.009985446 0.08583146 -0.004397749 0.02031391 0.08181166 -0.004578173 0.01009041 0.08058619 -0.004636108 0.04290038 0.1026189 -0.003672182 0.09248745 0.1031122 -0.003592789 0.06975728 0.107861 -0.003443896 0.111443 0.1067938 -0.003502488 0.1161643 0.108297 -0.003438413 0.126079 0.1078758 -0.003457605 0.1222969 0.09285932 -0.004094183 0.0936293 0.09400105 -0.00405395 0.0913909 0.1275629 -0.002322673 0.19801 0.1036593 -0.003630042 0.09838318 0.136413 -0.001527845 0.203307 0.1267 -0.002334356 0.198009 0.08108377 -0.003097951 0.1578919 0.08606523 -0.002799153 0.1739504 0.0796656 -0.002974689 0.1578764 0.1354377 -0.001540243 0.2032418 0.111603 -0.003283739 0.155475 0.125835 -0.002342224 0.198007 0.100238 -0.002880156 0.1859329 0.09553027 -0.003086149 0.180049 0.101422 -0.002945959 0.185936 0.08872866 -0.003014087 0.1739609 0.08739513 -0.002915203 0.1739547 0.11618 -0.003115773 0.169393 0.08534801 -0.003367125 0.157948 0.08677148 -0.00342983 0.1579695 0.115137 -0.003159046 0.163482 0.110945 -0.002765119 0.191929 0.104952 -0.003082215 0.185946 0.111989 -0.00279802 0.191933 0.09680497 -0.003143608 0.180051 0.09273391 -0.003228068 0.1739822 0.118264 -0.003029048 0.181215 0.119988 -0.002974212 0.186002 0.119307 -0.002985537 0.187125 0.138424 -0.001497983 0.203372 0.130145 -0.002267181 0.198015 0.1006219 -0.00325787 0.180057 0.101893 -0.003278911 0.180059 0.106122 -0.00311011 0.185949 0.156532 -5.01925e-4 0.209958 0.1342131 -0.001534342 0.2032453 0.124969 -0.002346158 0.198006 0.122362 -0.002331435 0.198001 0.123233 -0.002341091 0.1980029 0.1328509 -0.001522421 0.2032071 0.10729 -0.003130257 0.185953 0.103162 -0.003292441 0.180061 0.108455 -0.00314325 0.185957 0.114064 -0.002841711 0.1919389 0.115097 -0.002853572 0.191943 0.09039473 -0.004122793 0.009693384 0.06082481 0.004957199 0.05647867 0.06149524 0.005008399 0.05271732 0.1189945 0.002915799 0.1379676 0.04764294 0.004621028 0.05782109 0.05802756 0.004629373 0.07217359 0.05743902 0.00480479 0.06336754 0.05953055 0.004831075 0.06374025 0.03864639 0.004921257 0.03394824 0.07449716 0.004851281 0.04290026 0.07816386 0.004752635 0.01018834 0.09751468 0.003833115 0.04588454 0.09814184 0.003881275 0.09362888 0.09931874 0.003827631 0.09139072 0.09179204 0.004155516 0.06975775 0.08990466 0.004235804 0.06975787 0.09045505 0.004184067 0.0913909 0.09285926 0.004094183 0.0936293 0.08576077 0.004395544 0.07044678 0.139514 5.05054e-4 0.00737971 0.163484 7.57513e-5 0.203948 0.137404 6.95626e-4 0.007510304 0.1368722 8.0058e-4 0.01425808 0.1557427 4.46266e-4 0.1640239 0.163182 1.08237e-4 0.204894 0.163108 1.15838e-4 0.205079 0.135295 8.83088e-4 0.007636845 0.154244 5.7588e-4 0.1639209 0.1541475 6.23232e-4 0.1682115 0.1572329 5.05192e-4 0.1861259 0.162855 1.40904e-4 0.2056249 0.162762 1.50013e-4 0.205804 0.133185 0.001066625 0.007759451 0.152832 6.96282e-4 0.163825 0.1554175 6.64061e-4 0.186124 0.16236 1.86861e-4 0.206471 0.162567 1.68162e-4 0.206145 0.162465 1.77418e-4 0.20631 0.131074 0.001246392 0.007878422 0.151419 8.14645e-4 0.1637279 0.151412 8.5369e-4 0.168197 0.162138 2.06309e-4 0.206782 0.150007 9.30969e-4 0.163632 0.1530129 8.68913e-4 0.1861209 0.1618 2.34562e-4 0.207208 0.161913 2.25259e-4 0.207072 0.162025 2.15932e-4 0.20693 0.1486036 0.001044929 0.1635356 0.161568 2.53097e-4 0.207467 0.161685 2.43842e-4 0.20734 0.1469816 0.001173794 0.1634253 0.1506265 0.001066684 0.186116 0.16145 2.62327e-4 0.207588 0.161155 2.84462e-4 0.207864 0.161316 2.72549e-4 0.207718 0.1443638 0.001375257 0.1632456 0.160983 2.97033e-4 0.208014 0.1427059 0.001499831 0.1631329 0.160799 3.10262e-4 0.208168 0.1490583 0.001236617 0.1920875 0.160604 3.2415e-4 0.208325 0.1401136 0.001688063 0.1629549 0.1469878 0.001398563 0.1920784 0.160398 3.38696e-4 0.208485 0.1384893 0.00180298 0.1628445 0.1435164 0.001622319 0.1860975 0.1601949 3.52669e-4 0.208635 0.160015 3.64429e-4 0.208756 0.1358661 0.001982212 0.1626645 0.1412022 0.001791179 0.1860883 0.159837 3.75798e-4 0.208869 0.153192 8.5383e-4 0.203859 0.134261 0.002088904 0.1625554 0.159659 3.86776e-4 0.208973 0.152532 8.94432e-4 0.20384 0.147323 0.00136429 0.19805 0.15187 9.34179e-4 0.203821 0.159483 3.97362e-4 0.209069 0.146456 0.001425027 0.1980479 0.1316381 0.002256929 0.1623755 0.1336229 0.002188384 0.174162 0.145591 0.001484453 0.198047 0.151206 9.73054e-4 0.203801 0.159309 4.07558e-4 0.209156 0.1302221 0.002344906 0.1622794 0.1505399 0.001011013 0.203781 0.144727 0.001542508 0.198045 0.143864 0.001599192 0.198043 0.1589574 4.26357e-4 0.2093185 0.07604551 0.004847645 0.01027721 0.1281529 0.002469956 0.1621375 0.1309509 0.002351999 0.1741445 0.133449 0.002251207 0.180127 0.149873 0.001048088 0.20376 0.09114253 0.004080772 0.009667634 0.149205 0.001084148 0.203739 0.1377645 0.002054691 0.1920407 0.143003 0.001654386 0.198042 0.08895808 0.004204094 0.009753644 0.1034597 0.003552258 0.06304281 0.142143 0.00170803 0.19804 0.148535 0.001119256 0.2037169 0.158774 4.35739e-4 0.209397 0.0867629 0.004323959 0.00984019 0.1128605 0.003180146 0.111458 0.136368 0.002142727 0.192032 0.132576 0.002362191 0.186057 0.141284 0.001760184 0.1980389 0.158594 4.44335e-4 0.209469 0.101226 0.003695726 0.06975734 0.1029925 0.003638267 0.08467727 0.1069425 0.003451764 0.09362864 0.111194 0.003271102 0.1114529 0.121009 0.002857208 0.1587135 0.1224344 0.002782404 0.1587465 0.128403 0.002548396 0.1801159 0.1308299 0.00246483 0.1860517 0.140425 0.001810669 0.198037 0.147864 0.001153349 0.2036949 0.1255019 0.002658009 0.1740476 0.1347206 0.002242207 0.1920288 0.147192 0.00118637 0.203673 0.08244645 0.004547357 0.01001292 0.09641528 0.003921508 0.05782067 0.09913313 0.003818213 0.07647222 0.1095275 0.003359019 0.111448 0.127143 0.002617001 0.180114 0.125883 0.002683162 0.180111 0.1584129 4.52533e-4 0.209536 0.146519 0.001218318 0.2036499 0.139567 0.001859486 0.198035 0.08029854 0.0046525 0.01010024 0.09297174 0.00408554 0.05185252 0.123541 0.002758085 0.1740307 0.133338 0.002321302 0.192019 0.1291379 0.002558767 0.186042 0.13871 0.001906514 0.198033 0.145846 0.001249074 0.203627 0.158231 4.60334e-4 0.209598 0.08946496 0.004249036 0.04588443 0.09556621 0.003982841 0.06975758 0.1016629 0.003719985 0.09362882 0.1113756 0.003297865 0.131978 0.1221998 0.002823591 0.1740155 0.1273932 0.002650797 0.186037 0.1317014 0.002409994 0.1920158 0.137854 0.001951813 0.198032 0.124623 0.00274676 0.180108 0.158049 4.67639e-4 0.209655 0.08589512 0.004411637 0.03991645 0.09212243 0.004138886 0.06378912 0.1045275 0.003603458 0.1114335 0.123364 0.002807736 0.180105 0.122104 0.002866029 0.180102 0.1451719 0.001278698 0.203604 0.136997 0.001995205 0.1980299 0.144497 0.00130707 0.203581 0.09638112 0.003956258 0.093629 0.09400099 0.004054009 0.0913909 0.1028605 0.003678143 0.111428 0.1195279 0.002945899 0.1740015 0.1297145 0.002509415 0.1920057 0.1251184 0.002761483 0.1860258 0.136141 0.00203669 0.198028 0.143822 0.00133419 0.203557 0.157864 4.73998e-4 0.209709 0.0843411 0.004472851 0.05561554 0.101193 0.003749191 0.111423 0.1181856 0.00300312 0.1739827 0.120844 0.002921521 0.180099 0.135285 0.002076148 0.198026 0.157678 4.79786e-4 0.209758 0.08801704 0.0043118 0.06975775 0.09952545 0.003816604 0.1114185 0.119584 0.002974092 0.180096 0.1228297 0.002861976 0.1860164 0.1168465 0.003057181 0.1739737 0.118324 0.003023564 0.180093 0.143147 0.001359999 0.203534 0.127708 0.002599954 0.1919964 0.134429 0.00211358 0.198024 0.142472 0.001384437 0.2035109 0.08108258 0.004609227 0.05031347 0.09785795 0.003879964 0.111413 0.1170639 0.003069698 0.180091 0.133572 0.002148807 0.198023 0.1415343 0.001418232 0.2034535 0.157491 4.85003e-4 0.209803 0.06535899 0.005252838 0.01075726 0.07804024 0.004718005 0.04977124 0.08415889 0.00445199 0.07016122 0.09619027 0.003939032 0.1114079 0.1141645 0.003155589 0.17395 0.1257029 0.002679169 0.1919882 0.121129 0.002928316 0.186008 0.132716 0.002181649 0.1980209 0.157303 4.89649e-4 0.209843 0.06322497 0.005316853 0.01086175 0.08182287 0.004528522 0.06974488 0.08868181 0.004242062 0.09139102 0.08757525 0.004266679 0.09362953 0.09452235 0.00399363 0.111403 0.1128219 0.003199517 0.1739302 0.115803 0.003112316 0.180088 0.119983 0.002969086 0.186003 0.131858 0.002211987 0.198019 0.140447 0.00144875 0.203441 0.06124031 0.005370736 0.01096212 0.08126276 0.004532039 0.07288706 0.08061796 0.004531741 0.07650512 0.08275812 0.004371523 0.09512174 0.09285438 0.0040434 0.1113985 0.08784949 0.004161059 0.111384 0.08951789 0.004127442 0.1113885 0.1114777 0.003239631 0.1739113 0.114542 0.003151178 0.180085 0.1188369 0.003006279 0.185998 0.1132799 0.003186047 0.180082 0.157114 4.93725e-4 0.209878 0.139773 0.00146687 0.203418 0.123703 0.002745747 0.1919779 0.131 0.002239644 0.198017 0.07994574 0.004526257 0.0802769 0.08940351 0.004163146 0.1054933 0.1101312 0.003275871 0.1738865 0.11769 0.003039658 0.185993 0.112018 0.003216803 0.180079 0.130142 0.002264499 0.198016 0.1388441 0.001491844 0.2033613 0.156924 4.97209e-4 0.209909 0.05913668 0.0054214 0.01107209 0.06994968 0.004943072 0.04832935 0.07954186 0.004520595 0.08254319 0.116541 0.003069102 0.185988 0.1216914 0.002798497 0.1919691 0.108813 0.003306627 0.174013 0.1292819 0.002286374 0.198014 0.156729 4.99886e-4 0.209936 0.05701845 0.005465209 0.01118695 0.07695341 0.004568576 0.08208185 0.0828436 0.004224181 0.11137 0.07920676 0.004309117 0.1054791 0.1025332 0.003501355 0.1628945 0.110755 0.003243088 0.180077 0.107474 0.003333568 0.1740069 0.115392 0.003094255 0.185983 0.128422 0.00230515 0.1980119 0.137755 0.001509606 0.203351 0.05490046 0.005501389 0.01130646 0.06562149 0.005026459 0.04755795 0.07499867 0.004596829 0.08173352 0.08618092 0.004188656 0.111379 0.1011318 0.003519058 0.1628684 0.109492 0.003264665 0.180074 0.106135 0.003355681 0.174001 0.11424 0.003114938 0.185979 0.1196654 0.002835631 0.1919605 0.1270217 0.002328932 0.1980066 0.156532 5.01922e-4 0.209958 0.1368853 0.001520872 0.2033339 0.05278247 0.005529582 0.01143068 0.0730471 0.004617571 0.08138567 0.08451235 0.004209816 0.111374 0.103458 0.003384113 0.1739889 0.09973019 0.003531098 0.1628429 0.09832894 0.003537118 0.1628187 0.108227 0.003281235 0.1800709 0.104797 0.003372669 0.173995 0.156333 5.03316e-4 0.209975 0.05066478 0.005549132 0.01155996 0.05340778 0.005412876 0.02201288 0.07109224 0.004630625 0.08103728 0.09951192 0.003381252 0.1740783 0.103161 0.003291368 0.180061 0.104429 0.003297924 0.180064 0.118173 0.002851128 0.191954 0.1252959 0.002343952 0.1980049 0.1354841 0.001535177 0.2032732 0.1561329 5.04069e-4 0.2099879 0.04854738 0.005559742 0.01169466 0.06190526 0.005035638 0.05041658 0.06914156 0.004635095 0.0806896 0.07580745 0.004300117 0.1054748 0.07410782 0.004282474 0.1054729 0.114062 0.002838969 0.1919389 0.10612 0.003108143 0.185949 0.113026 0.002820909 0.191936 0.108452 0.003140807 0.185957 0.101892 0.003277957 0.180059 0.09532481 0.003599047 0.1581234 0.102119 0.003389894 0.173983 0.1235615 0.002342581 0.1980027 0.11715 0.002856194 0.19195 0.15593 5.04181e-4 0.209996 0.04643028 0.005560755 0.01183485 0.067191 0.004630625 0.08034199 0.07750707 0.00430876 0.105477 0.09935015 0.003227889 0.180055 0.1008675 0.003387451 0.1741191 0.09389829 0.003591835 0.1580955 0.109614 0.003147006 0.185961 0.116123 0.002856075 0.191947 0.134009 0.001538574 0.2032088 0.1557245 5.03833e-4 0.21 0.04431354 0.005551636 0.01198095 0.06524211 0.004616618 0.07999461 0.09247201 0.003577113 0.158068 0.1006219 0.003256976 0.180057 0.107288 0.003128051 0.185953 0.115094 0.002850532 0.191943 0.04219734 0.00553137 0.01213335 0.04641407 0.005328536 0.02648872 0.06329315 0.00459218 0.0796473 0.09816163 0.003367841 0.1740491 0.09104615 0.003554224 0.158042 0.12236 0.002330124 0.198001 0.133091 0.001525759 0.203209 0.1553957 5.01996e-4 0.21 0.04008179 0.005499005 0.01229226 0.04429769 0.005294382 0.02648866 0.06200009 0.004569709 0.07941681 0.07031697 0.004331767 0.0995928 0.07719534 0.00407648 0.1190374 0.09681493 0.003346562 0.1740282 0.0896207 0.003522455 0.1580165 0.121487 0.002315282 0.198 0.1321574 0.001512885 0.2031776 0.1550609 4.97199e-4 0.21 0.03796708 0.005453467 0.0124582 0.03948968 0.005345702 0.01902896 0.05559265 0.004771649 0.06303846 0.05917966 0.004790127 0.06570929 0.06025815 0.004531383 0.07910639 0.06427735 0.004446208 0.0876677 0.06858688 0.004293024 0.09959292 0.09547138 0.003316938 0.1740114 0.0881958 0.003481209 0.157993 0.111986 0.002795815 0.191933 0.119735 0.002267837 0.197997 0.13112 0.00148487 0.203158 0.120612 0.002294659 0.197999 0.03585314 0.005393683 0.01263117 0.03733468 0.005283057 0.01902896 0.05855768 0.004484415 0.0788033 0.06139016 0.004432141 0.08468365 0.06521809 0.004299402 0.09512257 0.07401949 0.003989756 0.1192286 0.09412884 0.003278255 0.1740001 0.08677148 0.00342977 0.15797 0.118856 0.002234339 0.197996 0.110943 0.002763211 0.1919299 0.03374046 0.005318701 0.0128113 0.03518015 0.005204975 0.01902896 0.02451002 0.004511475 0.01924657 0.05746024 0.004534006 0.0753569 0.05689865 0.004428625 0.0785076 0.08108365 0.003097891 0.1578925 0.08250373 0.003202795 0.1579095 0.09278708 0.003230035 0.1739872 0.08534789 0.003367066 0.1579484 0.1179749 0.00219357 0.197995 0.130468 0.001462996 0.203143 0.109896 0.002722442 0.191927 0.1547349 4.891e-4 0.21 0.03162896 0.005227088 0.01299887 0.02951908 0.005116939 0.01319408 0.03302645 0.005109906 0.01902896 0.02741116 0.004985868 0.01339715 0.03106003 0.004989147 0.01952928 0.07085114 0.003856122 0.1194236 0.08392524 0.003291904 0.1579279 0.09297746 0.002935111 0.180046 0.100237 0.002879142 0.1859329 0.09425395 0.003016769 0.180047 0.10142 0.002944827 0.185936 0.108845 0.002672791 0.191924 0.129819 0.001436233 0.203128 0.1543544 4.75041e-4 0.21 0.01677745 0.003874182 0.01454806 0.02014416 0.004039108 0.01903688 0.01854056 0.004126131 0.01434308 0.02890658 0.004854261 0.01951301 0.00692898 1.57392e-4 0.01579898 0.006933748 -1.81767e-4 0.01579636 0.01169741 0.002366602 0.01903623 0.009708583 0.001546084 0.01902943 0.06927412 0.003768682 0.119532 0.09010732 0.003100514 0.1739714 0.117091 0.002144634 0.1979939 0.129173 0.001404225 0.203114 0.0256319 0.004857063 0.01357489 0.02670794 0.004696369 0.01938837 0.03174984 0.002619922 0.06141567 0.06771683 0.003664672 0.119688 0.08876979 0.00301671 0.1739644 0.105666 0.002459406 0.191916 0.09170019 0.002839028 0.1800439 0.116205 0.002086639 0.197993 0.12853 0.001366198 0.203101 0.1540548 4.59305e-4 0.21 0.02385467 0.004709422 0.01375848 0.02208 0.004540205 0.0139479 0.00774157 0.001218795 0.01569527 0.007483124 9.9829e-4 0.01573008 0.03034961 0.0034644 0.04886847 0.00832498 -1.73484e-7 0.01902872 0.06631606 0.00353825 0.1202355 0.08743268 0.002918064 0.1739582 0.07966548 0.002974629 0.1578764 0.127255 0.001268863 0.203079 0.1536076 4.27292e-4 0.2099999 0.127891 0.001321434 0.2030889 0.115317 0.002018332 0.197992 0.1538257 4.44429e-4 0.21 0.02030175 0.004345774 0.01414358 0.05649405 0.003625333 0.09959274 0.06482315 0.003394007 0.1205351 0.08609765 0.002802073 0.1739532 0.113535 0.001843988 0.19799 0.114427 0.001938045 0.197991 0.104598 0.002361595 0.191914 0.008015811 0.001418888 0.0156576 0.05431628 0.003214657 0.1026629 0.05787432 0.003370285 0.1072703 0.08476501 0.002666234 0.1739478 0.112641 0.001734137 0.19799 0.126624 0.001207292 0.203069 0.1035259 0.002247035 0.191913 0.1533944 4.07412e-4 0.2099999 0.01800864 0.003739893 0.01903343 0.008301556 0.001601815 0.01561784 0.007061958 -4.96618e-4 0.01577818 0.008917033 -0.001934409 0.01552075 0.009709119 -0.001546263 0.01902985 0.008614003 -0.001782238 0.01556187 0.08531916 0.002040863 0.180039 0.09307658 0.002155542 0.18592 0.09427595 0.002328097 0.185921 0.10245 0.002113163 0.191911 0.125997 0.001135349 0.203061 0.1531882 3.84626e-4 0.2099999 0.01502108 0.003582775 0.01475787 0.01588273 0.003379523 0.01903063 0.008898377 0.001923263 0.01553499 0.008596062 0.0017699 0.01557677 0.008032381 -0.001433551 0.0156427 0.008318781 -0.001615285 0.01560276 0.05216318 0.002986013 0.1015737 0.09921348 0.001530945 0.191907 0.100291 0.001768171 0.191908 0.0840556 0.001767039 0.180038 0.09187757 0.001947939 0.185919 0.101371 0.001956582 0.191909 0.111747 0.001605629 0.197989 0.125375 0.001051247 0.2030529 0.1529648 3.55582e-4 0.2099999 0.01327645 0.003231525 0.01497405 0.009844005 0.002296566 0.0154109 0.009523868 0.002184689 0.01545178 0.01377719 0.002925992 0.01903349 0.01154947 0.002804458 0.01519435 0.007260322 -7.7269e-4 0.01575058 0.007497787 -0.001015782 0.01571756 0.05357235 0.002637803 0.1089766 0.08077079 0.002097249 0.173923 0.110852 0.001451015 0.197989 0.124759 9.49963e-4 0.203047 0.152818 3.33046e-4 0.21 0.009208023 0.002061307 0.01549309 0.04849296 0.00234127 0.1008814 0.07388156 9.83895e-4 0.1668599 0.0781719 0.001468837 0.173921 0.07517576 0.001506984 0.1669267 0.0794633 0.001815915 0.173922 0.123558 6.65351e-4 0.203039 0.152501 2.69383e-4 0.21 0.124153 8.22559e-4 0.203042 0.109962 0.001256287 0.197988 0.152606 2.93221e-4 0.21 0.152712 3.14337e-4 0.21 0.007247209 7.53366e-4 0.01576077 0.009543836 -0.002193391 0.01543974 0.01169586 -0.00236696 0.01903098 0.04679447 0.001893818 0.1008103 0.05018478 0.001848936 0.1086936 0.109079 0.001016259 0.197988 0.108233 6.63856e-4 0.197988 0.0981428 0.001238405 0.191907 0.007051467 4.74925e-4 0.01578515 0.009227335 -0.002071201 0.01547986 0.0450682 0.001238286 0.1004944 0.04858189 0.001208305 0.1085733 0.08836328 -8.91335e-4 0.185916 0.08280539 -0.001429438 0.180038 0.07693916 9.59497e-4 0.17392 0.107641 0 0.197988 0.122993 4.34614e-4 0.203037 0.09711456 8.08981e-4 0.191906 0.152292 2.12614e-4 0.21 0.152396 2.42565e-4 0.21 0.007757246 -0.001234829 0.01568126 0.04402077 -1.6908e-7 0.1006327 0.04761034 0 0.1088232 0.07408607 -9.82556e-4 0.1673296 0.07608067 0 0.17392 0.0875687 0 0.185916 0.09639447 0 0.191906 0.122602 0 0.203036 0.152097 1.23414e-4 0.21 0.152191 1.75355e-4 0.21 0.009864449 -0.002304494 0.01540029 0.01316618 -0.003205239 0.01500284 0.0137763 -0.00292623 0.01902979 0.01150506 -0.002792239 0.01520168 0.0159173 -0.003378629 0.01911085 0.04525935 -0.001236855 0.1009339 0.04859071 -0.001208484 0.108593 0.09921365 -0.001531064 0.191907 0.09814298 -0.001238465 0.191907 0.08405578 -0.001767158 0.180038 0.08949917 -0.001364409 0.185917 0.0971148 -8.09093e-4 0.191906 0.108233 -6.63938e-4 0.197988 0.122993 -4.34646e-4 0.203037 0.1520169 -4.93683e-5 0.21 0.1520169 4.97867e-5 0.21 0.04675227 -0.001894116 0.1007131 0.05052077 -0.001844584 0.1094745 0.07817208 -0.001468896 0.173921 0.109079 -0.001016318 0.197988 0.123558 -6.65385e-4 0.203039 0.152191 -1.75129e-4 0.21 0.152096 -1.23097e-4 0.21 0.04283714 -0.002434551 0.08754843 0.04928195 -0.002328813 0.1027367 0.07946348 -0.001815915 0.173922 0.109962 -0.001256406 0.197988 0.124153 -8.22577e-4 0.203042 0.152396 -2.42397e-4 0.21 0.152292 -2.12479e-4 0.21 0.01484388 -0.003547906 0.01480948 0.01992946 -0.004297375 0.01426529 0.02163338 -0.004488945 0.01409327 0.01801532 -0.003739893 0.01904684 0.05018287 -0.002703547 0.1008979 0.124759 -9.50025e-4 0.203047 0.110853 -0.001451075 0.197989 0.111747 -0.001605808 0.197989 0.100291 -0.00176835 0.191908 0.1525 -2.69211e-4 0.21 0.01653319 -0.003833174 0.01462316 0.01826447 -0.004085004 0.01443827 0.0224775 -0.004290163 0.01950597 0.0454896 -0.003130018 0.0854575 0.05468279 -0.002930879 0.1076565 0.0954743 -0.002475976 0.185923 0.09042286 -0.002726316 0.180043 0.112642 -0.001734316 0.19799 0.125375 -0.001051247 0.2030529 0.101371 -0.001956939 0.191909 0.152711 -3.14326e-4 0.21 0.1526049 -2.93154e-4 0.21 0.04522746 -0.00342971 0.08043968 0.05416601 -0.003217637 0.1023087 0.08341449 -0.002506673 0.173927 0.09427648 -0.002328395 0.185921 0.10245 -0.00211358 0.191911 0.125997 -0.001135408 0.20306 0.152924 -3.49559e-4 0.21 0.152818 -3.32934e-4 0.21 0.03086417 -0.005183517 0.01324421 0.03293997 -0.005280733 0.0130704 0.02462321 -0.004508972 0.01951384 0.04576104 -0.00368005 0.07725805 0.05793213 -0.003368616 0.1074167 0.09170067 -0.002839326 0.1800439 0.09666979 -0.002602398 0.185925 0.1035259 -0.002247512 0.1919119 0.113535 -0.001844227 0.19799 0.126623 -0.001207351 0.203069 0.1530772 -3.7099e-4 0.21 0.02334028 -0.004657506 0.01392596 0.02659738 -0.004700899 0.01908504 0.04734337 -0.003874897 0.07661652 0.05649429 -0.003625392 0.09959274 0.09425455 -0.003017246 0.180047 0.09905195 -0.002802073 0.18593 0.114428 -0.001938402 0.197991 0.127255 -0.001268982 0.203079 0.1532848 -3.95923e-4 0.21 0.02504956 -0.004805564 0.01376336 0.02671456 -0.004931986 0.01360958 0.04764312 -0.004621028 0.05782109 0.04282885 -0.004220843 0.06043714 0.05587542 -0.003842949 0.09363061 0.06167107 -0.004012107 0.09959262 0.06921666 -0.003771781 0.1193451 0.06771433 -0.003665924 0.1196508 0.1067309 -0.002543628 0.191919 0.092978 -0.002935528 0.180046 0.115318 -0.002018749 0.197992 0.1278899 -0.001321554 0.2030889 0.1535114 -4.18857e-4 0.21 0.05763232 -0.003973066 0.09363055 0.0839253 -0.003291964 0.1579279 0.117092 -0.00214523 0.1979939 0.129172 -0.001404345 0.203114 0.12853 -0.001366317 0.203101 0.116206 -0.002087116 0.197993 0.153719 -4.36385e-4 0.2099999 0.07750725 -0.00430876 0.105477 0.09006363 -0.00309807 0.1739684 0.117976 -0.002194285 0.197995 0.107791 -0.002614498 0.1919209 0.1539346 -4.51835e-4 0.21 0.05664867 -0.00432384 0.08169853 0.06339913 -0.00410366 0.09959256 0.07074093 -0.003861248 0.119086 0.103778 -0.003045976 0.1859419 0.0980786 -0.003190815 0.1800529 0.0993511 -0.003228664 0.180055 0.09139662 -0.00316894 0.1739732 0.118857 -0.002235174 0.197996 0.129818 -0.001436412 0.203128 0.108846 -0.002674281 0.191924 0.1541514 -4.64722e-4 0.21 0.03503471 -0.005361258 0.01290059 0.05689865 -0.004428625 0.0785076 0.05855774 -0.004484355 0.0788033 0.0606926 -0.004329144 0.087668 0.06512784 -0.004180014 0.0995925 0.07237899 -0.003932833 0.1191221 0.102601 -0.003000915 0.185939 0.109898 -0.00272417 0.191926 0.1308743 -0.001477479 0.2031536 0.1544141 -4.775e-4 0.21 0.05126857 -0.004787325 0.05707502 0.06025815 -0.004531383 0.07910639 0.0624848 -0.004394114 0.08766794 0.06685727 -0.004242718 0.09959298 0.07402104 -0.003991305 0.1191696 0.0881958 -0.003481268 0.157992 0.09407144 -0.003276586 0.1739938 0.119737 -0.002268731 0.197997 0.03712278 -0.005426347 0.01273661 0.06139397 -0.004557609 0.07930874 0.07070934 -0.004217028 0.1054689 0.0896207 -0.003522515 0.1580165 0.0954082 -0.003315508 0.1740041 0.120614 -0.002295672 0.197999 0.1317729 -0.001502752 0.2031739 0.03916567 -0.005476534 0.01258105 0.06332087 -0.004592597 0.07965224 0.07240855 -0.004255056 0.1054709 0.09104615 -0.003554344 0.158041 0.09674888 -0.003345489 0.1740199 0.113028 -0.002823412 0.191936 0.1548429 -4.92399e-4 0.2099999 0.121489 -0.002316474 0.198 0.04116165 -0.005513012 0.01243364 0.06526958 -0.004616856 0.0799995 0.074108 -0.004282474 0.1054729 0.09247201 -0.003577232 0.158067 0.09808838 -0.003367066 0.1740381 0.04332184 -0.005539894 0.01227891 0.06005698 -0.004887223 0.0607869 0.06722211 -0.004630804 0.08034747 0.08090662 -0.004301786 0.1054815 0.07580763 -0.004300117 0.1054748 0.09389823 -0.003591954 0.1580945 0.09942913 -0.003380894 0.17406 0.1241019 -0.00234586 0.198004 0.1553298 -5.01378e-4 0.2099999 0.04528319 -0.005553722 0.01214247 0.06917512 -0.004635095 0.08069556 0.09532475 -0.003599166 0.1581225 0.1007693 -0.003387689 0.1740843 0.09832888 -0.003537178 0.1628177 0.10443 -0.003299117 0.180064 0.109617 -0.003149688 0.185961 0.116127 -0.002859473 0.191946 0.0473445 -0.00555849 0.012003 0.07112938 -0.004630446 0.08104389 0.07920694 -0.004309117 0.1054791 0.08947247 -0.003951847 0.1316518 0.102119 -0.003389954 0.173983 0.105697 -0.003299415 0.180066 0.110777 -0.003150045 0.185965 0.117153 -0.00285983 0.19195 0.1557247 -5.03718e-4 0.21 0.04940599 -0.005553841 0.01186728 0.0730825 -0.004617452 0.08139193 0.09973013 -0.003531157 0.1628425 0.103458 -0.003384172 0.1739889 0.106963 -0.003293871 0.180069 0.111935 -0.00314486 0.18597 0.1181769 -0.002855122 0.191954 0.15593 -5.0418e-4 0.209996 0.05146777 -0.00554037 0.01173496 0.06091779 -0.005166947 0.03885895 0.07495099 -0.004597425 0.081725 0.09260237 -0.003918647 0.1316947 0.09103739 -0.003938436 0.1316731 0.1011317 -0.003519177 0.1628677 0.104797 -0.003372669 0.173995 0.108229 -0.003282725 0.1800709 0.106136 -0.003355741 0.174 0.11309 -0.00313431 0.185974 0.119198 -0.002845644 0.191958 0.1561329 -5.04068e-4 0.2099879 0.05352956 -0.005518555 0.01160615 0.06075406 -0.005131006 0.04262745 0.07690638 -0.004569292 0.0820735 0.09416729 -0.003892838 0.1317171 0.1025332 -0.003501474 0.1628935 0.109493 -0.003266274 0.180074 0.115367 -0.003057181 0.18782 0.1170388 -0.003036499 0.1875253 0.1206782 -0.002824187 0.1919627 0.156334 -5.03317e-4 0.209975 0.06177777 -0.005355894 0.01112145 0.06243497 -0.005221009 0.03034615 0.07954186 -0.004520833 0.08254319 0.104874 -0.003469705 0.1613095 0.1024595 -0.003539681 0.1582739 0.107474 -0.003333628 0.174006 0.10541 -0.003417134 0.167565 0.113277 -0.003164112 0.175965 0.0576536 -0.005451381 0.01135808 0.06300967 -0.005233407 0.02712178 0.09129291 -0.004051864 0.1172002 0.112232 -0.003216922 0.170037 0.118325 -0.003010272 0.187299 0.122715 -0.002779304 0.1919702 0.09467685 -0.003938317 0.123028 0.1043894 -0.003517448 0.1552285 0.1040166 -0.003557741 0.1492337 0.111186 -0.003269255 0.164109 0.156729 -4.99893e-4 0.209936 0.09457021 -0.003969371 0.1172205 0.1101049 -0.003323078 0.157976 0.124272 -0.002734065 0.191979 0.156924 -4.97221e-4 0.209909 0.07644736 -0.004768073 0.04948741 0.08418089 -0.004451096 0.07016515 0.09452259 -0.00399369 0.111403 0.09915387 -0.003792166 0.1274182 0.101978 -0.003685951 0.131802 0.102099 -0.003662824 0.137608 0.103799 -0.00358808 0.143471 0.108051 -0.003423511 0.146326 0.117222 -0.00307244 0.1753039 0.1257166 -0.002685606 0.1919836 0.140444 -0.001449525 0.20344 0.06986451 -0.005098879 0.01068532 0.08576077 -0.004395246 0.07044678 0.09784698 -0.00386691 0.1172417 0.100302 -0.00377345 0.12018 0.107005 -0.003473997 0.140398 0.157117 -4.93909e-4 0.209878 0.141118 -0.001429736 0.203463 0.132719 -0.002184867 0.1980209 0.08031988 -0.004636704 0.05017763 0.08217382 -0.004525601 0.0677759 0.09785813 -0.003880023 0.111413 0.09952551 -0.003816664 0.1114175 0.101922 -0.003702163 0.126003 0.1049054 -0.003574192 0.1284877 0.113297 -0.00320965 0.161541 0.133576 -0.002152204 0.198022 0.141793 -0.001408338 0.203486 0.157307 -4.89957e-4 0.209843 0.09880596 -0.003852367 0.102573 0.1031242 -0.003657877 0.1183831 0.134432 -0.002117156 0.198024 0.157496 -4.85365e-4 0.209803 0.08595591 -0.004392921 0.02374249 0.07580536 -0.004857838 0.01038366 0.08511662 -0.00444585 0.03693258 0.09476339 -0.004025697 0.08766353 0.09983295 -0.003808379 0.09972035 0.101779 -0.003719627 0.110759 0.1255105 -0.0027498 0.1860129 0.1180764 -0.00300765 0.1739684 0.142468 -0.001385331 0.20351 0.135289 -0.002079904 0.198026 0.1431429 -0.001360893 0.2035329 0.09445756 -0.004037082 0.07274186 0.115303 -0.003128945 0.158576 0.1194117 -0.002951025 0.1739868 0.1361449 -0.002040565 0.198028 0.143818 -0.001335144 0.203556 0.157683 -4.80133e-4 0.209758 0.08868962 -0.004282653 0.0429567 0.09289205 -0.004104971 0.06682288 0.091753 -0.004148662 0.05483645 0.09601426 -0.003969669 0.07871079 0.09656882 -0.003953218 0.08120822 0.1167294 -0.003065407 0.1586099 0.1207557 -0.002891123 0.1739933 0.137001 -0.001999258 0.1980299 0.157867 -4.74261e-4 0.209709 0.0877425 -0.004314243 0.03096479 0.09022766 -0.004215359 0.04886835 0.0932784 -0.004082083 0.06080478 0.0934174 -0.00408864 0.06333619 0.09536385 -0.004004955 0.07437503 0.1197389 -0.002929866 0.1647385 0.1224303 -0.002812981 0.1740752 0.144493 -0.001308083 0.203579 0.137858 -0.001956045 0.198031 0.145168 -0.001279711 0.203603 0.08923655 -0.004248678 0.03693258 0.08923649 -0.004262089 0.03962475 0.09028166 -0.004219412 0.04555267 0.09132695 -0.004176318 0.05148047 0.09237217 -0.004132688 0.05740839 0.1129388 -0.003221869 0.1320002 0.1095275 -0.003359138 0.111448 0.1145023 -0.003142595 0.1320238 0.1207487 -0.002878844 0.163255 0.1240478 -0.002732992 0.1740456 0.138714 -0.001910924 0.198033 0.145842 -0.001250147 0.203626 0.15805 -4.67749e-4 0.209655 0.08714598 -0.004346072 0.02776908 0.08819121 -0.004304289 0.03369688 0.121008 -0.002857506 0.158711 0.1256091 -0.002652764 0.1740877 0.158233 -4.608e-4 0.209596 0.111194 -0.003271222 0.1114529 0.1160652 -0.00306034 0.1320467 0.1235492 -0.002734541 0.1633102 0.147188 -0.001187562 0.203671 0.1087025 -0.003355741 0.09362852 0.1128605 -0.003180265 0.1114575 0.1176281 -0.002975285 0.1320704 0.1259709 -0.002596437 0.161988 0.1249495 -0.002658486 0.1633372 0.1283144 -0.002505064 0.174102 0.158415 -4.53322e-4 0.209533 0.1478599 -0.001154601 0.203693 0.141288 -0.001765072 0.198038 0.09696024 -0.003829896 0.03469485 0.1051687 -0.00347954 0.07050329 0.1118227 -0.003199756 0.09958595 0.1168572 -0.002987444 0.1217762 0.1171697 -0.002948641 0.115893 0.1281374 -0.002471089 0.1621365 0.153017 -8.81097e-4 0.18612 0.150631 -0.001078605 0.186116 0.1585969 -4.45277e-4 0.209466 0.1017539 -0.003558933 0.03767877 0.09752625 -0.003773808 0.02798098 0.1037102 -0.003511309 0.05558264 0.1092208 -0.003279507 0.08020198 0.1143848 -0.003028869 0.09476315 0.1132205 -0.00311321 0.09810286 0.1309739 -0.002350628 0.174117 0.1587769 -4.36663e-4 0.209394 0.1033528 -0.003432095 0.03074723 0.106873 -0.003304779 0.05117768 0.1193205 -0.002846121 0.1234006 0.1302354 -0.00234431 0.1622803 0.149869 -0.001049399 0.203758 0.105841 -0.003342151 0.04518395 0.1316557 -0.002256155 0.1623767 0.1336591 -0.002186059 0.1741309 0.158956 -4.27481e-4 0.209318 0.150536 -0.001012384 0.203779 0.144731 -0.001548111 0.198045 0.1342924 -0.002087295 0.1625576 0.145595 -0.001490175 0.198047 0.151201 -9.7446e-4 0.2038 0.159134 -4.17732e-4 0.209237 0.136231 -0.002020239 0.1741375 0.159313 -4.07844e-4 0.209149 0.1358947 -0.001980602 0.1626664 0.159491 -3.97699e-4 0.209056 0.1385067 -0.001802146 0.1628457 0.142347 -0.001719415 0.1860952 0.1449502 -0.001566886 0.1920597 0.159668 -3.87159e-4 0.208958 0.1401315 -0.001687049 0.1629561 0.144149 -0.001586258 0.1860989 0.1598449 -3.76225e-4 0.208855 0.1469953 -0.001412272 0.1920648 0.1426823 -0.001501858 0.1631312 0.145907 -0.001452982 0.1861039 0.160022 -3.64896e-4 0.208746 0.160197 -3.53172e-4 0.2086319 0.1445796 -0.001359522 0.1632604 0.1482615 -0.0012694 0.1861104 0.160376 -3.41085e-4 0.208506 0.156453 -6.39897e-4 0.203939 0.160558 -3.28634e-4 0.208369 0.147171 -0.001158833 0.1634383 0.160741 -3.15803e-4 0.208223 0.160925 -3.02593e-4 0.208069 0.1485658 -0.001048207 0.163533 0.16111 -2.89002e-4 0.207907 0.1499599 -9.35749e-4 0.1636288 0.161462 -2.6253e-4 0.207579 0.161296 -2.75032e-4 0.207737 0.151419 -8.15118e-4 0.1637279 0.1615999 -2.51977e-4 0.20744 0.152832 -6.96757e-4 0.163825 0.1527795 -7.39783e-4 0.1682045 0.1617259 -2.42066e-4 0.207304 0.1542926 -5.73045e-4 0.1639243 0.157236 -5.1772e-4 0.1861259 0.162039 -2.1618e-4 0.206918 0.1619459 -2.24167e-4 0.2070429 0.1557151 -4.49296e-4 0.164022 0.162244 -1.98509e-4 0.206633 0.162135 -2.07852e-4 0.206784 0.1570941 -3.27241e-4 0.1641157 0.1599014 -1.91812e-4 0.177177 0.162351 -1.89148e-4 0.206476 0.16163 -1.70635e-4 0.1920959 0.162663 -1.60955e-4 0.205979 0.160902 -1.8558e-4 0.186129 0.1630229 -1.26351e-4 0.205271 0.143729 -1.18076e-4 0.007093846 0.161787 -7.25227e-5 0.182745 0.162419 -6.55736e-5 0.1888909 0.1630499 -5.54564e-5 0.1950359 0.163378 -8.94188e-5 0.204328 0.124588 -0.001813054 0.01292139 0.104986 0 0.01078838 0.122353 -0.001986801 0.01267814 0.12682 0.001636445 0.01316428 0.12682 -0.001636385 0.01316428 0.124588 0.001813113 0.01292145 0.129048 -0.001456737 0.01340669 0.129048 0.001456797 0.01340675 0.131273 -0.001274049 0.01364886 0.131273 0.001274108 0.01364886 0.133495 0.0010885 0.01389068 0.133494 -0.00108844 0.01389056 0.135713 -8.99881e-4 0.01413196 0.135713 8.99959e-4 0.01413196 0.137928 -7.08315e-4 0.014373 0.137928 7.08398e-4 0.014373 0.140139 5.13864e-4 0.01461368 0.140139 -5.13774e-4 0.01461368 0.142347 -3.1626e-4 0.01485389 0.142347 3.16357e-4 0.01485395 0.1445519 -1.15772e-4 0.01509386 0.1445519 1.15876e-4 0.01509386 0.122353 0.001986861 0.01267814 0.104862 -4.75918e-4 0.01077479 0.104768 -6.14183e-4 0.01076465 0.120114 -0.002157568 0.0124346 0.104972 1.64624e-4 0.01078689 0.1045179 -8.37137e-4 0.01073735 0.104368 -9.15744e-4 0.01072108 0.115627 -0.002490103 0.01194626 0.10493 3.24729e-4 0.0107823 0.111127 -0.002810776 0.01145654 0.113379 -0.002651929 0.01170158 0.104206 -9.69371e-4 0.0107035 0.120115 0.002157628 0.0124346 0.104038 -9.96555e-4 0.01068514 0.108871 -0.002966701 0.01121109 0.104862 4.75977e-4 0.01077479 0.106612 -0.003119587 0.01096528 0.104768 6.14242e-4 0.01076465 0.10435 -0.003269493 0.01071918 0.103867 -9.96555e-4 0.01066654 0.117873 0.002325356 0.01219069 0.102085 -0.003416478 0.01047259 0.09981578 -0.003560483 0.01022565 0.104653 7.35753e-4 0.01075208 0.1033869 -8.37137e-4 0.01061427 0.103252 -7.35695e-4 0.01059967 0.1045179 8.37196e-4 0.01073735 0.115628 0.002490162 0.01194638 0.104368 9.15803e-4 0.01072108 0.102918 0 0.01056325 0.09981578 0.003560543 0.01022565 0.106613 0.003119647 0.01096534 0.103867 9.96614e-4 0.01066654 0.104038 9.96614e-4 0.01068514 0.111127 0.002810835 0.01145654 0.108871 0.002966701 0.01121115 0.1029739 3.24729e-4 0.01056939 0.103043 4.75977e-4 0.0105769 0.113379 0.002651989 0.0117017 0.104206 9.6943e-4 0.0107035 0.10435 0.003269553 0.01071918 0.102085 0.003416538 0.01047259 0.103698 9.6943e-4 0.01064819 0.1033869 8.37196e-4 0.01061427 0.103537 9.15803e-4 0.01063066 0.103136 6.14242e-4 0.01058709 0.103252 7.35753e-4 0.01059967 0.102932 1.64624e-4 0.01056486 0.102932 -1.64565e-4 0.01056486 0.103043 -4.75918e-4 0.0105769 0.1029739 -3.2467e-4 0.01056939 0.103136 -6.14183e-4 0.01058709 0.103537 -9.15744e-4 0.01063066 0.103698 -9.69371e-4 0.01064819 0.1178719 -0.002325296 0.01219058 0.104653 -7.35695e-4 0.01075208 0.10493 -3.2467e-4 0.0107823 0.104972 -1.64565e-4 0.01078689 0.102178 0 0.006267011 0.103559 9.15803e-4 0.006029009 0.1034049 9.6943e-4 0.006055533 0.102767 9.15803e-4 0.006165444 0.102496 7.35753e-4 0.006212234 0.1023859 6.14242e-4 0.006231248 0.1026239 8.37196e-4 0.006190061 0.102297 4.75977e-4 0.006246566 0.102921 9.6943e-4 0.00613892 0.102231 3.24729e-4 0.006257832 0.103082 9.96614e-4 0.006111204 0.103245 9.96614e-4 0.00608319 0.102191 1.64624e-4 0.006264746 0.102296 -4.75717e-4 0.006246566 0.103831 7.35753e-4 0.00598216 0.102231 -3.24516e-4 0.006257832 0.102191 -1.64611e-4 0.006264746 0.103702 8.37196e-4 0.006004333 0.103941 6.14242e-4 0.005963206 0.102385 -6.1396e-4 0.006231248 0.10403 4.75977e-4 0.005947828 0.102767 -9.15584e-4 0.006165504 0.104149 0 0.005927383 0.104135 1.64624e-4 0.005929708 0.102496 -7.35473e-4 0.006212234 0.1026239 -8.36938e-4 0.006190121 0.104095 3.24729e-4 0.005936563 0.104095 -3.24757e-4 0.005936563 0.103244 -9.96562e-4 0.00608325 0.10403 -4.76037e-4 0.005947828 0.104135 -1.64611e-4 0.005929708 0.102921 -9.69263e-4 0.00613898 0.103082 -9.96504e-4 0.006111264 0.103831 -7.35836e-4 0.00598222 0.103559 -9.15845e-4 0.006029009 0.103702 -8.37266e-4 0.006004333 0.103941 -6.14321e-4 0.005963206 0.1034049 -9.6943e-4 0.006055533 0.102932 1.64624e-4 0.01056486 0.102918 0 0.01056325 0.102178 0 0.006267011 0.1023859 6.14242e-4 0.006231248 0.103136 6.14242e-4 0.01058709 0.102297 4.75977e-4 0.006246566 0.103043 4.75977e-4 0.0105769 0.1029739 3.24729e-4 0.01056939 0.102231 3.24729e-4 0.006257832 0.1026239 8.37196e-4 0.006190061 0.102767 9.15803e-4 0.006165444 0.103537 9.15803e-4 0.01063066 0.103252 7.35753e-4 0.01059967 0.102496 7.35753e-4 0.006212234 0.1033869 8.37196e-4 0.01061427 0.104038 9.96614e-4 0.01068514 0.103082 9.96614e-4 0.006111204 0.103245 9.96614e-4 0.00608319 0.103867 9.96614e-4 0.01066654 0.103698 9.6943e-4 0.01064819 0.102921 9.6943e-4 0.00613892 0.103702 8.37196e-4 0.006004333 0.1045179 8.37196e-4 0.01073735 0.103559 9.15803e-4 0.006029009 0.1034049 9.6943e-4 0.006055533 0.104368 9.15803e-4 0.01072108 0.104206 9.6943e-4 0.0107035 0.104862 4.75977e-4 0.01077479 0.10403 4.75977e-4 0.005947828 0.10493 3.24729e-4 0.0107823 0.104768 6.14242e-4 0.01076465 0.103831 7.35753e-4 0.00598216 0.103941 6.14242e-4 0.005963206 0.104972 -1.64565e-4 0.01078689 0.104986 0 0.01078838 0.104149 0 0.005927383 0.104135 1.64624e-4 0.005929708 0.104972 1.64624e-4 0.01078689 0.104095 3.24729e-4 0.005936563 0.10403 -4.76037e-4 0.005947828 0.104768 -6.14183e-4 0.01076465 0.104862 -4.75918e-4 0.01077479 0.104135 -1.64611e-4 0.005929708 0.104095 -3.24757e-4 0.005936563 0.10493 -3.2467e-4 0.0107823 0.1045179 -8.37137e-4 0.01073735 0.103702 -8.37266e-4 0.006004333 0.104368 -9.15744e-4 0.01072108 0.104653 -7.35695e-4 0.01075208 0.103941 -6.14321e-4 0.005963206 0.103831 -7.35836e-4 0.00598222 0.104038 -9.96555e-4 0.01068514 0.1034049 -9.6943e-4 0.006055533 0.103244 -9.96562e-4 0.00608325 0.104206 -9.69371e-4 0.0107035 0.103559 -9.15845e-4 0.006029009 0.103867 -9.96555e-4 0.01066654 0.103082 -9.96504e-4 0.006111264 0.103698 -9.69371e-4 0.01064819 0.102921 -9.69263e-4 0.00613898 0.103537 -9.15744e-4 0.01063066 0.1033869 -8.37137e-4 0.01061427 0.102767 -9.15584e-4 0.006165504 0.1026239 -8.36938e-4 0.006190121 0.103252 -7.35695e-4 0.01059967 0.102496 -7.35473e-4 0.006212234 0.103136 -6.14183e-4 0.01058709 0.103043 -4.75918e-4 0.0105769 0.102385 -6.1396e-4 0.006231248 0.102296 -4.75717e-4 0.006246566 0.1029739 -3.2467e-4 0.01056939 0.102231 -3.24516e-4 0.006257832 0.102932 -1.64565e-4 0.01056486 0.102191 -1.64611e-4 0.006264746 0.104653 7.35753e-4 0.01075208 0.102191 1.64624e-4 0.006264746 + + + + + + + + + + -2.72337e-6 0.707114 -0.7070996 3.36876e-6 0.7071049 -0.7071087 3.55523e-7 0.7071081 -0.7071055 1.44229e-6 0.7070937 -0.70712 -5.66091e-6 0.7071956 -0.707018 1.50458e-6 0.7072406 -0.706973 2.54683e-6 0.707161 -0.7070525 1.88408e-6 0.7070771 -0.7071366 -1.59775e-6 0.7070372 -0.7071764 2.1206e-6 0.7070696 -0.707144 -2.69268e-5 0.7066669 -0.7075465 -3.35793e-6 0.7070444 -0.7071692 0 0.707106 -0.7071076 1.85805e-6 0.7071287 -0.7070849 0 0.7071068 -0.7071068 0 0.707107 -0.7071066 0 0.7071068 -0.7071068 1 0 0 0.02392834 0.7069042 0.7069044 0.02392834 0.7069044 0.7069043 -1 0 0 -1 -4.04216e-7 0 -0.008636832 -0.7074009 -0.7067599 -0.01507651 -0.7075604 -0.7064922 -0.009918749 -0.7067363 -0.7074077 0.01132249 -0.7073666 -0.7067562 0.004547357 -0.7073436 -0.7068553 0.007507741 -0.7067053 -0.7074683 -0.001037657 -0.7066485 -0.7075641 -0.01028501 -0.7865763 -0.6174073 0.001373291 -0.7177972 -0.696251 -0.001159727 -0.7099694 -0.7042317 -0.01690751 -0.7876642 -0.6158729 -0.02227896 -0.7064887 -0.7073737 -0.02411019 -0.7113431 -0.7024314 -0.1352902 -0.6926567 -0.7084655 -0.1101124 -0.6979992 -0.7075822 -0.1137776 -0.6963692 -0.7086076 -0.01129192 -0.8249544 -0.5650866 -0.06122124 -0.7098126 -0.7017251 -0.02887117 -0.7172027 -0.6962664 -0.04049873 -0.7126193 -0.7003812 -0.08520948 -0.7042604 -0.7048097 -0.06296145 -0.7081716 -0.7032275 -0.07117074 -0.705329 -0.7052985 -0.04922789 -0.7106155 -0.7018563 -0.09735482 -0.6990016 -0.7084624 -0.08643192 -0.7022292 -0.7066851 -0.1411821 -0.6916583 -0.7082913 -0.1604701 -0.6887583 -0.7070088 -0.125496 -0.6937988 -0.7091501 -0.154639 -0.6897563 -0.7073352 -0.1721283 -0.6887271 -0.7042919 -0.1864737 -0.6876029 -0.7017334 -0.1904379 -0.6877739 -0.7005003 -0.2064311 -0.6883886 -0.695347 -0.2179986 -0.6901003 -0.6901003 -0.2012127 -0.6884509 -0.6968132 -0.01202154 -0.8268983 -0.5622231 0.02353036 -0.7125043 -0.7012732 0.02322512 -0.7147311 -0.6990137 0.02392679 -0.7108152 -0.7029718 0.02301156 -0.7190968 -0.6945288 0.02295041 -0.7201316 -0.6934578 0.02429348 -0.70967 -0.7041154 0.02487313 -0.7084733 -0.7052992 0.02545326 -0.7074726 -0.7062824 0.01889121 -0.7104513 -0.7034929 0.006439566 -0.7075651 -0.706619 0.005981802 -0.707323 -0.7068653 -0.008514761 -0.7076456 -0.7065164 -0.08160722 -0.9965609 0.01437431 -0.2129917 -0.9763315 0.0375688 -0.2417409 -0.9694052 0.0426045 -0.3576553 -0.9317227 0.06305277 -0.3954717 -0.9158293 0.06970649 -0.5385985 -0.8371961 0.09494447 -0.5011831 -0.8608191 0.0883525 -0.6260813 -0.7719044 0.1103898 -0.667059 -0.7356662 0.1175906 -0.7334982 -0.6672716 0.1293403 -0.7771696 -0.6141974 0.1370003 -0.8657746 -0.4765911 0.1526275 -0.8191736 -0.555058 0.1444487 -0.8880246 -0.4323081 0.1565953 -0.9312616 -0.3252732 0.1641625 -0.9382756 -0.3037554 0.1654434 -0.9713057 -0.1650481 0.1712435 -0.9814072 -0.08310389 0.1730135 -0.9703075 -0.1709704 0.1710925 -0.9825543 -0.06759923 0.1732555 -0.06378406 -0.9979006 0.01123088 0.08127135 -0.9965893 -0.01431328 0.1020859 -0.9946132 -0.01797562 0.242049 -0.9693256 -0.04266607 0.3959216 -0.9156279 -0.06979668 0.2534012 -0.9663304 -0.0446496 0.5384489 -0.8372922 -0.09494495 0.3919868 -0.9173725 -0.06909513 0.5307289 -0.8423604 -0.09357184 0.6670886 -0.7356347 -0.117621 0.6520033 -0.7494497 -0.1149643 0.7535189 -0.6438634 -0.13285 0.7773255 -0.6139864 -0.137062 0.8356109 -0.5291999 -0.1473153 0.8988 -0.4087175 -0.1584573 0.8658651 -0.4764074 -0.1526884 0.931239 -0.3253064 -0.1642249 0.9435197 -0.2865411 -0.1663275 0.9713104 -0.1649879 -0.1712749 0.9717835 -0.1621165 -0.1713332 0.9814045 -0.08307313 -0.1730436 0.9824787 -0.06876003 -0.1732277 0.02429318 -0.7063639 -0.707432 0.02642971 -0.7054545 -0.7082623 0.02893215 -0.7049926 -0.7086244 0.0237441 -0.7066175 -0.7071973 0.03018379 -0.700331 -0.7131797 0.03546339 -0.704599 -0.7087191 0.03036659 -0.7019423 -0.7115864 0.03039687 -0.7038288 -0.709719 0.03058034 -0.703135 -0.7103986 0.03000044 -0.6980988 -0.7153727 0.02981716 -0.6944018 -0.7189696 0.02966457 -0.6867111 -0.7263249 0.02963417 -0.6851884 -0.7277628 0.04393994 -0.7064298 -0.7064179 0.04648143 -0.7083388 -0.7043406 0.04535669 -0.7086841 -0.7040666 0.04297155 -0.7079018 -0.7050026 0.04175031 -0.7069174 -0.7060629 0.03769147 -0.7043576 -0.708844 0.03927785 -0.7048041 -0.7083138 0.04092574 -0.7045585 -0.7084649 0.03640919 -0.706638 -0.706638 0.04202532 -0.704878 -0.7080826 0.02376389 -0.706804 -0.7070102 0.0422061 -0.7082976 -0.7046512 0.02859681 -0.707077 -0.7065582 0.03790485 -0.7085035 -0.7046886 0.03390657 -0.7084985 -0.7048973 0.0393387 -0.7086164 -0.7044965 0.03954112 -0.7075229 -0.7055835 0.04550397 -0.7037866 -0.7089526 0.04393959 -0.7042189 -0.708622 1 9.40792e-6 0 1 -1.24896e-5 0 1 -1.93789e-5 0 0 -0.7071073 -0.7071063 0 -0.7071065 -0.7071071 1 1.16786e-5 0 1 -4.99857e-6 0 1 1.27317e-5 0 1 -2.13961e-5 0 1 9.19126e-6 0 1 -1.23272e-5 0 1 9.84485e-6 0 0 0.7071065 -0.7071072 0 0.7071065 -0.7071071 0 0.707108 -0.7071056 0 0.7071063 -0.7071073 0 0.707107 -0.7071067 0 0.7071066 -0.7071071 0 0.7071069 -0.7071068 0 0.7071062 -0.7071074 0 0.7071074 -0.7071061 0 0.7071067 -0.7071069 0 0.7071069 -0.7071067 0 0.7071067 -0.707107 0 0.7071073 -0.7071064 0 0.7071067 -0.707107 0 0.7071071 -0.7071065 0 0.7071073 -0.7071063 0 0.707107 -0.7071067 0 0.7071067 -0.707107 0 0.7071071 -0.7071066 0 0.7071074 -0.7071062 0 0.7071067 -0.707107 0 0.7071068 -0.7071068 0 0.7071061 -0.7071076 0 0.707107 -0.7071065 0 0.7071068 -0.7071069 0 0.7071068 -0.7071068 0 0.7071064 -0.7071072 -1 0 0 -0.06055068 -0.7056415 -0.7059772 -0.05020409 -0.7062151 -0.7062151 -0.05945205 -0.7057645 -0.7059476 -0.1626089 -0.6976804 -0.6977109 -0.1553459 -0.6982632 -0.698782 -0.1555577 -0.698499 -0.698499 -0.04962462 -0.7062203 -0.7062509 -0.03869897 -0.7066228 -0.7065313 -0.04052984 -0.7067089 -0.7063426 -0.03558611 -0.7069317 -0.7063862 -0.02777218 -0.7068493 -0.7068188 -0.03170955 -0.7070106 -0.7064918 -0.02227896 -0.7069161 -0.7069466 -0.02700924 -0.707093 -0.7066047 -0.02763724 -0.7071062 -0.7065671 -0.07159733 -0.7050175 -0.7055668 -0.06689763 -0.7054159 -0.7056295 -0.07819122 -0.7048504 -0.7050335 -0.0726965 -0.7051138 -0.7053579 -0.08392781 -0.7046273 -0.7045968 -0.08395808 -0.7043814 -0.7048391 -0.08990919 -0.7041972 -0.7042888 -0.09787505 -0.7034981 -0.7039253 -0.09586095 -0.7038351 -0.7038657 -0.1022084 -0.7033121 -0.7034952 -0.1083448 -0.7028375 -0.7030512 -0.1119449 -0.7024028 -0.7029216 -0.1212818 -0.7017192 -0.7020549 -0.1149037 -0.7023013 -0.7025455 -0.1114736 -0.7026814 -0.702718 -0.1280885 -0.7011144 -0.7014501 -0.1260467 -0.7011313 -0.7018027 -0.134742 -0.7004754 -0.7008416 -0.1401447 -0.6998078 -0.7004488 -0.1416705 -0.6998375 -0.7001122 -0.1485053 -0.6991593 -0.6993729 -0.1838462 -0.6951305 -0.6949779 -0.1726754 -0.6963173 -0.696653 -0.1769179 -0.6960442 -0.6958611 -0.169596 -0.6969702 -0.6967566 -0.1983478 -0.6931341 -0.6929815 -0.1908066 -0.6940088 -0.6942224 -0.1910834 -0.6942606 -0.6938944 -0.2089334 -0.6913177 -0.691684 -0.2197669 -0.6897892 -0.6898503 -0.2241356 -0.6890097 -0.6892234 -0.2053964 -0.692122 -0.6919389 -0.243362 -0.6859244 -0.6857718 -0.2500466 -0.6845226 -0.6847668 -0.2365847 -0.6869869 -0.6870785 -0.2343568 -0.6874448 -0.6873838 -0.2807734 -0.6785865 -0.6787391 -0.2841374 -0.6778097 -0.6781149 -0.2662204 -0.6814973 -0.6816805 -0.2654221 -0.6816377 -0.6818513 -0.2540147 -0.6839445 -0.6838834 -0.3336317 -0.6663174 -0.6668667 -0.3165493 -0.6707904 -0.6706988 -0.3375146 -0.6655377 -0.6656903 -0.2978338 -0.6750777 -0.6749557 -0.3074846 -0.6725901 -0.673109 -0.3876292 -0.6519593 -0.6516846 -0.4159187 -0.6432273 -0.6428611 -0.4004086 -0.6476122 -0.6482836 -0.3647371 -0.6581199 -0.6586692 -0.3613168 -0.6593369 -0.6593369 -0.5186431 -0.6045851 -0.6045546 -0.4821823 -0.6191552 -0.6197961 -0.4819871 -0.6195058 -0.6195974 -0.4390859 -0.6349608 -0.6356322 -0.4475334 -0.6324188 -0.6322662 -0.6323795 -0.5472322 -0.5483003 -0.5791392 -0.5758736 -0.5770334 -0.5996542 -0.5661434 -0.5655941 -0.5285887 -0.5997895 -0.6007051 -0.5582938 -0.5868296 -0.5864633 -0.6864735 -0.5141913 -0.5141608 -0.6878824 -0.5127912 -0.5136762 -0.6423643 -0.5421094 -0.5417431 -0.7970818 -0.4260544 -0.4279466 -0.8115431 -0.4132946 -0.4130199 -0.847301 -0.3745605 -0.3765443 -0.729933 -0.483336 -0.4833055 -0.7719239 -0.449732 -0.4493047 -0.742984 -0.4726471 -0.4738984 -0.9048889 -0.3010701 -0.300887 -0.9302363 -0.258165 -0.2607897 -0.8921134 -0.3184397 -0.320515 -0.8777084 -0.3383995 -0.3392845 -0.8468702 -0.3757187 -0.3763596 -0.9590274 -0.1987088 -0.2019438 -0.955664 -0.2080463 -0.208382 -0.9647429 -0.1857704 -0.1864418 -0.9256271 -0.2674732 -0.2677174 -0.9420914 -0.236858 -0.2374073 -0.9708875 -0.1675522 -0.1711841 -0.9696674 -0.1715504 -0.1741141 -0.9759428 -0.1536641 -0.1546713 -0.9795653 -0.1422181 -0.1422181 -0.2269381 -0.6886578 -0.6886578 -0.2128397 -0.6909508 -0.6908592 0 -1 0 0 -1 0 0 -1 0 0.001058757 0 0.9999995 0 0 1 -1.86091e-4 0 1 -9.88772e-5 0 1 2.85751e-4 0 1 3.21802e-5 0 1 -2.43415e-4 0 1 -2.55249e-4 0 1 -1.14878e-4 0 1 -3.89024e-4 0 1 7.85043e-4 0 0.9999998 3.72971e-4 0 1 -3.72781e-4 0 1 1.3473e-4 0 1 -3.08698e-4 0 1 3.34284e-4 0 1 -2.43743e-4 0 1 -4.46624e-4 0 1 0 -1.74242e-5 1 -1.53645e-4 -1.72152e-5 1 3.15186e-4 -1.74291e-5 1 1.47425e-4 -1.29873e-6 1 1.52197e-4 0 1 -1.41878e-4 0 1 1.5329e-4 0 1 4.9968e-5 0 1 -1.4028e-4 0 1 -8.89282e-5 0 1 1.36246e-4 0 1 9.56324e-5 0 1 -1.35288e-4 0 1 -1.37403e-4 0 1 -1.59894e-5 0 1 1.33785e-4 0 1 1.77684e-4 0 1 -2.7513e-4 0 1 0.7232776 0.008911609 0.6904999 0.7506194 0.01532059 0.6605573 0.7233296 0.00766021 0.6904607 0.7580969 0.01446604 0.6519816 0.6915085 0.00262463 0.7223637 0.6915062 0.003692805 0.7223612 0.6600967 0.004760921 0.7511656 0.6551262 0.004822015 0.7555041 0.6305618 0.009705126 0.7760784 0.62088 0.006042718 0.7838824 0.5769372 3.05193e-5 0.8167886 0.6034865 0.006775259 0.7973445 0.5727798 -0.001037597 0.8197087 0.5374463 -0.005371391 0.843281 0.5447678 -0.008331716 0.8385456 0.5064666 -0.01025444 0.8621987 0.4735675 -0.007568776 0.8807251 0.4599792 -0.009094595 0.8878832 0.5173653 -0.01022398 0.8557037 0.4324538 -0.002533018 0.9016525 0.4146304 -0.003479123 0.9099833 0.4017872 -3.66232e-4 0.915733 0.3814023 -0.002685666 0.9244053 0.3067168 -0.002014219 0.9517987 0.3480727 -0.003418147 0.9374614 0.3236525 0 0.9461761 0.2721081 -1.52595e-4 0.9622668 0.28896 0.001220762 0.9573404 0.2556902 0.001464903 0.9667578 0.1836931 0.001464903 0.9829826 0.1942259 4.88312e-4 0.9809568 0.2198925 0.00149542 0.9755231 0.01947122 0 0.9998105 0.02948153 0 0.9995654 0.02942055 0 0.9995672 0.09796553 0 0.9951899 0.07498568 3.05192e-5 0.9971846 0.09824055 3.0519e-5 0.9951628 0.1239371 0 0.9922902 0.1239972 0 0.9922826 0.07495534 3.05193e-5 0.9971869 0.1478017 0 0.9890171 0.1506397 5.49335e-4 0.9885886 0.05182194 0 0.9986564 0.05206543 0 0.9986437 0.2205285 0.001495361 0.9753795 0.1696228 0 0.9855092 0.2447322 0.001068115 0.9695901 0.3666237 -5.18822e-4 0.9303691 0.7907586 0.008636951 0.6120673 0.7828526 0.01663303 0.6219849 0.8166666 -0.007629811 0.5770594 0.8050315 0.001831114 0.5932294 0.8235448 -0.006897449 0.5672094 0.8358515 -0.01214647 0.5488213 0.8486527 -0.007233083 0.5289011 0.967719 -0.001983702 0.2520238 0.9795606 -0.003540158 0.2011186 0.9781956 -0.005188226 0.2076209 0.9841784 0.01297056 0.1767053 0.9873555 0.001342833 0.1585164 0.859386 -0.008606314 0.5112552 0.9659552 -5.49341e-4 0.2587091 0.9532726 -5.79868e-4 0.3021112 0.9965814 -1.83117e-4 0.08261609 0.9992818 -0.004486262 0.03762984 0.9963709 -6.4089e-4 0.08511632 0.9527572 0.00137335 0.3037298 0.9408623 -5.79856e-4 0.3387886 0.9914372 0.002563536 0.1305599 0.9934945 -0.006683707 0.1136844 0.8735752 -0.001739561 0.4866861 0.8845027 -0.004455745 0.4665139 0.8933504 1.52595e-4 0.4493609 0.908262 -0.002777278 0.4183926 0.9059269 -0.003326535 0.423421 0.9246399 -0.004303157 0.3808184 0.9212284 -0.004120111 0.3890004 0.9367282 -0.00100708 0.3500561 0.9995852 -0.001190185 0.02877926 0.9998531 0.001648008 -0.01705992 0.9998275 0.01812815 0.004058957 0.9989795 0.01837241 -0.04126173 0.9979364 -0.003418087 -0.06412011 0.9959017 0.003692805 -0.09036725 0.9966105 0.006531119 -0.08200556 0.995769 0 -0.09189224 0.9947695 0 -0.1021464 0.9947543 -2.51661e-4 -0.1022925 0.994749 -0.006609201 -0.1021314 0.9947543 -5.01017e-4 -0.1022922 0.9947543 5.08828e-4 -0.1022928 0.9947545 2.70171e-4 -0.1022913 0.9947544 -2.57313e-4 -0.102293 0.9947472 -0.006563663 -0.1021521 0.9947543 5.97343e-4 -0.102292 0.9947544 0 -0.1022918 0.9947187 0.008358597 -0.102298 0.9947544 0 -0.1022925 0.06778222 0 -0.9977002 0.06841778 0 -0.9976568 0.06850451 0 -0.9976509 0.06849569 0 -0.9976514 0.06847977 0 -0.9976525 0.06848132 0 -0.9976525 0.06777304 0 -0.9977008 0.06780511 0 -0.9976986 0.06849634 0 -0.9976514 0.06845849 0 -0.997654 0.06784343 0 -0.997696 0.0678336 0 -0.9976967 0.06850379 0 -0.9976509 0.06848907 0 -0.9976519 0.06780177 0 -0.9976989 0.06781733 0 -0.9976978 0.06853026 0 -0.9976491 0.06855964 0 -0.9976471 0.06782424 0 -0.9976973 0.06783306 0 -0.9976967 0.06853473 0 -0.9976488 0.06855553 0 -0.9976473 0.06779158 -4.50558e-4 -0.9976995 0.06785589 0 -0.9976952 0.06778156 0 -0.9977002 0.06841737 0 -0.9976569 0.06849932 0 -0.9976512 0.06845122 0 -0.9976545 0.06772255 0 -0.9977043 0.06846606 0 -0.9976536 0.06844955 0 -0.9976546 0.06777131 0 -0.9977009 0.06846415 0 -0.9976537 0.06841909 0 -0.9976567 0.06771367 0 -0.9977049 0.06775075 0 -0.9977023 0.06844085 0 -0.9976552 0.06846189 0 -0.9976539 0.06836444 0 -0.9976604 0.0683937 0 -0.9976585 0.06769698 0 -0.997706 0.06769305 0 -0.9977062 0.06841009 0 -0.9976573 0.06844168 0 -0.9976552 0.06838691 0 -0.9976589 0.06841379 0 -0.9976571 0.06840234 0 -0.9976579 0.0683552 0 -0.9976611 0.9844881 0 0.1754511 0.984484 5.36544e-5 0.1754744 0.9844827 1.39094e-5 0.1754821 0.9844856 0 0.1754661 0.9844887 5.79235e-6 0.1754483 0.9844867 -2.93475e-6 0.1754595 0.9844834 -7.02874e-5 0.1754776 0.984486 -2.28399e-5 0.1754633 0.984488 4.34967e-5 0.1754521 0.9844862 -8.29775e-6 0.1754624 0.9844863 -1.19838e-5 0.1754615 0.9844857 2.15122e-5 0.1754654 0.9844859 1.27466e-5 0.1754639 0.9844884 -3.81486e-5 0.1754496 0.9844866 -1.53613e-5 0.1754599 0.9844871 -9.53925e-6 0.1754571 0.984486 -1.02451e-5 0.1754636 0.9844858 -9.88134e-6 0.1754643 0.9844853 5.02124e-5 0.1754674 0.1754691 0 -0.984485 0.1754581 0 -0.9844869 0.1754636 2.38581e-7 -0.984486 -0.1754632 0 0.9844861 -0.1754859 0 0.9844821 -0.1754781 -3.92066e-6 0.9844834 -0.9844838 0 -0.1754757 -0.9844838 0 -0.1754758 -0.1754496 0 0.9844885 -0.1754394 0 0.9844902 -0.1754741 -8.88512e-6 0.9844841 -0.1754531 4.42299e-6 0.9844878 -0.9844884 -1.70849e-5 -0.17545 -0.9844878 -2.21305e-5 -0.1754531 -0.9844858 1.40398e-5 -0.1754648 -0.9844869 -3.21319e-5 -0.1754583 -0.9844852 4.35649e-5 -0.1754681 -0.9844838 -6.47255e-5 -0.1754755 -0.9844865 7.24119e-6 -0.1754608 -0.9844885 2.30852e-5 -0.1754492 -0.9844872 -8.65365e-6 -0.175457 -0.9844865 -7.58824e-6 -0.1754609 -0.9844862 -1.82293e-5 -0.1754624 -0.9844833 -1.90554e-5 -0.1754789 -0.9844893 2.30554e-5 -0.1754453 -0.9844865 -8.13532e-6 -0.1754601 -0.9844865 -4.42819e-6 -0.1754602 -0.9844853 0 -0.1754671 0.05579 -0.4259024 0.9030475 0.05725449 -0.4255939 0.9031013 0.063358 -0.3962013 0.9159751 0.06234967 -0.4172517 0.9066496 0.06213742 -0.4171081 0.9067303 0.06467062 -0.44244 0.8944633 0.05581861 -0.4896722 0.8701181 0.06347912 -0.3960731 0.9160221 0.06164908 -0.4384716 0.8966282 0.06363189 -0.4340703 0.898629 0.06390708 -0.4339517 0.8986668 0.05893212 -0.4809488 0.8747659 0.05456775 -0.5371633 0.8417114 0.06317359 -0.4404757 0.8955392 0.06320613 -0.4950286 0.8665747 0.05942004 -0.4974562 0.8654518 0.06183165 -0.5478786 0.8342697 0.05920743 -0.5785545 0.8134921 0.06845396 -0.4334604 0.898569 0.05285972 -0.5731562 0.8177395 0.05185216 -0.6014124 0.7972544 0.0567969 -0.5829241 0.8105392 0.05591154 -0.6052304 0.7940845 0.05502659 -0.606788 0.7929568 0.052432 -0.6207306 0.7822688 0.05569756 -0.5708011 0.8191971 0.05243217 -0.5933873 0.8032076 0.05111938 -0.6059862 0.7938309 0.9848062 2.49189e-4 -0.1736573 0.9848137 0 -0.1736146 0.9848089 2.48124e-5 -0.173642 0.9848119 -2.32161e-4 -0.1736252 0.9847884 0.002347946 -0.1737427 0.9848183 -0.001829504 -0.173579 0.9847847 0.003574252 -0.1737422 0.9848123 -6.47402e-4 -0.1736217 0.9848105 8.23932e-4 -0.1736311 0.984808 0 -0.1736469 0.9848065 -1.94068e-4 -0.1736547 0.9848081 6.48418e-5 -0.1736462 0.9848082 2.46775e-5 -0.1736461 0.9848083 3.30648e-5 -0.1736454 0.9848068 -1.33319e-4 -0.1736535 0.9848078 -3.30926e-5 -0.1736484 0.9848083 3.31522e-5 -0.1736454 0.984808 0 -0.1736469 0.9848067 -8.20988e-6 -0.1736545 0.9848081 -4.94972e-5 -0.1736466 0.984807 -1.61007e-5 -0.173653 0.9848079 1.42967e-5 -0.1736478 0.9848072 -4.04861e-6 -0.1736512 0.9848068 4.0883e-6 -0.173654 0.9848071 5.40301e-6 -0.1736524 0.9848074 -1.48832e-5 -0.1736503 -0.1731724 -8.94326e-4 -0.9848911 -0.1737677 -2.23352e-4 -0.9847868 -0.1744638 0 -0.9846637 -0.1734543 0 -0.9848419 -0.1741604 -6.93597e-4 -0.9847171 -0.1732668 2.50547e-4 -0.9848749 -0.173495 -0.001336991 -0.9848338 -0.1733971 1.68543e-4 -0.984852 -0.1736869 0.006292045 -0.9847809 -0.1737322 0.001655995 -0.9847916 -0.17314 -0.004549086 -0.9848868 -0.1722434 -0.01592034 -0.9849258 -0.1736927 -0.003543555 -0.9847936 -0.1731504 -3.45472e-4 -0.9848954 -0.1735078 -9.72528e-4 -0.9848321 -0.1737369 -0.002835273 -0.9847881 -0.1736381 0.001399576 -0.9848086 -0.1736438 8.36012e-4 -0.9848082 -0.1736952 -8.16613e-5 -0.9847996 -0.173706 0.002124369 -0.9847953 -0.1734681 -2.45557e-4 -0.9848396 -0.1734833 -2.3663e-4 -0.9848368 -0.1742784 6.32322e-4 -0.9846963 -0.9848094 -1.23683e-5 0.1736388 -0.9848097 -3.75002e-5 0.1736374 -0.9848082 3.96052e-5 0.1736459 -0.9848077 -1.20906e-5 0.173649 -0.9848076 3.77308e-5 0.1736499 -0.9848084 8.52992e-5 0.1736446 -0.9848067 3.13069e-5 0.1736543 -0.9848123 -6.29899e-5 0.1736231 -0.9848082 -3.21444e-5 0.1736457 -0.9848102 -1.24378e-5 0.1736347 -0.9848077 3.56945e-5 0.1736487 -0.9848077 7.75942e-6 0.1736487 -0.9848073 2.2305e-4 0.1736508 -0.9848081 -1.07297e-4 0.1736462 -0.984808 -5.16686e-5 0.1736469 -0.9848088 5.14714e-4 0.1736421 -0.9848085 4.77256e-4 0.1736436 -0.9848054 2.53126e-4 0.1736621 -0.9848076 6.16216e-6 0.1736491 0.05969518 -0.5981729 0.7991407 0.05981713 -0.6000335 0.7977354 0.0566138 -0.5515195 0.8322387 0.05853652 -0.5856705 0.8084328 0.05838322 -0.5901803 0.8051576 0.05981653 -0.58608 0.8080422 0.06012213 -0.5761958 0.8150974 0.0601834 -0.5527295 0.8311848 0.0584743 -0.5938682 0.8024347 0.05868774 -0.5965215 0.8004485 0.05987858 -0.5727836 0.8175168 0.05911523 -0.5982326 0.799139 0.05948138 -0.5682324 0.8207156 0.05545318 -0.5733622 0.8174234 0.05829113 -0.6126368 0.7882121 0.05838298 -0.6135249 0.7875142 0.05435454 -0.5946651 0.8021341 0.05829167 -0.6143515 0.7868764 0.05652153 -0.6230188 0.7801621 0.05658209 -0.6234412 0.7798203 0.05667418 -0.6243013 0.7791252 0.05667388 -0.6245727 0.7789076 0.05478274 -0.6325195 0.7726047 0.05346894 -0.6150761 0.7866528 0.05481278 -0.632972 0.7722319 0.05459928 -0.6304101 0.7743399 0.05450749 -0.6295219 0.7750685 0.05240082 -0.6536217 0.7550053 0.05420225 -0.6274767 0.7767466 0.05325514 -0.6245043 0.7792036 0.05346989 -0.6248838 0.7788845 0.05208581 -0.6553001 0.7535707 0.05307328 -0.6243058 0.7793751 0.05295002 -0.6242616 0.779419 0.05374419 -0.6255511 0.77833 0.05239945 -0.6540309 0.754651 0.05469024 -0.631349 0.773568 0.054874 -0.6340421 0.7713492 0.05630743 -0.622434 0.7806442 0.05667388 -0.6242678 0.779152 0.05664432 -0.6240642 0.7793173 0.05664402 -0.6240307 0.7793441 0.05841255 -0.6141255 0.7870438 0.05975687 -0.6013227 0.7967686 0.05816948 -0.6104747 0.7898968 0.05823004 -0.61166 0.7889749 0.05923753 -0.5557528 0.8292345 0.05926859 -0.5627774 0.824481 0.06082373 -0.5088995 0.8586744 0.06085532 -0.5432121 0.8373872 0.06012308 -0.526459 0.848072 0.06058174 -0.5360493 0.8420101 0.06146621 -0.4976507 0.8651969 0.06000047 -0.5140938 0.8556329 0.06158685 -0.4537836 0.8889812 0.06061106 -0.4332199 0.8992479 0.06112957 -0.4127393 0.9087957 0.06195384 -0.4104518 0.9097753 0.06152623 -0.4209178 0.9050098 0.06143456 -0.4194217 0.9057103 0.0606718 -0.411122 0.9095591 0.0617702 -0.3948534 0.9166653 0.06112974 -0.48327 0.8733347 0.06076323 -0.4636137 0.8839516 0.06116008 -0.3523116 0.9338822 0.06097793 -0.3474949 0.9356971 0.06235069 -0.3821002 0.9220151 0.06131345 -0.3681859 0.9277284 0.06106948 -0.3666 0.9283722 0.06253314 -0.2502242 0.9661664 0.06171047 -0.2787654 0.9583745 0.06271666 -0.2566653 0.9644634 0.06235116 -0.3033632 0.9508329 0.06244313 -0.3455738 0.9363117 0.06134396 -0.3176458 0.9462231 0.06134307 -0.1193901 0.9909507 0.06146544 -0.1630636 0.9846991 0.06232076 -0.1519565 0.9864205 0.061984 -0.189126 0.9799946 0.06277793 -0.1853123 0.9806724 0.06180131 -0.1699613 0.983511 0.06106936 -0.03729474 0.9974367 0.06317389 -0.04632747 0.9969268 0.06228935 -0.02032566 0.9978511 0.05707114 0.4904153 0.8696181 0.05945098 0.4407247 0.8956714 0.05786478 0.4367327 0.8977284 0.06094598 0.05505585 0.9966216 0.06003183 0.1012942 0.9930437 0.06161826 0.1147828 0.9914778 0.0629 0.03436458 0.9974281 0.06280791 0.05832159 0.9963202 0.06256335 -0.1608641 0.9849917 0.06280875 -0.172892 0.9829362 0.06299179 -0.1458517 0.9872991 0.05951297 0.2130869 0.9752191 0.06122153 0.1526571 0.9863812 0.06140369 0.1817697 0.9814221 0.06250321 0.1435927 0.9876613 0.06235033 0.1572951 0.9855815 0.05731564 -0.5686091 0.8206088 0.05337828 -0.4846163 0.8730967 0.05447608 -0.4804274 0.8753411 0.05966436 0.3543545 0.9332058 0.06045895 0.3591219 0.9313304 0.05984747 0.3807533 0.9227379 0.06061017 0.3141903 0.9474234 0.06079345 0.2535809 0.965402 0.06103771 0.2829403 0.9571935 0.0594204 -0.5511115 0.8323133 0.06357163 -0.2769013 0.9587933 0.06357121 -0.2916097 0.9544227 0.06351095 -0.2722029 0.9601417 0.05871886 0.4486014 0.8918009 0.05652105 0.4958716 0.8665546 0.05511844 0.5551522 0.8299205 0.05896264 0.4029725 0.9133108 0.0619834 -0.1030615 0.9927419 0.06262528 -0.1160948 0.9912619 0.0612204 -0.416824 0.9069233 0.06106859 -0.4154251 0.9075751 0.06094652 -0.4141739 0.9081551 0.06073319 -0.4123147 0.9090149 0.06207627 -0.4397835 0.8959559 0.06167858 -0.374863 0.9250263 0.06164854 -0.37334 0.9256439 0.06158864 -0.3716379 0.9263327 0.06149643 -0.3702299 0.9269024 0.06180065 -0.415728 0.907387 0.06097674 -0.3651891 0.9289343 0.06180173 -0.3307995 0.9416752 0.06158685 -0.3246588 0.9438239 0.06225919 -0.3000345 0.9518945 0.06204527 -0.2899314 0.9550341 0.06238067 -0.2387802 0.969068 0.06158787 -0.2187316 0.9738395 0.06271755 -0.140237 0.9881296 0.06283843 -0.1288813 0.9896671 0.0614342 -0.08816862 0.9942093 0.06268554 -0.06857562 0.9956747 0.06195294 0.007202386 0.9980531 0.06177115 0.08011329 0.99487 0.06238168 0.1296769 0.9895921 0.061984 0.1692276 0.983626 0.06186139 0.2438443 0.9678394 0.06073403 0.3373333 0.9394242 0.0592069 0.4150282 0.90788 0.05920791 0.4264194 0.9025857 0.05908584 0.438688 0.8966949 0.05487275 0.4991959 0.86475 0.06137394 -0.2765644 0.9590336 0.06299161 -0.2157402 0.9744169 0.05621576 0.5042939 0.8617004 0.05569761 0.501401 0.8634204 0.05649042 0.5072238 0.859961 0.05679619 0.512417 0.8568565 0.05667477 0.5096462 0.8585154 0.05749791 0.5631073 0.8243811 0.05682665 0.5140952 0.8558487 0.05856549 0.5347805 0.8429591 0.05554497 0.544768 0.8367453 0.05282884 0.6375477 0.7685975 0.0546301 0.5779194 0.8142634 0.05411112 0.5803289 0.8125826 0.05719262 0.5069823 0.8600569 0.05713182 0.5083271 0.8592669 0.05731457 0.5108873 0.8577351 0.05719351 0.5089738 0.8588799 0.05716252 0.5075962 0.8596968 0.05710202 0.508364 0.8592471 0.05774259 0.5238648 0.8498421 0.05328661 0.5979946 0.7997269 0.0574975 0.5267252 0.8480889 0.05777251 0.5240732 0.8497115 0.05145442 0.6544417 0.7543597 0.05746805 0.4696632 0.8809733 0.0578944 0.5221793 0.8508685 0.05777317 0.4594085 0.8863444 0.05758982 0.4643507 0.8837771 0.0582304 0.4498818 0.8911878 0.05859655 0.4455171 0.8933538 0.05798691 0.4540989 0.8890622 0.05896264 0.442586 0.8947855 0.05349999 0.538693 0.8408018 0.05145561 0.59586 0.8014383 0.05707126 0.417231 0.9070067 0.05868875 0.3876268 0.9199462 0.05896335 0.3789281 0.9235458 0.05929946 0.3699582 0.927154 0.05526947 0.4500911 0.8912706 0.05337792 0.5021315 0.8631424 0.06018376 0.3527101 0.9337952 0.06067109 0.3443118 0.936893 0.05969488 0.3613433 0.9305201 0.06003105 0.3127903 0.9479233 0.05932897 0.3054346 0.950363 0.05835247 0.3455066 0.9366003 0.06012231 0.2950268 0.9535955 0.06033545 0.2791547 0.9583488 0.06128215 0.2542538 0.9651941 0.06186199 0.2456168 0.967391 0.06061041 0.2368872 0.9696447 0.06091618 0.2069197 0.9764598 0.06131291 0.1912024 0.9796339 0.0617702 0.1760939 0.9824334 0.06225794 0.1290022 0.989688 0.06225979 0.1617535 0.9848653 0.06204497 0.1138356 0.9915603 0.06180089 0.1328186 0.9892117 0.06293112 0.07993042 0.994812 0.06351065 0.06479245 0.9958757 0.06241202 0.09650212 0.9933741 0.0628696 0.03347957 0.9974601 0.06387716 0.02823048 0.9975585 0.06357097 -0.003692746 0.9979705 0.06308311 0.01358097 0.9979159 0.06409049 -0.02792513 0.9975534 0.06384533 -0.06424206 0.99589 0.06244194 -0.1200619 0.9908007 0.04666441 -0.5330243 0.8448122 0.04760962 -0.5234623 0.8507178 0.04663383 -0.5326884 0.8450256 0.06238132 -0.1497884 0.9867482 0.06387656 -0.2549874 0.9648323 0.0636627 -0.2647832 0.9622042 0.06366217 -0.3093996 0.9487988 0.06131279 -0.3640314 0.9293665 0.05969554 -0.3044902 0.9506431 0.06082481 -0.515409 0.854783 0.05810898 -0.4243116 0.9036498 0.06140404 -0.478079 0.8761678 0.05636876 -0.4439005 0.8943015 0.06384688 -0.3313508 0.941345 0.06174075 -0.4392659 0.8962331 0.06415081 -0.3563697 0.9321402 0.06192374 -0.3996509 0.9145734 0.06109893 -0.3687912 0.9275021 0.0644564 -0.3862197 0.920152 0.06335693 -0.3821865 0.9219108 0.0610997 -0.3445941 0.9367613 0.06225961 -0.3795092 0.9230908 0.06146597 -0.3783792 0.9236078 0.04944103 -0.5034749 0.8625941 0.05386632 -0.5970467 0.800396 0.04657214 -0.5321315 0.8453798 0.06229031 -0.1410613 0.9880393 0.06231898 -0.1258893 0.990085 0.06228858 -0.1326647 0.9892019 0.0641815 -0.2471737 0.9668433 0.06460791 -0.241677 0.9682036 0.06515824 -0.2381405 0.9690427 0.06390726 -0.2350896 0.9698705 0.06305241 -0.186197 0.9804872 0.0637235 -0.1289119 0.9896066 0.06341791 -0.1181074 0.9909737 0.06338822 -0.09006196 0.9939169 0.0527063 0.6658333 0.7442366 0.05093663 0.71937 0.6927572 0.05383527 0.6750777 0.7357798 0.05652123 0.6079394 0.7919692 0.04977685 0.7578844 0.6504872 0.05185186 0.7316643 0.6796903 0.05310404 -0.604074 0.795157 0.05539232 -0.5794072 0.8131538 0.05585008 -0.4627627 0.8847211 0.0577116 -0.5207476 0.8517578 0.05881041 -0.4774416 0.8766932 0.06204545 -0.4102998 0.9098377 0.06173962 -0.4240292 0.9035417 0.06070232 0.2656987 0.9621432 0.05130189 0.6927442 0.7193565 0.9947544 -0.003805279 -0.1022214 0.9947482 4.99912e-4 -0.1023519 0.9844833 0 0.1754789 0.984484 0 0.1754745 0.9844891 0 0.175446 0.9844829 0 0.1754808 0.9844889 0 0.1754472 0.9844842 0 0.1754738 0.984489 0 0.1754463 0.984489 0 0.1754469 0.1754635 0 -0.984486 0.1755019 -1.71044e-6 -0.9844791 0.1754481 -1.92128e-6 -0.9844887 0.1754978 0 -0.9844799 0.9844874 0 0.1754556 0.9844861 6.08346e-6 0.1754634 0.9844846 4.89901e-6 0.1754708 0.9844871 0 0.175457 0.9844881 0 0.175451 -0.1754499 0 0.9844884 -0.1754536 -7.56814e-7 0.9844878 -0.1754496 0 0.9844884 0.9844858 0 0.1754643 0.984485 0 0.1754694 0.9844822 -1.07197e-5 0.1754844 0.9844853 0 0.1754671 0.9844889 -1.30445e-5 0.1754471 0.9844856 -1.66976e-6 0.1754654 0.9844853 3.49722e-6 0.1754675 0.9844864 0 0.1754614 0.9844859 -1.66482e-6 0.1754644 0.9844861 0 0.175463 0.984488 0 0.1754519 0.9844838 -1.53664e-5 0.1754756 -0.1754925 6.42947e-6 0.9844807 -0.1754523 0 0.984488 -0.1754357 -6.73502e-6 0.9844909 -0.1754463 7.73636e-6 0.984489 -0.1754338 -4.9723e-6 0.9844913 -0.1754714 1.54631e-5 0.9844846 -0.1754571 1.37391e-6 0.9844872 -0.1754748 3.08482e-5 0.984484 -0.1754471 -2.06024e-5 0.9844889 -0.1754487 7.77884e-6 0.9844886 -0.1754525 -1.64023e-5 0.984488 -0.1754876 4.59463e-6 0.9844816 -0.1754651 4.93056e-6 0.9844857 -0.1754698 0 0.9844848 -0.1754765 7.05962e-6 0.9844837 -0.1754615 2.06545e-6 0.9844863 -0.175463 1.65946e-6 0.9844861 -0.1754664 -5.00462e-6 0.9844855 -0.1754411 6.27258e-5 0.9844899 -0.1754593 1.64949e-5 0.9844868 -0.1754541 2.29243e-5 0.9844877 -0.1754764 0 0.9844837 -0.1754793 -2.50988e-6 0.9844832 -0.9844846 0 -0.1754712 -0.9844896 0 -0.1754437 -0.9844843 0 -0.1754733 -0.9844841 0 -0.1754737 -0.9844846 0 -0.1754714 -0.9844888 1.6617e-6 -0.1754474 -0.984485 0 -0.1754691 -0.9844844 1.40936e-6 -0.1754721 -0.1754638 0 0.9844859 -0.1754748 0 0.984484 -0.1754709 0 0.9844847 -0.175483 0 0.9844825 -0.9844803 0 -0.175495 -0.9844805 0 -0.1754944 0.1754813 0 -0.9844828 0.1754691 0 -0.984485 0.1754882 0 -0.9844816 0.1754707 0 -0.9844847 -0.9844874 0 -0.1754556 -0.9844857 0 -0.1754649 -0.9844827 0 -0.1754818 -0.9844828 0 -0.1754809 -0.9844873 0 -0.1754559 -0.9844861 0 -0.1754633 -0.9844893 0 -0.1754453 -0.9844888 0 -0.1754476 0.1754528 0 -0.9844878 0.1754574 1.86448e-6 -0.9844871 0.1754662 0 -0.9844855 0.1754738 0 -0.9844841 0.1754283 0 -0.9844922 0.1754357 0 -0.984491 0.1754803 0 -0.984483 0.175486 0 -0.984482 0.1754472 0 -0.9844889 0.1754502 0 -0.9844884 0.1754524 0 -0.984488 0.1754564 0 -0.9844872 0.1754745 1.82401e-6 -0.9844841 0.175455 2.07703e-6 -0.9844875 0.17544 0 -0.9844902 0.1754659 1.91184e-6 -0.9844855 0.1754794 0 -0.9844831 0.1754919 0 -0.9844809 0.1754368 0 -0.9844907 0.1754364 0 -0.9844908 0.1754756 1.87876e-6 -0.9844838 0.1754832 0 -0.9844825 0.1754647 0 -0.9844858 0.1754727 1.92565e-6 -0.9844843 0.9854707 0 -0.1698459 0.9854707 -8.5762e-7 -0.1698454 0.985471 0 -0.1698442 0.985471 0 -0.1698444 0.9854708 0 -0.1698452 0.9854707 2.9639e-6 -0.1698454 0.9854708 1.4419e-6 -0.1698446 0.985471 0 -0.1698439 0.9854717 5.7776e-6 -0.1698401 0.9854747 -2.66956e-5 -0.1698225 0.985478 6.20086e-6 -0.1698036 0.9854766 -2.25722e-5 -0.169812 0.9854698 -6.14787e-6 -0.1698507 0.9854701 0 -0.1698493 0.07737344 0.9969757 -0.007279515 0.07590657 -0.9970903 -0.007003426 0.07549959 -0.997124 -0.006601333 0.07725811 -0.9969819 -0.007636725 0.07872372 -0.9968675 -0.007599771 0.08013331 -0.9967542 -0.007740914 0.07942438 -0.9968146 -0.007251739 0.08296877 -0.9965206 -0.007945418 0.08254069 -0.9965543 -0.008167684 0.08440685 -0.996397 -0.008288145 0.08395934 -0.9964616 -0.003891468 0.08723849 -0.9961504 -0.008596777 0.08866941 -0.9960209 -0.008951187 0.09008967 -0.9958938 -0.008921563 0.0918982 -0.9957243 -0.00938034 0.03000003 -0.9969911 0.0714752 0.0219435 -0.9948753 0.0987001 0.01892197 -0.9941998 0.1058717 0.07444834 -0.9972003 -0.00700736 0.07241654 -0.9973554 -0.006185472 0.07303959 -0.9973065 -0.006710827 0.0716207 -0.9974101 -0.006609082 0.06951475 -0.997565 -0.005652189 0.07018208 -0.9975142 -0.006316423 0.06875669 -0.9976139 -0.00625354 0.06669694 -0.9977596 -0.005223393 0.0673474 -0.9977115 -0.006017923 0.06591355 -0.9978061 -0.00620377 0.06419855 -0.9979219 -0.005518198 0.06449586 -0.9978999 -0.006025075 0.06299734 -0.9979904 -0.006826579 0.06173902 -0.9980826 -0.004393219 0.01925754 -0.9959301 0.08804762 0.02298051 -0.9963117 0.08267498 0.01071202 -0.9919787 0.1259505 0.02341127 -0.9997102 0.005608797 0.03802639 -0.9992762 -0.00112915 0.03894269 -0.9992353 -0.003540217 0.7086374 0.02591121 -0.705097 0.03811854 -0.9992614 0.00488305 0.04672527 -0.9987493 0.01779282 0.05050826 -0.9987214 -0.00213629 0.0506615 -0.9986125 0.01437443 0.05029606 -0.9980172 0.03784412 0.06106817 -0.9978138 0.02526956 0.06268668 -0.9977687 0.02298104 0.05740642 -0.9978834 0.03054958 0.04483234 -0.9978182 0.04846411 0.05533057 -0.9979037 0.03357064 0.09029197 -0.995898 -0.005882918 0.09113496 -0.9958204 -0.006036221 0.09192246 -0.995747 -0.006188273 0.08981412 -0.9959419 -0.00575602 0.09085255 -0.9958441 -0.00635761 0.08757519 -0.9961375 -0.006387114 0.0941199 -0.9955403 -0.006405532 0.08705747 -0.9961837 -0.006247997 0.09006494 -0.9959157 -0.006344199 0.08913409 -0.9959999 -0.006268262 0.09856665 -0.9951066 -0.006881952 0.08742719 -0.9961512 -0.006268501 0.08890837 -0.9960203 -0.006239354 0.09232473 -0.9957089 -0.006322562 0.09131187 -0.9958038 -0.006086409 0.08894568 -0.9960186 -0.005978345 0.08771091 -0.9961307 -0.005511224 0.08596068 -0.996253 -0.009529232 0.08814448 -0.9960604 -0.009714186 0.09108102 -0.9957968 -0.009641528 0.08866208 -0.9960459 -0.005626976 0.0889253 -0.9960206 -0.005947947 0.08588796 -0.9962942 -0.004633247 0.08562892 -0.9963169 -0.004507541 0.08427804 -0.9964357 -0.003643393 0.08377492 -0.9964791 -0.003357052 0.08044862 -0.9967577 -0.001464903 0.08771115 -0.9961349 -0.004699885 0.07895457 -0.9968777 -0.001066505 0.08411097 -0.9964526 -0.002746701 0.08377391 -0.9964672 -0.005920588 0.08737689 -0.9961515 -0.00689733 0.08335477 -0.9964784 -0.009096205 0.07437366 -0.997224 0.003601133 0.08175981 -0.9966518 -8.24007e-4 0.08267658 -0.9965754 -0.001464903 0.0807349 -0.9966934 -0.009183704 0.08057004 -0.996749 2.74671e-4 0.08118027 -0.9966865 -0.005066096 0.0781725 -0.9968966 -0.009286403 0.07162743 -0.9974129 0.006103694 0.07925868 -0.9968527 0.001678526 0.07809871 -0.9969415 0.002899289 0.07880079 -0.996882 -0.004089534 0.06802666 -0.9976333 0.01001018 0.07672375 -0.9970428 0.00439465 0.07550489 -0.9971287 0.005798637 0.06637847 -0.9977225 0.01199388 0.07544738 -0.9971057 -0.009384572 0.06476211 -0.9978012 0.01409995 0.0741012 -0.997223 0.007446706 0.0712015 -0.9974314 -0.007812917 0.07406926 -0.9972038 -0.00991863 0.07135409 -0.9974009 -0.0100103 0.07159644 -0.9973762 0.01071196 0.07294011 -0.9972962 0.008942008 0.06164753 -0.9979273 0.01846373 0.0632041 -0.9978686 0.01623588 0.07034581 -0.9974458 0.01239061 0.06009203 -0.9979733 0.02093607 0.06863623 -0.997591 -0.01007109 0.06839263 -0.9976298 -0.007568657 0.05853593 -0.9980102 0.02343875 0.06882113 -0.9975251 0.01440513 0.07126224 -0.9974576 -2.44153e-4 0.06839245 -0.9976576 0.001403808 0.06988888 -0.997519 -0.008453786 0.06528091 -0.9978612 0.003387629 0.06543338 -0.9978287 -0.007507741 0.06438082 -0.9978654 -0.01095187 0.05203551 -0.9980444 0.03463947 0.06442654 -0.9977118 0.02050906 0.06302082 -0.9979873 -0.007049739 0.06180149 -0.9980717 0.005798637 0.06036663 -0.9981561 -0.006347954 0.05606263 -0.9983856 -0.009125053 0.05951184 -0.9981814 -0.009613394 0.05795586 -0.9982818 0.008636891 0.05408012 -0.9984685 0.01165831 0.05447566 -0.9985072 -0.003967404 0.03317445 -0.9972185 0.06674569 -0.0293594 0.9995639 -0.003173947 -0.03369271 0.9994295 -0.00238043 0.9919297 0.03479164 -0.1219235 0.01265215 -0.9998797 0.008979558 -0.1100813 -0.9924101 0.05481171 -0.1102043 -0.992388 0.05496478 -0.1287603 -0.989706 0.0624727 -0.06854599 -0.9969078 0.03842359 -0.06842452 -0.9969173 0.03839343 -0.05795556 -0.9977275 0.0343644 -0.1107843 -0.9911078 0.07370358 -0.1114845 -0.9869115 0.1165201 -0.1297075 -0.9825419 0.1333698 0.01627331 -0.9998333 0.008283793 0.008549332 -0.9999063 0.01070511 -0.007721364 -0.9998409 0.01608359 -0.008972465 -0.9998219 0.01660215 -0.002655148 -0.9998928 0.01440495 -0.5488294 -0.7676836 0.3308297 -0.5011883 -0.7196761 0.4804962 -0.7473219 -1.22077e-4 0.6644624 -0.55725 0.7933465 0.2450997 -0.5574995 0.7932931 0.2447052 -0.3179811 0.9374018 0.1420065 -0.1890041 -0.978103 0.08713167 -0.153692 -0.9831895 0.09857529 -0.1890339 -0.9747119 0.1191762 -0.04022461 -0.9988097 0.02758955 -0.03250271 -0.9991622 0.02487295 -0.03644007 -0.9989895 0.02630764 -0.05765014 0.9977537 0.03412008 -0.04840278 0.9983617 0.03051877 -0.05792534 0.9977325 0.03427296 -0.0346089 0.9966998 0.07342946 -0.02737528 0.9974755 0.06552374 -0.03357058 0.9983294 0.04702937 -0.04242163 0.9957186 0.08212709 -0.04123061 0.9977147 0.05352962 -0.04837197 0.9983556 0.03076273 -0.04883021 0.9983342 0.03073251 -0.04028552 0.9988064 0.02761995 -0.2338388 0.9663324 0.1073364 -0.2335651 0.9665501 0.1059634 -0.1881785 0.9782785 0.08694791 0.006836295 0.9995053 0.03070235 0.01132243 0.9995825 0.02658188 0.006500482 0.9998545 0.01577818 -0.1096841 0.9924676 0.05456739 -0.09436351 0.9943575 0.04846352 -0.1112106 0.9922281 0.05581891 0.04448759 0.99901 -3.29812e-4 -0.007751822 0.9998381 0.01623618 -0.01321482 0.9997496 0.01806735 -0.009155571 0.9998208 0.01657158 0.02396565 0.9996961 0.005774199 0.02012449 0.9997733 0.006960511 0.05610561 0.9984197 -0.0032202 0.04167914 0.9991309 5.72265e-4 0.01650601 0.9998311 0.008096694 0.0607649 0.998143 -0.004276275 0.05622422 0.9984128 -0.003300607 0.05982762 0.9982013 -0.003870189 0.06940031 0.9975457 -0.00927776 0.06759905 0.9976888 -0.006897211 0.06564629 0.9978179 -0.007080376 0.07300078 0.9972908 -0.009064018 0.06955337 0.9975523 -0.007202506 0.07077348 0.9974518 -0.009003043 0.06326657 0.9978606 0.01648044 0.07303208 0.9973016 0.007477164 0.07177978 0.9973794 0.009064018 0.07559651 0.9971293 0.004303216 0.06805688 0.9976291 0.01022374 0.07690858 0.9970344 0.002777218 0.0768826 0.9969995 -0.009016275 0.07952326 0.9967939 -0.008841156 0.08099615 0.9966782 -0.008499443 0.08579701 0.9962914 -0.006512343 0.07803487 0.9969064 -0.009395897 0.08833646 0.9960625 -0.007503986 0.08258527 0.9965782 -0.003387629 0.08459782 0.9964051 -0.004486203 0.07843267 0.9969195 -9.15557e-5 0.09082603 0.9958329 -0.008217632 0.08802807 0.9960973 -0.006433427 0.09085988 0.9958295 -0.008253395 0.08769959 0.9961267 -0.006351172 0.09077972 0.9958368 -0.008253276 0.08855491 0.9960497 -0.006577432 0.08784276 0.9961131 -0.006520152 0.08642375 0.9962379 -0.006407201 0.09082299 0.9958443 -0.006754755 0.08795607 0.9961038 -0.00640136 0.08795559 0.9961039 -0.006393849 0.09113633 0.9958035 -0.008343398 0.08894032 0.9960148 -0.006664216 0.08581066 0.9962903 -0.006497383 0.08645868 0.9962348 -0.006424248 0.09204638 0.9957228 -0.00797522 0.0946542 0.9954865 -0.006872236 0.08862626 0.9960434 -0.006558001 0.08773785 0.9961233 -0.006361246 0.08821648 0.9960805 -0.006451368 0.08867728 0.9960422 -0.006039023 0.09115391 0.9957991 -0.008664488 0.0914995 0.9957661 -0.008815586 0.08838087 0.9960694 -0.005873978 0.08811163 0.9960978 -0.005061686 0.08903241 0.9960002 -0.007549703 0.09119027 0.9957923 -0.009060323 0.08749848 0.9961463 -0.006073296 0.08575946 0.9963052 -0.004608392 0.08350336 0.9964931 -0.005378246 0.08227986 0.9966056 -0.002716183 0.07956206 0.99683 -9.15559e-5 0.07263624 0.9973449 0.005218803 0.08060032 0.996746 -9.76604e-4 0.07812929 0.9969424 0.001403868 0.0699802 0.9975157 0.008087515 0.07412803 0.9972099 -0.008813798 0.07434481 0.9972158 0.005798637 0.06479227 0.9977957 0.01434403 0.06640869 0.9977174 0.01223796 0.07413113 0.9972458 -0.002349972 0.07153761 0.9974376 -9.15584e-4 0.06863766 0.997612 -0.007690787 0.06515896 0.9978329 -0.009155809 0.06372267 0.9979255 -0.009186029 0.06591618 0.9977802 -0.009485185 0.06891101 0.9976227 6.10372e-4 0.06561589 0.9978199 -0.007080376 0.06659179 0.9977785 0.001922667 0.05710071 0.998332 -0.008545219 0.05871802 0.9982373 -0.008636772 0.05469006 0.9984908 -0.005035579 0.06054973 0.9981252 -0.008942067 0.06250238 0.9980247 -0.006347894 0.02672392 0.9996307 0.004935681 0.05962413 0.9982131 -0.003947615 0.03742033 0.999298 0.001830279 0.03534942 0.9993721 0.002422273 0.0595116 0.9982204 -0.003819286 0.06048059 0.9981605 -0.004236757 0.03490817 0.9993872 0.002604484 0.0118336 0.999883 0.009703576 0.05795025 0.9983162 -0.002555847 0.06296044 0.9980055 -0.004594504 0.09132122 0.9957798 -0.009116888 0.09123766 0.9957868 -0.009181022 0.09106677 0.9958036 -0.00906831 0.08252459 0.9965614 -0.007424652 0.07992744 0.9967732 -0.00740242 0.07867765 0.9968723 -0.007443547 0.07774686 0.9969483 -0.007044255 0.07601428 0.9970791 -0.007437467 0.07465261 0.9971861 -0.006858289 0.07321947 0.9972927 -0.006808698 0.07410055 0.9972309 -0.006309211 0.07185137 0.9973931 -0.006670951 0.07047647 0.9974931 -0.006382167 0.07097589 0.9974603 -0.00596106 0.06914359 0.9975864 -0.006379544 0.06782996 0.9976786 -0.006039023 0.06839025 0.9976425 -0.005691587 0.06649518 0.9977718 -0.005461871 0.06652665 0.99777 -0.005414307 0.06511044 0.9978621 -0.005646646 0.06347054 0.9979691 -0.005411088 0.06413602 0.9979321 -0.004262089 -0.02414071 0.9994744 0.02163809 -0.02328604 0.9994999 0.02139383 -0.02896225 0.999305 0.02346885 0.03516048 0.9993792 0.002229154 0.02265477 -0.999724 0.006229519 0.001983702 0.9998173 0.01901298 0.002075254 0.9993796 0.03515803 0.01280003 -0.9998742 0.009370923 0.002166807 -0.9999151 0.01284837 0.006347835 -0.9999144 0.0114445 0.001403808 -0.9999154 0.01293992 -0.04016351 -0.9988079 0.02774208 -0.03335702 -0.9991248 0.02523905 -8.42834e-4 -0.999908 0.01354384 -0.04880064 0.998048 0.03897333 -0.04968529 0.9969111 0.06082481 -0.0679351 0.9969613 0.03811812 -0.06848561 0.9969177 0.03827136 -0.0831651 0.9880626 0.1296765 -0.09555608 0.9902005 0.1018431 -0.09695869 0.9844806 0.1462774 -0.1114556 0.9869254 0.1164302 -0.1125528 0.9798018 0.1652891 -0.1290348 0.9880873 0.08386653 -0.1297051 0.9825549 0.1332759 -0.1534184 0.975841 0.1555547 -0.1535095 0.9832547 0.0982095 -0.05832189 -0.9976988 0.03457808 -0.05771082 -0.9977481 0.03418093 -0.06845486 -0.9969141 0.03842383 -0.02664273 -0.9993941 0.02240067 -0.02664333 -0.9993851 0.02279788 -0.03006142 -0.9992609 0.02395755 -0.02890127 -0.9993075 0.02343839 -0.02325558 -0.999502 0.02133285 -0.15336 -0.9642911 0.2159247 -0.1864394 -0.9480668 0.2577009 -0.1534505 -0.9758211 0.1556479 0.006776511 -0.999909 0.01166939 -0.1882122 -0.9782639 0.08704084 -0.1527491 -0.9856213 0.07223922 -0.1530544 -0.9855605 0.07242232 -0.08389735 -0.9805216 0.1775913 -0.09738636 -0.9755423 0.1970617 -0.08328634 -0.9880526 0.1296752 0.02381187 -0.9997047 0.004863202 0.01651674 -0.9998335 0.007763028 0.002014219 -0.9999189 0.01257371 0.001861631 -0.9999162 0.01281785 -0.002807736 -0.9998924 0.01440489 0.006073296 0.9998995 -0.01281803 0.06015288 -0.9981845 -0.003082394 0.0124517 0.9999225 0 0.03100252 -0.9995126 0.003681123 -0.2272129 -0.9235007 0.3090645 -0.1881195 -0.9639141 0.1883636 -0.9160291 -3.0519e-5 0.4011118 -0.9164017 -1.83116e-4 0.40026 0.02324676 -0.9997115 0.006045401 0.003775715 -0.9999215 0.0119546 -0.3092244 0.9012432 0.3035477 -0.2970446 0.8673593 0.3993149 -0.2271881 0.9234632 0.3091945 -0.1878774 0.9783607 0.0866751 -0.01907444 -0.9996225 0.01977634 -0.02398818 -0.9994774 0.02166867 -0.4516232 0.6664174 0.5932323 -0.5012222 0.7195894 0.4805909 -0.07111018 0.9907819 0.1153023 -0.07184153 0.9843882 0.1606822 -0.0612213 0.9874151 0.1458203 0.03835201 -0.9992634 0.001428782 -0.03436446 0.9994092 -7.01939e-4 0.9930685 0.03839331 -0.1110904 0.994165 0.03903412 -0.100561 0.02036881 -0.9997684 0.006946325 0.04219126 -0.9991096 3.75406e-4 0.0292924 -0.999562 0.004244625 0.05459195 -0.9985052 -0.002651929 0.01663255 -0.9998256 0.008502781 0.03778523 -0.9992845 0.001716196 0.04970753 -0.998762 -0.001920998 0.04038488 -0.9991837 0.001007735 0.04444152 -0.9990121 1.31301e-4 0.9921873 0.03747785 -0.1189953 0.03792476 -0.9992796 0.001387834 0.05059313 -0.9987177 -0.001816034 0.05053639 -0.9987207 -0.001795232 0.01516807 -0.9953873 0.09473192 0.04862982 -0.9988158 -0.0014081 0.005340754 -0.9902719 0.1390433 0.01089519 -0.9947629 0.1016278 -0.08054083 -0.9958193 0.04309344 -0.09497642 -0.9933767 0.06467062 -0.09436613 -0.9943543 0.04852592 -8.24009e-4 -0.9879564 0.1547306 0.006470084 -0.9940791 0.108466 -0.06064099 -0.9928405 0.1029097 -0.04974609 -0.9969062 0.06085503 -0.0511493 -0.9944517 0.09192228 -0.04876911 -0.9983326 0.03088504 -0.0402854 -0.9988039 0.02771145 -0.04043769 -0.9987961 0.0277723 0.9699868 0.02938979 -0.2413751 -0.02633786 0.9996497 -0.002655148 -0.02478164 0.9996895 -0.002655148 -0.03549379 -0.9931865 0.1109983 -0.0275591 -0.9974684 0.06555581 -0.02823007 -0.9944312 0.1015367 -0.04129272 -0.9977105 0.05356156 -0.04074347 -0.9985669 0.03470063 -0.03640884 0.9993364 0.00112915 0.03122091 -0.9994981 0.005371332 0.03140425 -0.9993832 0.01571738 0.01565605 -0.9934148 0.1134991 0.02667373 -0.9966955 0.07672518 -0.0199899 -0.9991602 0.03576821 -0.01382499 -0.9994292 0.03082394 -0.02075278 -0.9980876 0.05822986 0.02005076 -0.9952458 0.09530991 -0.009308159 -0.9841379 0.1771613 0.001678526 -0.9931797 0.1165825 -0.01434403 -0.9895859 0.1432267 -0.008636772 -0.9909716 0.1337938 -0.01941007 -0.9788062 0.2038671 -0.01443564 -0.9985647 0.0515778 -0.00814855 -0.9996183 0.02639889 -0.008575856 -0.9989247 0.04556518 -0.01486283 -0.9963017 0.08462995 -0.008881032 -0.996968 0.07730489 -0.0326246 0.9991552 0.02499485 -0.03244179 0.9991649 0.0248425 -0.02575826 0.9994166 0.02243167 0.007954597 0.9999108 0.01073014 -0.04013186 0.998811 0.02768027 -0.04004073 0.9988222 0.02740591 -0.03006142 0.9992609 0.02395755 -0.01788407 0.9996481 0.01959311 -0.01922678 0.9996116 0.02017289 0.03054392 0.9995263 0.003778994 0.03263425 0.9994622 0.003208339 0.03533661 0.9993732 0.002169191 0.09049022 0.9958548 -0.009210944 0.08999699 0.9959017 -0.008969068 0.09104931 0.9958056 -0.009013235 0.08814966 0.9960899 -0.005867779 0.08767622 0.9961288 -0.006363213 0.09077823 0.9958478 -0.006833612 0.08744877 0.9961491 -0.006320238 0.08939945 0.9959558 -0.008940458 0.08860975 0.9960302 -0.008508861 0.08873867 0.9960166 -0.008743107 0.08984881 0.9959191 -0.008517682 0.08918696 0.9959753 -0.008883357 0.08215284 0.9966106 -0.004280984 0.09067827 0.9958479 -0.008033215 0.08964723 0.9959385 -0.008360743 0.08889132 0.9960271 -0.005349755 0.0906974 0.9958461 -0.008041799 0.0878719 0.9961193 -0.005008161 0.08893245 0.9960233 -0.005357205 0.08802545 0.9960815 -0.00855571 0.0876547 0.996113 -0.008704245 0.08677309 0.9961872 -0.009042799 0.08806341 0.9960756 -0.008847773 0.08960157 0.9959408 -0.00857824 0.08806127 0.9960827 -0.008043587 0.08737003 0.996163 -0.005089521 0.08903205 0.996011 -0.005958139 0.08616763 0.9962707 -0.004471361 0.08754819 0.9961467 -0.005201697 0.08621132 0.9962438 -0.008121609 0.08551865 0.9963067 -0.007725954 0.08557271 0.9962906 -0.009071171 0.08617776 0.9962438 -0.008463203 0.08718085 0.9961573 -0.008383214 0.08207601 0.9966209 -0.003228008 0.08960044 0.995945 -0.008079349 0.0861786 0.9962469 -0.008093357 0.08474457 0.9963952 -0.003864884 0.08833593 0.996058 -0.008086025 0.08402657 0.9964569 -0.003642559 0.08436536 0.996428 -0.003739178 0.08439677 0.996401 -0.007896482 0.08405756 0.9964237 -0.008615374 0.08399099 0.9964317 -0.008339047 0.08399176 0.9964296 -0.008574306 0.08442336 0.9963938 -0.008496403 0.0871793 0.9961651 -0.00741434 0.08442288 0.9963968 -0.008149743 0.08279347 0.9965599 -0.003701686 0.08614182 0.9962614 -0.006550848 0.08275574 0.9965413 -0.007557809 0.082681 0.9965392 -0.008577346 0.0828123 0.9965319 -0.00814712 0.08489501 0.9963532 -0.008565425 0.0828132 0.9965348 -0.007776379 0.08004832 0.9967896 -0.001677453 0.08579862 0.9962812 -0.007914006 0.08050131 0.9967526 -0.001967787 0.08144676 0.9966743 -0.002628862 0.0813204 0.9966584 -0.007689237 0.08153283 0.9966368 -0.00822246 0.08122372 0.9966635 -0.008035778 0.08009141 0.9967575 -0.007748603 0.07583975 0.9971176 0.002227842 0.08489382 0.9963629 -0.007355332 0.08158999 0.9966323 -0.008206963 0.07816308 0.9969404 -6.452e-4 0.08335083 0.9965059 -0.005350708 0.07913339 0.9968634 -0.0011487 0.07999116 0.9967678 -0.007440805 0.07969367 0.9967896 -0.007712066 0.08262544 0.9965434 -0.008630394 0.08349382 0.9964787 -0.007680118 0.07758808 0.9969855 -3.79434e-4 0.07696956 0.9970335 6.10385e-5 0.0777933 0.9969694 -4.57787e-4 0.07820862 0.9969047 -0.00802946 0.0782063 0.9969101 -0.007351577 0.08262383 0.9965555 -0.007109045 0.07952338 0.9967959 -0.008610844 0.08179128 0.9966329 -0.00576806 0.07464945 0.9972086 0.001586973 0.07571852 0.9971288 9.7662e-4 0.07724773 0.9969848 -0.007358491 0.08038526 0.9967234 -0.008987963 0.08015507 0.9967767 -0.003379225 0.07400757 0.9972558 0.002014219 0.07537418 0.9971314 -0.006920158 0.07538622 0.9971219 -0.008064508 0.07538336 0.9971306 -0.006923675 0.08038288 0.9967381 -0.007198691 0.07688158 0.997001 -0.00885719 0.07321602 0.997313 0.002472043 0.08051371 0.9967271 -0.007271826 0.0790432 0.9968603 -0.004669308 0.06736028 0.9976702 -0.01080566 0.07260441 0.9973576 0.002533018 0.07286185 0.9973205 -0.006571829 0.07302492 0.9972963 -0.008213818 0.07302069 0.9973084 -0.00663042 0.07802343 0.9969275 -0.006937026 0.07412821 0.9972069 -0.009145975 0.07800948 0.9969286 -0.006928861 0.07657229 0.9970576 -0.003570675 0.07168918 0.9974227 0.002929806 0.07100164 0.9974566 -0.00624597 0.07190221 0.9973844 -0.007385492 0.07060712 0.9974855 -0.006114423 0.07532817 0.9971113 -0.009738445 0.06997972 0.9975396 0.004211544 0.07533001 0.997138 -0.006424844 0.07188528 0.9973686 -0.009406983 0.07391655 0.9972325 -0.007995903 0.06820917 0.9976546 0.005737483 0.06855756 0.9976304 -0.005797028 0.06835085 0.997645 -0.005717515 0.07282596 0.9972906 -0.01038843 0.07007408 0.9975043 -0.00865066 0.06692862 0.9977346 0.006805777 0.06170988 0.9979177 0.01876932 0.06671977 0.9977568 -0.005475342 0.07138359 0.9974173 -0.007965385 0.06549382 0.99782 0.008118033 0.06012213 0.9979664 0.02118003 0.07040774 0.9974585 0.01092582 0.0672149 0.9977228 -0.005616784 0.07021856 0.9974746 -0.01067894 0.05856603 0.9980034 0.02365225 0.06424319 0.9978914 0.009247362 0.06777971 0.9976593 -0.009049355 0.06909608 0.9975293 0.01269608 0.06427443 0.9979194 -0.005072474 0.06680577 0.9977229 -0.009277701 0.06271702 0.9980098 -0.006561636 0.06403636 0.9979351 -0.004976928 0.06762987 0.9976016 0.01474058 0.05697882 0.9980304 0.02624624 0.06228858 0.9979915 0.01153606 0.06229978 0.9980465 -0.004683732 0.0553621 0.9980445 0.02902388 0.06613487 0.9976695 0.0167855 0.06460887 0.9977301 0.01898282 0.05929839 0.9981237 0.01525944 0.04479801 0.998996 -1.89955e-4 0.06103813 0.9981268 -0.004153966 0.06047058 0.9981611 -0.00421971 0.06060689 0.998153 -0.004197895 0.05972629 0.9981954 -0.006225883 0.0611549 0.9981185 -0.004448413 0.06213629 0.9980269 -0.00903356 0.06295245 0.9979721 -0.009422838 0.05374443 0.9980414 0.03201466 0.06121176 0.9981159 -0.004212081 0.05942296 0.9982258 -0.003793954 0.05960702 0.9982149 -0.00378865 0.05969929 0.9981748 -0.009116291 0.05203473 0.9980295 0.03506618 0.06408971 0.9979379 0.003570675 0.06296062 0.9977874 0.02136325 0.05777364 0.9983239 -0.003424823 0.05973631 0.9982064 -0.003951668 0.05767905 0.9983291 -0.003489851 0.06076836 0.9981434 -0.004104852 0.05790579 0.9983155 -0.003636002 0.05788469 0.9983168 -0.003618061 0.06509333 0.9978656 -0.005223453 0.0579546 0.9983126 -0.003640532 0.05713224 0.99835 -0.00576812 0.0580734 0.9983054 -0.00372833 0.05817556 0.9982993 -0.003770172 0.06125104 0.99784 0.02374351 0.05029523 0.9980009 0.03827077 0.05725324 0.9982087 0.01736515 0.05625814 0.9984115 -0.003070294 0.05817955 0.9983 -0.003540694 0.05578821 0.9984382 -0.002987384 0.05811029 0.9983035 -0.003666341 0.05591171 0.9984308 -0.003161787 0.05975282 0.9982058 -0.003870606 0.05615282 0.998417 -0.003258287 0.05589991 0.998432 -0.002979218 0.05748742 0.9983405 -0.003416419 0.05642867 0.9984021 -0.00300765 0.06143492 0.9980965 0.005401849 0.05984812 0.9981916 -0.005646049 0.0594207 0.9978839 0.02639901 0.05496448 0.9982727 0.02075284 0.05439376 0.9985162 -0.002627611 0.0543949 0.9985162 -0.002627909 0.05624109 0.9984124 -0.003144681 0.05439352 0.998516 -0.00271058 0.05438899 0.9985159 -0.002817094 0.05641126 0.9984022 -0.003288269 0.05610233 0.9984204 -0.003044128 0.05444157 0.9985129 -0.002858281 0.05449908 0.9985097 -0.002877771 0.05459499 0.998505 -0.002682566 0.05244243 0.9986214 -0.002279162 0.05646342 0.9983999 -0.003118574 0.05243873 0.998622 -0.00211656 0.0537095 0.9985538 -0.002427518 0.05539196 0.9984295 -0.008392691 0.05691796 0.9983687 -0.00451678 0.05587601 0.9984328 -0.003172814 0.05463272 0.9985022 -0.002935111 0.05752867 0.9979174 0.02917635 0.04852563 0.9979503 0.04171985 0.05234032 0.9986177 -0.004822015 0.05847519 0.9982596 0.007660329 0.04669421 0.9978833 0.04525983 0.05244499 0.9986216 -0.002153873 0.05439007 0.9985162 -0.002709269 0.05281215 0.998602 -0.002265691 0.05444163 0.998513 -0.002833545 0.05251675 0.9986172 -0.00237149 0.05449861 0.9985104 -0.002654016 0.05268764 0.9986087 -0.002230167 0.05267524 0.9986088 -0.002441585 0.05268788 0.9986081 -0.002445578 0.05256283 0.9986153 -0.002190351 0.05458092 0.9985058 -0.002675414 0.05052161 0.9987217 -0.001637935 0.05322521 0.9985537 -0.007599234 0.05142486 0.9986502 -0.007294058 0.05361908 0.9985577 -0.002740621 0.05294972 0.9983235 0.02337718 0.04483282 0.9977974 0.04889184 0.05560564 0.9979414 0.03195339 0.05077427 0.9987087 -0.001749873 0.05241787 0.9986227 -0.002235412 0.0528537 0.9985994 -0.002411484 0.05082988 0.9987056 -0.001877129 0.05045223 0.9987249 -0.001822054 0.05079972 0.9987069 -0.001985967 0.05006575 0.9987447 -0.001585483 0.05083 0.9987055 -0.001990854 0.05069351 0.9987127 -0.001778006 0.05256158 0.9986154 -0.002153158 0.0498991 0.9987452 -0.004242181 0.05545371 0.9984117 0.009949266 0.05398887 0.9985356 -0.003448665 0.05098468 0.9986975 -0.002009391 0.05362242 0.9979508 0.03491407 0.04293978 0.9976866 0.05270576 0.05096697 0.9983425 0.02673476 0.05052274 0.9987215 -0.001699447 0.04883384 0.9988062 -0.0012483 0.04886424 0.9988046 -0.00135219 0.04870361 0.9988122 -0.001461386 0.04945617 0.9987753 -0.001471281 0.0487836 0.9988083 -0.001493215 0.04873484 0.9988111 -0.001234173 0.05069178 0.9987129 -0.001689672 0.05052447 0.9987213 -0.001832008 0.04658764 0.998914 -6.29862e-4 0.04859125 0.9988182 -0.001148045 0.05047786 0.9987238 -0.001709043 0.05179029 0.9985734 0.01300096 0.04878401 0.9988083 -0.001458168 0.05145537 0.9979476 0.03811848 0.04779243 0.9988504 -0.003723263 0.04940974 0.9987547 -0.006927728 0.04831153 0.9983366 0.03146505 0.04684138 0.9989021 -7.2372e-4 0.04861539 0.998817 -0.001205682 0.04856061 0.9988194 -0.001308023 0.04685151 0.9989016 -8.09494e-4 0.04890447 0.9988024 -0.00149101 0.046952 0.9988967 -9.75903e-4 0.04683518 0.9989022 -9.98812e-4 0.04683488 0.9989024 -7.53711e-4 0.0468083 0.9989034 -9.8982e-4 0.04671847 0.9989079 -7.15096e-4 0.0465936 0.9989136 -8.80489e-4 0.0487346 0.9988111 -0.001192033 0.04859763 0.9988175 -0.001392424 0.04448163 0.9990102 -7.32034e-5 0.04677534 0.9989051 -9.45306e-4 0.04718291 0.9988678 -0.006073296 0.04513698 0.9989655 -0.005554378 0.04574793 0.9989479 -0.003204464 0.04095625 0.9975385 0.0569176 0.04922658 0.99793 0.04138326 0.03888142 0.9973667 0.06122142 0.04664707 0.9989113 -6.87153e-4 0.04477608 0.9989971 -1.85323e-4 0.04659885 0.9989134 -7.71982e-4 0.04465562 0.9990024 -2.35835e-4 0.04483377 0.9989945 -2.99574e-4 0.04676389 0.9989056 -9.43296e-4 0.0447303 0.998999 -4.2034e-4 0.04475885 0.9989977 -4.64633e-4 0.04469126 0.9990009 -4.40803e-4 0.04475778 0.9989979 -2.08946e-4 0.04463291 0.9990035 -1.669e-4 0.04671877 0.9989079 -6.70621e-4 0.04364234 0.9990438 -0.002655148 0.04724365 0.9987404 0.01690763 0.04608321 0.9989376 5.18818e-4 0.04470753 0.999 -4.09494e-4 0.04696917 0.9978898 0.04483282 0.03680551 0.997168 0.06558465 0.04449629 0.9982681 0.03848409 0.04265081 0.9990901 3.77365e-4 0.04271405 0.9990873 3.56282e-4 0.04053431 0.9991779 8.00402e-4 0.04251623 0.9990957 3.18513e-4 0.04444497 0.9990118 -3.21192e-4 0.04251623 0.9990958 1.6974e-4 0.04256713 0.9990936 1.51915e-4 0.04259353 0.9990925 1.07609e-4 0.04256689 0.9990937 1.17251e-4 0.04259288 0.9990925 3.70301e-4 0.04248625 0.9990971 4.07089e-4 0.04463183 0.9990035 -1.21198e-4 0.04144507 0.9991387 -0.002044737 0.04272687 0.9990766 -0.004516839 0.04233223 0.9991036 5.0579e-4 0.04256063 0.999094 1.59169e-4 0.04458886 0.9978322 0.04840373 0.04168891 0.9981544 0.04416096 0.04036062 0.9991847 0.001008987 0.04213762 0.9991118 3.92631e-4 0.04022234 0.9991904 9.22734e-4 0.03769993 0.999287 0.002054035 0.04022222 0.9991905 7.82144e-4 0.04030907 0.999187 7.6573e-4 0.04036271 0.9991849 7.11703e-4 0.04035866 0.999185 7.13266e-4 0.04036241 0.9991847 9.77457e-4 0.04023742 0.9991897 0.001021027 0.04011929 0.9991946 8.41981e-4 0.04248595 0.999097 4.56177e-4 0.04233938 0.9991033 2.40527e-4 0.03770488 0.9992874 0.001785516 0.04011291 0.9991946 0.001113414 0.04046863 0.9991737 -0.003814876 0.04126214 0.9991429 0.003326594 0.04034012 0.9991858 7.59957e-4 0.03778249 0.999283 -0.002502501 0.03909528 0.9992347 -0.001342833 0.03473019 0.9969223 0.07028442 0.04202443 0.9988816 0.02166837 0.04208528 0.9977486 0.05221748 0.03250235 0.9966481 0.07507592 0.03958982 0.9992159 5.21539e-4 0.03795254 0.9992784 0.001514136 0.03753858 0.9992941 0.001525819 0.03790199 0.9992805 0.00138241 0.03791338 0.9992801 0.001388072 0.03797107 0.9992775 0.001641809 0.03784412 0.9992823 0.00168693 0.03771126 0.9992876 0.001508414 0.04023736 0.9991896 0.001072645 0.0351535 0.9993788 0.00251007 0.03512758 0.999382 -0.001342833 0.03793615 0.9992792 0.001424074 0.03662329 0.9993291 -5.7987e-4 0.0393691 0.9976267 0.05649012 0.02880984 0.9960759 0.08368283 0.03885078 0.9980044 0.04977661 0.03811699 0.999272 0.001593232 0.03534924 0.9993731 0.001968622 0.0353741 0.9993723 0.00195378 0.03812235 0.9992721 0.001423537 0.0348373 0.9993905 0.002281188 0.03797274 0.9992778 0.001366555 0.03541326 0.9993706 0.002086579 0.03540915 0.9993702 0.002366662 0.03528469 0.9993745 0.002411067 0.03784346 0.9992822 0.001739501 0.03399765 0.999422 2.74667e-4 0.03604269 0.9989728 0.02746695 0.03717243 0.9992925 0.005737602 0.03537482 0.9993718 0.002147078 0.03653073 0.9975003 0.0604878 0.03573775 0.9977582 0.05658221 0.03562277 0.9993627 0.002328038 0.03263419 0.9994642 0.002557873 0.03217798 0.9994775 0.003071129 0.03266787 0.9994622 0.002875447 0.03540927 0.9993708 0.002088069 0.03269171 0.9994614 0.00286585 0.03266841 0.9994622 0.002874612 0.032691 0.9994606 0.003148972 0.03256988 0.9994645 0.003193259 0.03528481 0.9993743 0.002465724 0.03118991 0.9995128 0.00125122 0.03219801 0.9994816 6.10389e-5 0.03243678 0.9994685 0.003295302 0.03267037 0.999462 0.002924382 0.03338766 0.9972963 0.065463 0.03381466 0.9993944 0.008209466 0.025209 0.9954525 0.09186351 0.03297543 0.9994515 0.003089487 0.03024399 0.9995354 0.003791689 0.02897089 0.9995722 0.004048466 0.02977675 0.9995496 0.003724932 0.02981138 0.9995488 0.003703236 0.02976745 0.9995501 0.003720164 0.02981048 0.9995477 0.003992676 0.02968901 0.9995511 0.004037499 0.03256911 0.9994643 0.003250122 0.03244388 0.9994691 0.003011882 0.02651607 0.9996356 0.00505191 0.02956074 0.9995545 0.004141569 0.02914518 0.9995738 0.001647949 0.03067183 0.9994754 0.01040703 0.02978694 0.9995492 0.003769755 0.02588033 0.9996593 0.003418147 0.0282303 0.9995989 0.002319455 0.03247261 0.9974352 0.06378555 0.02203476 0.9948613 0.0988208 0.02938997 0.9989856 0.03412044 0.03027522 0.9970695 0.07025569 0.02739739 0.9996131 0.004818201 0.03018015 0.9995369 0.003906726 0.02677476 0.999631 0.004595577 0.02685064 0.999629 0.004583895 0.02584612 0.9996526 0.005171477 0.02663987 0.9996332 0.004885315 0.02968871 0.9995509 0.004096746 0.02956759 0.9995554 0.003855943 0.02394843 0.9996964 0.005796909 0.02716147 0.9995442 0.01318401 0.02246177 0.9997331 0.00540179 0.0267806 0.9996305 0.004663765 0.02514755 0.9996777 0.00350964 0.02682644 0.9967614 0.07581001 0.01754844 0.9937913 0.1098685 0.02896249 0.9969646 0.07226902 0.02354627 0.9997049 0.005978941 0.0267682 0.9996296 0.004917323 0.02634423 0.9996416 0.004770576 0.02338385 0.9997107 0.005624294 0.02344346 0.9997096 0.005601882 0.02431488 0.9996888 0.005584895 0.02343326 0.9997079 0.005921542 0.02311277 0.9997161 0.005800962 0.02663773 0.9996326 0.005008697 0.02652275 0.999637 0.004765748 0.01993697 0.9997766 0.007036626 0.02362179 0.9995946 0.01590049 0.02191245 0.9988789 0.04196327 0.02182126 0.9997509 0.004699945 0.02325522 0.9964357 0.08108818 0.02438485 0.9961786 0.08386689 0.0243476 0.9996876 0.005657255 0.0210393 0.9997564 0.006672084 0.0201351 0.9997726 0.007038116 0.02354609 0.9997051 0.00595045 0.02290755 0.9997164 0.006519079 0.021573 0.9997473 0.00633198 0.02014625 0.9997751 0.006630718 0.02027118 0.9997729 0.006578683 0.02014583 0.9997731 0.006926596 0.02001255 0.9997754 0.006977856 0.01994335 0.9997787 0.006705224 0.02343279 0.9997076 0.005983173 0.01629865 0.9998338 0.008180081 0.02081328 0.9997767 0.003649294 0.02385777 0.9997004 0.005474627 0.01883 0.9959169 0.08829057 0.01818954 0.9998154 0.006195425 0.01883006 0.9997937 0.007629632 0.01971524 0.9996208 0.01922696 0.01266527 0.9925037 0.1215566 0.0175358 0.9998162 0.007762968 0.01651477 0.9998302 0.008179605 0.02013516 0.9997731 0.006955623 0.02012443 0.9997708 0.007310986 0.0176723 0.999804 0.008925437 0.01651537 0.9998335 0.00776261 0.01642054 0.9998348 0.0077973 0.01651448 0.9998312 0.008065462 0.01638072 0.9998329 0.008117914 0.02001219 0.9997752 0.007009446 0.01630485 0.9998363 0.007848381 0.01245045 0.9998783 0.009409487 0.01492381 0.9998376 0.01010179 0.01443547 0.9998658 0.007751822 0.01571726 0.9996214 0.02258408 0.01394724 0.9986185 0.05066186 0.02010071 0.999776 0.00663644 0.01232981 0.9950228 0.09888273 0.0200206 0.9952929 0.09482318 0.007019281 0.9907605 0.1354421 0.01381796 0.9998646 0.008938908 0.01266151 0.9998756 0.009414613 0.01651489 0.999831 0.008092761 0.01650595 0.9998256 0.00873661 0.01719921 0.9998244 0.007450997 0.01265299 0.9998795 0.008993864 0.0128833 0.9998773 0.008907318 0.01265186 0.9998768 0.009297311 0.01252001 0.999878 0.009349942 0.006256341 0.9999163 0.01132243 0.006225824 0.9999173 0.0112614 0.001922667 0.999918 0.01266527 0.0163806 0.9998326 0.008150637 0.01245629 0.9998813 0.009076952 0.008367359 0.9999074 0.01073449 0.01083415 0.9998592 0.01281791 0.01046806 0.9999002 0.009491443 0.0164752 0.9998341 0.007773339 0.01541197 0.99412 0.1071821 0.009877502 0.9998992 0.0102055 0.008301734 0.9999067 0.01085937 0.01266157 0.9998764 0.009322464 0.008614897 0.9999063 0.01064598 0.01226836 0.9998759 0.009897708 0.008576869 0.9999101 0.01031607 0.008794486 0.999909 0.01023298 0.008575916 0.999907 0.01061767 0.008437275 0.9999075 0.01067376 -0.007873892 0.9998075 0.01797574 -0.008056938 0.9996158 0.0265209 -0.002838253 0.9997417 0.0225535 0.01251941 0.9998776 0.009383678 0.00837332 0.999911 0.01040107 0.001861631 0.9999162 0.01281785 0.007294118 0.9982925 0.05795645 0.01263397 0.9998798 0.008997142 0.008541882 0.9999114 0.010221 0.003479123 0.9935355 0.1134684 -7.01941e-4 0.9878749 0.155251 0.01074254 0.9926493 0.1205486 0.005720674 0.9999172 0.01153731 0.004570364 0.9999167 0.01207888 0.006195306 0.9999164 0.01135295 0.00640887 0.9999141 0.0114445 0.002044737 0.9999158 0.01281785 0.006681084 0.9999141 0.01127958 0.006012201 0.9999199 0.01113933 0.001525938 0.9999191 0.01263475 0.002075254 0.9999192 0.0125432 0.005981683 0.9999178 0.01135295 0.006256282 0.9999157 0.01138347 -0.01458823 0.9963341 0.08429437 -0.0205698 0.998093 0.0581997 -0.02102762 0.9955017 0.09238123 0.008437037 0.9999071 0.01070815 -0.008362293 0.9989279 0.04553478 -0.01373338 0.9994277 0.03091543 -0.002807736 0.9998924 0.01440489 -0.003204464 0.9998894 0.01452696 0.001770019 0.9999095 0.01333659 -0.005981683 0.9915865 0.1293082 0.002105772 0.997942 0.06408995 0.005310237 0.9907335 0.1357173 0.003173947 0.9999182 0.01239061 -0.001342833 0.9999024 0.01391673 -2.03767e-4 0.9999065 0.01367056 2.44149e-4 0.9999111 0.01333659 0.003234982 0.9999211 0.01214647 -0.002594053 0.999893 0.01440495 -0.00439465 0.9998785 0.01495403 -0.0032655 0.9998932 0.01425236 -0.002655148 0.9998963 0.01416081 -0.02649062 0.9988009 0.04117035 -0.002899289 0.9998742 0.01559537 -0.00790441 0.999838 0.01617515 -0.007995963 0.9998382 0.01611411 -0.002929806 0.9991926 0.04007142 -0.003021299 0.9975353 0.07010149 -0.009399712 0.9841041 0.1773438 4.883e-4 0.988686 0.1499997 -0.006256341 0.9998593 0.01556462 -0.0053249 0.9998667 0.01543903 -0.008392751 0.9998365 0.0160225 -0.007721364 0.9998434 0.01593106 -0.01330637 0.9997484 0.01806735 -0.01351994 0.999746 0.01803678 -0.01989835 0.999161 0.03579872 -0.01425212 0.9985674 0.05157637 -0.008667349 0.9969912 0.0770297 -0.01159733 0.9997815 0.01739597 -0.01016628 0.9998019 0.01711356 -0.01397758 0.9997358 0.01825022 -0.01391667 0.9997422 0.01794517 -0.01330637 0.9997527 0.01782327 -0.01889127 0.9996224 0.01995944 -0.01953184 0.9996058 0.02017277 -0.01342815 0.9996964 0.02066105 -0.01388615 0.9897335 0.1422494 -0.0173043 0.9801523 0.1974893 -0.006348013 0.985346 0.1704502 -0.01739597 0.9996597 0.01944077 -0.01612275 0.9996857 0.0191974 -0.01940989 0.9996106 0.02005076 -0.01916593 0.9996195 0.01983731 -0.02597177 0.9994097 0.02249258 -0.02594125 0.9994111 0.02246206 -0.01944065 0.9995306 0.02368277 -0.02038663 0.9879604 0.1533578 -0.02566665 0.9750903 0.2203185 -0.01501512 0.9802584 0.1971503 -0.02365195 0.9994868 0.02160722 -0.02304846 0.9994982 0.02173233 -0.0260021 0.9994041 0.02270609 -0.01907444 0.9996225 0.01977634 -0.02990835 0.999275 0.02356046 -0.02566617 0.9994258 0.02212601 -0.02417123 0.9994743 0.02160757 -0.02584987 0.9994183 0.02224862 -0.03289997 0.9991461 0.02499538 -0.03305232 0.9991388 0.02508676 -0.02594077 0.9993003 0.02694785 -0.02792519 0.9944739 0.1012023 -0.03421223 0.9834873 0.1777144 -0.03466957 0.9691016 0.2442134 -0.02719223 0.9858497 0.165412 -0.03042727 0.9992491 0.02398782 -0.03262448 0.9991521 0.02511686 -0.02904683 0.9992899 0.02400577 -0.02508682 0.9994445 0.02194333 -0.03650087 0.9989833 0.02646005 -0.03292953 0.999149 0.02484214 -0.03262484 0.9991635 0.02465939 -0.04043769 0.9987961 0.0277723 -0.04034614 0.9987972 0.02786386 -0.03286939 0.9989927 0.03054994 -0.04174983 0.9806329 0.1913534 -0.03524982 0.9932225 0.1107548 -0.02527004 0.9729288 0.2297197 -0.03772091 0.9989331 0.02664268 -0.04013282 0.9988049 0.02789461 -0.03644007 0.9989895 0.02630764 -0.04275715 0.9986745 0.02865737 -0.04025512 0.9988093 0.02755904 -0.08054083 0.9958193 0.04309344 -0.06854599 0.9969078 0.03842359 -0.08050793 0.9958208 0.0431227 -0.04849511 0.9983468 0.030855 -0.04879951 0.998331 0.03088498 -0.04043781 0.9985858 0.0345171 -0.05008262 0.9771456 0.206587 -0.0422694 0.9633466 0.2649089 -0.04312348 0.9916883 0.1212219 -0.04574769 0.9985152 0.02957272 -0.05475187 0.9979559 0.03296101 -0.04852527 0.9983388 0.03106838 -0.06433498 0.997254 0.03668439 -0.05783349 0.9977273 0.03457802 -0.04843425 0.9983506 0.03082454 -0.05804669 0.9977202 0.03442513 -0.05807709 0.9977184 0.03442507 -0.06964373 0.9944838 0.07843315 -0.06051939 0.9928479 0.1029105 -0.05908459 0.9958631 0.0690338 -0.05099725 0.9944622 0.09189271 -0.05175977 0.989784 0.1328481 -0.04992955 0.9568104 0.2863931 -0.03695899 0.9628566 0.267472 -0.1458826 0.9869053 0.06882119 -0.1284222 0.9897482 0.06250202 -0.1265633 0.9900448 0.06158781 -0.06830239 0.9969162 0.03863751 -0.8990405 -0.001800596 0.4378618 -0.9020593 0.1669101 0.3980329 -0.896935 -0.1946833 0.3969965 -0.5572815 0.793409 0.2448254 -0.3160268 0.9376428 0.1447528 -0.5497131 0.7941725 0.2590476 -0.06851559 0.9969099 0.03842365 -0.05813896 0.9973353 0.04406964 -0.05923783 0.972862 0.2236755 -0.05816984 0.94906 0.3096798 -0.07419216 0.9964213 0.04049897 -0.08038622 0.9958253 0.04324495 -0.08374327 0.9805354 0.1775883 -0.06863814 0.9963975 0.04980766 -0.08169877 0.9926542 0.08923691 -0.06940114 0.9675569 0.2429345 -0.06726324 0.9395187 0.335828 -0.05084389 0.9481195 0.3138222 -0.08536088 0.9953078 0.04556447 -0.09735548 0.993972 0.0504173 -0.09396815 0.9944024 0.04831165 -0.5813662 0.7683897 0.2675645 -0.6382374 0.702998 0.3137626 -0.08017247 0.9958544 0.04297024 -0.08023369 0.9958561 0.04281771 -0.09439635 0.9943514 0.04852575 -0.09461015 0.9943221 0.04870891 -0.08066207 0.9951376 0.05652141 -0.08865863 0.9128638 0.3985215 -0.07333737 0.9171602 0.3917127 -0.07712221 0.9280914 0.3642781 -0.08081471 0.9608649 0.2649673 -0.06180197 0.9341713 0.351432 -0.09396827 0.9944038 0.04828119 -0.09460961 0.9934316 0.06436502 -0.1078867 0.9418348 0.3182889 -0.09372276 0.9523649 0.2902018 -0.09717363 0.9755817 0.1969719 -0.5308485 0.8140043 0.2357902 -0.1285776 0.9897394 0.06232029 -0.1285783 0.989745 0.06222909 -0.1101112 0.9924051 0.05484199 -0.1102644 0.9923796 0.05499482 -0.1286967 0.9897164 0.06244093 -0.1291587 0.9896579 0.0624125 -0.1105086 0.9911591 0.07342821 -0.1241537 0.927979 0.3513417 -0.1011399 0.894694 0.4350784 -0.1125246 0.9691097 0.2194642 -0.0850569 0.8973249 0.4330977 -0.1525341 0.985612 0.07281839 -0.4864742 0.8469657 0.2144576 -0.7959454 -0.4703341 0.3811259 -0.3981206 -0.8976254 0.1891263 -0.5501429 -0.7944202 0.2573702 -0.4414566 -0.8749479 0.198953 -0.1528716 0.9855933 0.07236146 -0.1529002 0.9856113 0.07205533 -0.1880877 0.9639384 0.1882709 -0.1533281 0.9642829 0.2159839 -0.1304066 0.9736093 0.1872936 -0.1300429 0.9606273 0.2455282 -0.1149358 0.8714799 0.4767732 -0.09790676 0.8724022 0.4788827 -0.1730424 0.981703 0.07947134 -0.18809 0.9782027 0.08798694 -0.4006554 0.8962253 0.190409 -0.4446722 0.8731079 0.1998736 -0.1526257 0.9856427 0.07220798 -0.5272508 -0.8169091 0.2338081 -0.4832682 -0.8491297 0.2131446 -0.1528393 0.9856119 0.07217746 -0.1527803 0.9856254 0.07211738 -0.2210524 0.895868 0.3854302 -0.1832965 0.9270421 0.3271015 -0.2313358 0.9456083 0.2287112 -0.1864124 0.9480542 0.2577667 -0.1520171 0.9482069 0.2789167 -0.1440493 0.9084264 0.3924429 -0.1313245 0.8399212 0.5265797 -0.1113668 0.8421638 0.5275961 -0.2097875 0.973159 0.09460884 -0.2944794 0.9464601 0.13227 -0.3296997 0.9316619 0.1526574 -0.2515698 0.9612936 0.1123716 -0.6879432 -0.6240656 0.3705084 -0.6352814 -0.6959835 0.3347008 -0.1882131 0.978269 0.08698028 -0.1885477 0.978202 0.08701026 -0.189186 0.9746787 0.1192064 -0.1716069 0.8760408 0.4506704 -0.152534 0.7913888 0.5919775 -0.1252838 0.8060891 0.5783808 -0.3655557 0.913584 0.1781389 -0.2334443 0.9665859 0.105903 -0.2338955 0.9664672 0.1059916 -0.3189868 0.927143 0.1966047 -0.3182888 0.9373481 0.1416719 -0.2343876 0.9611723 0.1456377 -0.2056089 0.6248839 0.7531568 -0.1592807 0.6922105 0.7038995 -0.1757302 0.7291982 0.6613538 -0.2035941 0.8316505 0.5166304 -0.1482623 0.7336816 0.6631212 -0.1375821 0.7696112 0.6235142 -0.7069145 0.6092228 0.3593322 -0.331989 -0.9285194 0.1662386 -0.3164524 -0.9375463 0.1444468 -0.3182581 0.937317 0.1419465 -0.31786 0.9374659 0.1418544 -0.2508696 0.7454673 0.6175299 -0.3360783 0.5285329 0.779554 -0.2830308 0.8280344 0.4839966 -0.8046679 0.4541249 0.382466 -0.3543608 -0.9168944 0.1836658 -0.5572573 0.7933874 0.2449502 -0.4515938 -0.6665717 0.5930813 -0.309191 -0.9012349 0.303606 -0.5489173 0.767648 0.3307664 -0.4306206 0 0.9025331 -0.251082 0.4105145 0.8766047 -0.4076746 0.6135262 0.6763041 -0.1791198 0.6017863 0.7783119 -0.1688932 0.6518899 0.7392663 -0.5772414 -0.7725037 0.2646325 -0.9162589 -1.22074e-4 0.4005867 -0.9161497 -9.1557e-5 0.4008364 -0.8737958 -3.05192e-5 0.4862932 -0.624937 -9.15569e-5 0.7806753 -0.5354035 -6.1039e-5 0.8445965 -0.2950271 0 0.9554889 -0.2145178 0.3502662 0.9117542 -0.1966334 0.5003882 0.8431768 -0.293469 -0.9468464 0.1317497 -0.2122571 -0.9725069 0.09579795 -0.2337439 -0.9663488 0.1073958 -0.25255 -0.960972 0.1129226 -0.5574669 -0.7932596 0.2448874 -0.5571631 -0.7934447 0.2449796 -0.557164 -0.7934155 0.2450716 -0.2210832 -0.8958996 0.3853391 -0.2830684 -0.8280858 0.4838867 -0.5573635 -0.7934563 0.2444854 -0.318036 -0.9373836 0.1420037 -0.3182248 -0.93737 0.1416706 -0.2313326 -0.9455951 0.228769 -0.2970434 -0.8674167 0.3991912 -0.4077108 -0.6136263 0.6761914 -0.3360461 -0.5284693 0.7796111 -0.2510815 -0.4104528 0.8766338 -0.2278241 -0.1448125 0.9628736 -0.2280985 0.1474065 0.9624149 -0.3179227 -0.93744 0.1418856 -0.3178614 -0.93747 0.1418245 -0.3189536 -0.9271353 0.1966946 -0.2508706 -0.7454397 0.6175628 -0.2056112 -0.6247994 0.7532263 -0.1964207 -0.4993835 0.8438218 -0.2142419 -0.3516376 0.9112912 -0.1880555 -0.9782122 0.08795452 -0.233714 -0.9665043 0.1060533 -0.2336243 -0.9665427 0.1059015 -0.2336851 -0.9665112 0.106054 -0.233932 -0.9664614 0.1059637 -0.2343834 -0.9611552 0.1457571 -0.2035329 -0.8317415 0.516508 -0.1757282 -0.7290675 0.6614985 -0.1694433 -0.648719 0.7419251 -0.1789956 -0.6019929 0.7781807 -0.1763699 -0.9809758 0.08111977 -0.1099923 -0.992403 0.0551182 -0.1147518 -0.9917483 0.05716222 -0.1009875 -0.9935783 0.05102783 -0.1525027 -0.9856371 0.07254332 -0.1881212 -0.9782977 0.08685803 -0.1879999 -0.9783318 0.08673626 -0.1525024 -0.791261 0.5921564 -0.1716411 -0.8760291 0.4506801 -0.1441107 -0.9083371 0.392627 -0.1833887 -0.9270451 0.3270416 -0.1597079 -0.6908063 0.705181 -0.1488397 -0.9863343 0.07065081 -0.1525323 -0.9856616 0.07214611 -0.1525638 -0.9856678 0.071994 -0.09454691 -0.9943296 0.04867726 -0.1126471 -0.9797953 0.1652626 -0.09558546 -0.9901884 0.1019334 -0.1288218 -0.9897096 0.06228983 -0.1241811 -0.9279555 0.3513938 -0.1310479 -0.8402752 0.5260838 -0.1521371 -0.9482247 0.2787908 -0.136482 -0.7733266 0.6191435 -0.1485072 -0.7328003 0.6640402 -0.1299825 -0.9894723 0.06363314 -0.1285473 -0.9897413 0.06235092 -0.1284549 -0.9897649 0.0621674 -0.1286984 -0.9897295 0.06222808 -0.1293107 -0.9880356 0.08405047 -0.1304681 -0.9736129 0.1872332 -0.1300421 -0.9606824 0.2453131 -0.1149652 -0.8715623 0.4766156 -0.1171022 -0.8280168 0.5483387 -0.1269909 -0.8013456 0.5845669 -0.0941199 -0.9943627 0.04883003 -0.1099612 -0.9924284 0.05472117 -0.0817309 -0.992643 0.08933019 -0.09704983 -0.9844763 0.1462462 -0.1125853 -0.9691374 0.219311 -0.1079782 -0.9417419 0.3185326 -0.1015068 -0.8939073 0.4366076 -0.1045902 -0.8579936 0.5028997 -0.08874946 -0.9949831 0.04617536 -0.08008092 -0.9958539 0.04315334 -0.09436351 -0.9943575 0.04846352 -0.09393805 -0.9944067 0.04828131 -0.05914521 -0.9958553 0.0690943 -0.07120126 -0.9907754 0.1153015 -0.08041721 -0.9958307 0.04306209 -0.09375596 -0.9523313 0.2903017 -0.08865791 -0.9128255 0.3986096 -0.09119153 -0.8858823 0.4548589 -0.07761085 -0.9960924 0.04214727 -0.0799303 -0.9958791 0.04284924 -0.04828071 -0.9983609 0.03073239 -0.04922688 -0.9983025 0.03112924 -0.08020335 -0.9958585 0.04281783 -0.05798625 -0.99773 0.03424239 -0.07196515 -0.9843786 0.1606855 -0.08102709 -0.9950925 0.05679523 -0.06970626 -0.9944744 0.07849586 -0.08090513 -0.9607909 0.2652078 -0.07715272 -0.927969 0.3645832 -0.07815974 -0.909351 0.408622 -0.06814837 -0.9969257 0.03866726 -0.06830155 -0.996934 0.03817927 -0.05807715 -0.9977195 0.03439462 -0.06897342 -0.9963607 0.05008202 -0.05932986 -0.9727785 0.2240131 -0.05823075 -0.9489668 0.3099539 -0.06729418 -0.9394939 0.335891 -0.06949168 -0.9674823 0.2432057 -0.06744658 -0.9261244 0.3711395 -0.0486474 -0.9983403 0.03082424 -0.05847477 -0.9973062 0.04428333 -0.05020445 -0.9770491 0.2070133 -0.06140476 -0.9873901 0.1459126 -0.05691868 -0.9405476 0.3348591 -0.04867798 -0.9983417 0.03073275 -0.04849398 -0.9983544 0.03061014 -0.0347613 -0.9966945 0.07342904 -0.03363156 -0.9983272 0.04702925 -0.02658212 -0.9987986 0.04117023 -0.04910469 -0.9980247 0.03918606 -0.04187202 -0.9805442 0.1917812 -0.04898285 -0.9574699 0.2843447 -0.0519129 -0.9897635 0.132941 -0.04724383 -0.9521404 0.3019883 -0.04095655 -0.9987664 0.02807748 -0.04275739 -0.9986805 0.02844387 -0.03622597 -0.9990069 0.02594107 -0.04007118 -0.9988193 0.02746689 -0.04016256 -0.9988148 0.02749729 -0.04257386 -0.9957097 0.08215683 -0.04327565 -0.9916782 0.1212512 -0.03854596 -0.9660302 0.2555388 -0.03473049 -0.9648548 0.2604787 -0.03021395 -0.9992585 0.02386593 -0.03259432 -0.9991638 0.02468991 -0.0325334 -0.9991665 0.02465945 -0.03222841 -0.9991733 0.0247817 -0.03289997 -0.9991461 0.02499538 -0.03317409 -0.998977 0.03073257 -0.03430366 -0.9834235 0.1780496 -0.02551358 -0.9994248 0.02233964 -0.02575838 -0.9994207 0.02224868 -0.02581924 -0.9994129 0.02252316 -0.02600228 -0.9994096 0.02246206 -0.02621591 -0.9992889 0.02710098 -0.02731424 -0.9857541 0.1659607 -0.02868771 -0.9732155 0.2280979 -0.0195319 -0.9771775 0.2115249 -0.02035599 -0.9995806 0.02060014 -0.01965445 -0.9996015 0.02026486 -0.03045487 -0.9992459 0.02408725 -0.0198071 -0.9996028 0.02005124 -0.01925736 -0.9996153 0.01995933 -0.01944035 -0.9996069 0.02020329 -0.01953184 -0.9996058 0.02017277 -0.02130222 -0.9954675 0.09268605 -0.01974564 -0.9995216 0.02380466 -0.02056998 -0.9878473 0.1540612 -0.01449668 -0.9997233 0.01852524 -0.01336735 -0.9997469 0.01809781 -0.01290935 -0.9997579 0.0178228 -0.01382511 -0.9997435 0.01794517 -0.01327592 -0.9997531 0.01782327 -0.01342839 -0.9997461 0.01809781 -0.01351994 -0.999746 0.01803678 -0.01373362 -0.9996897 0.0207836 -0.008301198 -0.9998376 0.01599198 -0.007721364 -0.9998438 0.01590055 -0.002655148 -0.9998963 0.01416081 -0.00790441 -0.9998385 0.01614463 -0.007995963 -0.9998382 0.01611411 -0.008179068 -0.9998039 0.01803672 -0.007049858 -0.9849426 0.172738 -0.004058957 -0.9998804 0.01492357 -0.004577875 -0.9998773 0.01498502 -0.009277641 -0.9998196 0.01657158 -0.003173947 -0.9998939 0.01422184 -0.003143429 -0.9998905 0.01446592 -0.002929806 -0.9997442 0.02243149 -0.003143429 -0.9998731 0.01562583 -0.003173947 -0.9922279 0.1243947 -0.003143429 -0.9991907 0.04010188 -0.003326475 -0.9975 0.07058948 4.57779e-4 -0.9999114 0.01330608 0.001556456 -0.9999191 0.01263475 0.006469964 -0.9999178 0.01107829 0.006256282 -0.9999157 0.01138347 0.001892149 -0.9999181 0.01266527 0.001678466 -0.9999105 0.01327556 0.001892149 -0.9998204 0.01886045 0.001861631 -0.999379 0.03518849 0.001770079 -0.9979131 0.06454783 0 -0.9884486 0.1515572 0.003063857 -0.9999182 0.01242786 0.004791438 -0.9999185 0.01184129 0.005493342 -0.9999167 0.01168864 0.006042718 -0.9999198 0.01113933 0.006225824 -0.9999173 0.0112614 0.006256341 -0.9999174 0.01123088 0.006408929 -0.9998579 0.01559507 0.006592154 -0.9995068 0.03070241 0.006622552 -0.9982419 0.05890136 0.005279719 -0.9907001 0.1359611 0.007236361 -0.9999128 0.0110445 0.00840044 -0.9999061 0.0108245 0.008899927 -0.9999083 0.01021152 0.01251822 -0.9998782 0.009335935 0.008431553 -0.9999076 0.01066058 0.007809162 -0.9999111 0.01081299 0.008373737 -0.9999111 0.01038336 0.008367538 -0.9999074 0.01073217 0.01043754 -0.999902 0.009338855 0.01262861 -0.9998908 0.007672429 0.008541405 -0.9999101 0.01034832 0.01074266 -0.9998629 0.01260429 0.01834207 -0.9996277 0.0202037 0.01123112 -0.9984117 0.05520957 0.01071214 -0.9926607 0.1204584 0.01121157 -0.9998895 0.009770691 0.01287555 -0.9998731 0.009382724 0.009427845 -0.9999001 0.01053214 0.01245778 -0.9998767 0.009572207 0.01021337 -0.9999004 0.009748518 0.008717298 -0.9999094 0.01025724 0.01278793 -0.9998783 0.008944034 0.01265126 -0.9998768 0.009303867 0.01251733 -0.9998776 0.009389042 0.008430778 -0.9999071 0.01071459 0.01244235 -0.9998784 0.009409248 0.0124492 -0.9998815 0.00906074 0.02099722 -0.9997505 0.007629811 0.01443552 -0.9998672 0.007568717 -0.01083439 -0.9982604 0.05795639 0.0202037 -0.9993206 0.03082436 0.01794523 -0.9986771 0.04818964 0.01544272 -0.9940732 0.1076109 0.0149793 -0.9998514 0.008541107 0.02783256 -0.999601 0.004826962 0.01639235 -0.999832 0.008215725 0.01594245 -0.9998396 0.008171677 0.01556879 -0.9998453 0.008196771 0.01703834 -0.9998267 0.007512569 0.01637262 -0.9998332 0.008105158 0.01644617 -0.9998345 0.007777869 0.01651591 -0.9998311 0.008071482 0.02042591 -0.9997676 0.006905913 0.01637214 -0.9998328 0.008158028 0.01696401 -0.9998242 0.00799936 0.0164802 -0.9998348 0.007680654 0.01691877 -0.9998279 0.007630944 0.02902311 -0.9995744 0.002960264 0.01262336 -0.9998796 0.009025335 0.01648944 -0.9998483 0.005610823 0.01853901 -0.9998003 0.00746113 0.01959425 -0.9997791 0.007615506 0.02189993 -0.9997406 0.006268441 0.02086687 -0.9997616 0.006431341 0.02032947 -0.9997718 0.006569027 0.01988452 -0.9997777 0.00701332 0.02019667 -0.9997716 0.006988704 0.02064943 -0.9997648 0.006629049 0.0278564 -0.9996041 0.003992736 0.01630467 -0.9998351 0.008009552 0.02714055 -0.9996133 0.006071507 0.02224832 -0.9997407 0.004852473 0.02621597 -0.9993507 0.02472048 0.02530032 -0.99889 0.03973585 0.02188992 -0.9997402 0.00636053 0.01872891 -0.9997989 0.00717771 0.02054816 -0.9997647 0.00695461 0.02265965 -0.999724 0.006224989 0.02004832 -0.9997746 0.006997525 0.02378231 -0.9997012 0.005668282 0.02285546 -0.999722 0.005818128 0.02303725 -0.9997161 0.006101548 0.02349579 -0.9997061 0.00597918 0.03018808 -0.9995381 0.003500163 0.02788227 -0.9996032 0.00402373 0.02435398 -0.996164 0.08404874 0.02506542 -0.9996716 0.005335867 0.02331984 -0.9997101 0.006009697 0.02655977 -0.9996347 0.005019605 0.02651572 -0.9996358 0.005028724 0.0249018 -0.9996731 0.005813539 0.02640372 -0.9996401 0.004746675 0.02724701 -0.9996186 0.004517912 0.02680099 -0.9996303 0.004586458 0.02647691 -0.9996377 0.004857301 0.0272597 -0.9996167 0.004842519 0.02635943 -0.9996398 0.005075514 0.02929431 -0.9995557 0.005515813 0.03253209 -0.9994661 0.003035724 0.03119033 -0.9989759 0.0327773 0.02819925 -0.996802 0.0747708 0.03345346 -0.9994338 0.003621339 0.02900516 -0.9995708 0.004116535 0.02978187 -0.9995495 0.003722965 0.02909654 -0.9995687 0.003996074 0.0298354 -0.9995479 0.003749251 0.02898037 -0.9995722 0.003944396 0.0292527 -0.9995632 0.004220724 0.02988308 -0.9995458 0.003936707 0.03246968 -0.9994673 0.003297984 0.02966779 -0.9995512 0.004144787 0.03500503 -0.9993842 0.002445816 0.03171253 -0.9994859 0.00474143 -0.02798557 0.999608 -8.54522e-4 0.03601187 -0.9989646 0.0278024 0.02475082 -0.9954359 0.09216713 0.03263348 -0.9994623 0.003202378 0.03270632 -0.99946 0.003172874 0.02982115 -0.9995473 0.004023909 0.03254914 -0.9994654 0.003071606 0.03266972 -0.999462 0.002917945 0.03267019 -0.9994621 0.002866387 0.03255009 -0.9994651 0.003164887 0.03329771 -0.9994418 0.002738416 0.03270822 -0.99946 0.003144383 0.03738558 -0.9992991 0.001916229 0.02937966 -0.9995595 0.004192829 0.03737622 -0.9992995 0.001906394 0.03605347 -0.9993423 0.003902554 0.03189206 -0.9973212 0.06582885 0.02746689 -0.9959189 0.08597135 0.03634804 -0.9974208 0.06189244 0.03557693 -0.9993641 0.002393126 0.03535562 -0.999372 0.002402245 0.03667694 -0.9993259 0.001598834 0.03338128 -0.9994384 0.00295943 0.03486812 -0.9993889 0.002482235 0.03214359 -0.9994788 0.003029823 0.03639221 -0.9993359 0.001889228 0.03546929 -0.9993686 0.002089321 0.03539651 -0.9993712 0.00210154 0.03796786 -0.9992778 0.001565515 0.03459388 -0.9993988 0.002310812 0.03512263 -0.9993801 0.002454996 0.03510606 -0.9993807 0.002463221 0.03972119 -0.9992098 0.00140351 0.03663575 -0.9993236 0.003210604 0.9905104 0.03036689 -0.1340416 0.0416581 -0.9988801 0.02243131 0.03915554 -0.997567 0.05768042 0.02996945 -0.9963181 0.08032554 0.03543198 -0.9977115 0.05758839 0.036035 -0.9993479 0.002307295 0.03789842 -0.9992808 0.001302659 0.03782612 -0.9992832 0.001505136 0.03490972 -0.9993872 0.002605199 0.03738671 -0.9992996 0.001600682 0.03790628 -0.9992804 0.001378357 0.03535139 -0.9993726 0.002150535 0.04011607 -0.9991948 7.72786e-4 0.04215818 -0.9991107 8.40423e-4 0.03529399 -0.9993743 0.002312183 0.04136657 -0.9991438 7.1535e-4 0.04085528 -0.9991623 0.002407014 0.9937508 0.03537118 -0.1058694 0.04187172 -0.9976897 0.0534994 0.04297095 -0.9990747 0.001831114 0.03888165 -0.9979835 0.05017381 0.03874403 -0.999248 0.001570165 0.04543983 -0.9989671 -2.39086e-4 0.0378986 -0.9992802 0.001692235 0.03879785 -0.9992462 0.001335561 0.0402956 -0.9991875 8.03072e-4 0.04061901 -0.9991745 7.32177e-4 0.04034268 -0.9991858 6.75345e-4 0.04315805 -0.9990682 4.78003e-4 0.03796803 -0.999278 0.001366317 0.04317104 -0.9990676 5.2387e-4 0.04169636 -0.9991296 0.001234412 0.03664946 -0.9993269 0.001658201 0.04005116 -0.9991972 0.001024603 0.03781741 -0.9992837 0.001382887 0.04116964 -0.9991498 -0.002197325 0.04345905 -0.9990403 -0.005462884 0.0323807 -0.9966611 0.0749548 0.04431414 -0.9977707 0.04989922 0.03469997 -0.9969618 0.0697357 0.04240119 -0.9991006 4.5026e-4 0.04243451 -0.9990992 4.3917e-4 0.03875869 -0.9992478 0.001351177 0.04216969 -0.9991105 3.74363e-4 0.04316264 -0.9990681 6.37387e-5 0.04287838 -0.9990803 -2.24023e-5 0.04371535 -0.999044 3.25945e-4 0.0417512 -0.9991279 6.50224e-4 0.04286462 -0.9990808 4.97287e-4 0.03991127 -0.9992028 9.65508e-4 0.04290008 -0.9990795 1.40855e-4 0.04684734 -0.9989021 -3.66234e-4 0.04345953 -0.999051 -0.002899289 0.04678499 -0.9978358 0.0462051 0.03683596 -0.997197 0.06512677 0.04220747 -0.9981778 0.043123 0.04848122 -0.9988235 -0.001164376 0.04455983 -0.9990068 -1.2468e-4 0.04473441 -0.9989989 -1.85996e-4 0.04509991 -0.9989825 -3.99126e-4 0.04447585 -0.9990105 -1.76582e-4 0.04445582 -0.9990113 -2.99029e-4 0.04438692 -0.9990145 -2.92084e-4 0.03375184 -0.99943 -9.18989e-4 0.04012101 -0.9991946 7.43842e-4 0.0428189 -0.9990829 2.84339e-6 0.04910492 -0.9987928 -0.001281738 0.04449099 -0.9990098 -7.84963e-5 0.04237401 -0.9991018 2.35647e-4 0.04446071 -0.9990112 -7.26148e-5 0.04449617 -0.9990096 -3.3089e-4 0.04907459 -0.9978808 0.04272663 0.0456261 -0.9989526 -0.003479182 0.04532074 -0.9982784 0.03723323 0.04685801 -0.9989014 -7.28906e-4 0.04714632 -0.9988876 -9.01041e-4 0.03921717 -0.9992306 5.18827e-4 0.01452684 -0.9998825 0.004913449 0.04129159 -0.9991472 1.52593e-4 0.0469827 -0.9988954 -8.30171e-4 -0.9838368 -0.06415063 0.1671823 0.01022374 -0.9999445 -0.002563536 -0.02175807 -0.9996982 0.01140713 0.02840805 -0.9995889 0.00388211 0.04669767 -0.9989089 -6.43369e-4 0.04454147 -0.9990075 -3.38947e-4 0.04677003 -0.9989055 -6.72018e-4 0.04614824 -0.9989345 -5.72578e-4 0.04663157 -0.9989118 -9.37913e-4 0.05267542 -0.9985756 -0.008484184 0.04809832 -0.9988338 -0.004211604 0.03885066 -0.9973922 0.06082439 0.05121046 -0.997902 0.0396133 0.04086452 -0.9975649 0.05652064 0.04641449 -0.9989221 -6.41418e-4 0.0439471 -0.9990338 -5.1882e-4 -0.971284 -0.1617535 0.1744801 0.04318422 -0.9990671 -3.66227e-4 -0.9832968 -0.05816948 0.1724637 0.007294058 -0.9999638 -0.004394769 0.03141558 -0.9995049 0.001732349 0.02282786 -0.9997263 0.005127072 -0.3158736 0.9462171 0.0699805 -0.3158591 0.9462072 0.07017809 0.0374751 -0.9992972 9.65189e-4 0.02816575 -0.9995952 0.004015624 0.04905939 -0.998795 -0.001332104 0.04886704 -0.9988043 -0.001484096 0.0506739 -0.9987137 -0.001742005 0.04896634 -0.9987996 -0.001331925 0.04876112 -0.9988098 -0.001176238 0.04867064 -0.9988142 -0.001220703 0.04696577 -0.9988961 -9.74602e-4 0.04840469 -0.9988272 -0.001133084 0.0493955 -0.9987781 -0.001597881 0.05032521 -0.9987224 -0.004577755 0.05337774 -0.9979116 0.03637868 0.04294067 -0.9977073 0.0523101 0.04767131 -0.9983212 0.03289991 0.04843103 -0.9988259 -0.001153826 0.04544222 -0.998967 -3.35705e-4 0.01559501 -0.9998545 0.006927728 -0.270067 0.961975 0.04084271 -0.08489185 0.9963369 0.01030576 -0.08487212 0.99634 0.01016265 0.03922557 -0.9992304 2.76249e-4 0.03671497 -0.9993242 0.001818656 0.05061286 -0.9987165 -0.001968383 0.05079984 -0.9987074 -0.001763164 0.05080121 -0.9987069 -0.001996695 0.05067193 -0.9987139 -0.001701176 0.05106365 -0.9986938 -0.001779556 0.04835569 -0.9988291 -0.001435816 0.05015778 -0.9987396 -0.001831412 0.04998958 -0.9983271 0.02905374 0.05283445 -0.9986008 -0.002237081 0.05249381 -0.9986185 -0.002382338 0.05263811 -0.9986108 -0.002406358 0.05263817 -0.9986107 -0.002445399 0.05268174 -0.9986089 -0.002228558 0.05268186 -0.9986084 -0.002451956 0.05257517 -0.9986146 -0.00221163 0.05257517 -0.9986147 -0.002148747 0.05247128 -0.9986198 -0.002290844 0.05203229 -0.9986433 -0.002048075 0.05298095 -0.9985812 -0.005340814 0.05771207 -0.9983186 -0.005432426 0.0466634 -0.9979083 0.04474073 0.05446594 -0.9985124 -0.002588152 0.05384469 -0.998546 -0.002605736 0.05438441 -0.9985164 -0.002696216 0.05438464 -0.9985161 -0.002825617 0.05445122 -0.9985125 -0.002836406 0.05445194 -0.9985123 -0.00287491 0.05449485 -0.9985105 -0.002666592 0.05449491 -0.99851 -0.00288105 0.05439418 -0.9985161 -0.002650976 0.05426096 -0.9985235 -0.002589285 0.05439329 -0.9985162 -0.002614557 0.05135047 -0.9986783 -0.002238869 0.05426496 -0.9985227 -0.002796888 0.05633777 -0.998394 -0.005981683 0.05454188 -0.9985076 -0.002813816 0.05234032 -0.9983126 0.02514779 0.04846417 -0.9979723 0.04126173 0.05917662 -0.9978544 0.02801656 0.05619043 -0.9984155 -0.003057837 0.05597543 -0.9984275 -0.003070175 0.05610555 -0.9984201 -0.003093004 0.05615729 -0.9984168 -0.003236711 0.05607473 -0.9984214 -0.003224134 0.05616426 -0.9984162 -0.003271102 0.05594503 -0.9984294 -0.003010332 0.05674731 -0.9983831 -0.003322124 0.05620205 -0.9984148 -0.003029584 0.05654555 -0.9983952 -0.003125667 0.05624985 -0.9984111 -0.003349483 0.08252418 -0.9965435 -0.009532094 0.05490332 -0.9982703 0.02102744 0.05591672 -0.9984309 -0.003005206 0.06103926 -0.9981266 -0.004182219 0.05785113 -0.9983193 -0.003462493 0.05783736 -0.9983201 -0.003463566 0.05812847 -0.9983029 -0.00355792 0.05769872 -0.9983279 -0.003515839 0.05792641 -0.9983142 -0.003667652 0.05812442 -0.9983026 -0.003694176 0.05796301 -0.9983122 -0.003632962 0.05762642 -0.998332 -0.003522038 0.0595259 -0.998221 -0.003420412 0.05963492 -0.9981989 -0.006531119 0.0579918 -0.9983102 -0.003688275 0.06202822 -0.9980145 -0.01094686 0.05737638 -0.9981973 0.01760965 0.05748742 -0.9983406 -0.003399491 0.05958539 -0.9982158 -0.003859996 0.05956739 -0.9982169 -0.003852248 0.05978858 -0.9982036 -0.003876388 0.05958974 -0.9982151 -0.003952264 0.05967408 -0.9982101 -0.003959119 0.06025773 -0.9981741 -0.00418967 0.06360685 -0.9979645 -0.004592955 0.06033837 -0.9981693 -0.004161417 0.05980765 -0.9982025 -0.00384885 0.05799901 -0.9983098 -0.003688395 0.06431865 -0.9978696 -0.01092582 0.06277793 -0.9979774 -0.01001024 0.06125664 -0.9980667 -0.01051521 0.05368268 -0.9980584 0.031587 0.05903738 -0.9982486 -0.003780007 0.06074517 -0.9981442 -0.004250526 0.06283843 -0.9979994 -0.006988823 0.06119358 -0.9981165 -0.004346966 0.05984842 -0.9981053 0.01428306 0.05536097 -0.9980542 0.02868759 0.06592023 -0.9976541 0.01846373 0.06056469 -0.998156 -0.004101097 0.06214779 -0.99805 -0.005831599 0.06068325 -0.9981482 -0.004216849 0.060615 -0.9981519 -0.004310846 0.06687575 -0.9977015 -0.01092922 0.06588959 -0.9977749 -0.01019316 0.06747841 -0.9975882 0.01626682 0.05697923 -0.9980376 0.02597177 0.06781315 -0.9976653 -0.008087515 0.0610677 -0.9980502 0.01290935 0.0622918 -0.9980471 -0.004665136 0.06570696 -0.9978121 -0.007324457 0.06433564 -0.9979158 -0.004994988 0.06885343 -0.9975605 -0.0115053 0.06219726 -0.9979947 0.01174968 0.06424981 -0.9979214 -0.004999637 0.06726098 -0.9976792 -0.01059544 0.06384557 -0.9979078 0.01019328 0.06695407 -0.9977414 -0.005411863 0.07129311 -0.9973928 -0.01117944 0.07239168 -0.9973389 -0.008636951 0.07391655 -0.997263 -0.001709043 0.06679207 -0.9977523 -0.005407154 0.07004189 -0.9974888 -0.01050341 0.06555438 -0.9978125 0.008545219 0.06856864 -0.9976294 -0.005836129 0.06971269 -0.9975498 -0.005875885 0.07371211 -0.9972199 -0.010917 0.06711083 -0.9977204 0.007080316 0.07452762 -0.9971811 -0.008697926 0.07638806 -0.9970738 -0.002990782 0.0756148 -0.9970822 -0.01045966 0.07269787 -0.9972988 -0.01049411 0.06894242 -0.9976056 0.005493402 0.07106983 -0.9974519 -0.006244778 0.07400757 -0.9972255 -0.008026361 0.07250922 -0.9973466 -0.006507456 0.0765419 -0.9970285 -0.008697926 0.07016396 -0.9975249 0.004608392 0.07284426 -0.9973223 -0.006473422 0.07777667 -0.99692 -0.01007539 0.07544749 -0.9970955 -0.01041221 0.07086467 -0.9974769 0.00427258 0.06967437 -0.9975368 0.008117973 0.07538914 -0.9971103 -0.009359896 0.07538449 -0.9971308 -0.006896317 0.07889181 -0.9968451 -0.008728444 0.08022731 -0.9967468 -0.007720232 0.07184082 -0.9974095 0.003631711 0.07527685 -0.9971389 -0.006899595 0.08026635 -0.9967253 -0.009802937 0.0781725 -0.9968879 -0.01017552 0.07300126 -0.9973281 0.002746701 0.07404011 -0.9972532 0.002075314 0.07820695 -0.9968938 -0.009300649 0.07820475 -0.99691 -0.007386207 0.08026438 -0.9967436 -0.007738113 0.08254081 -0.9965562 -0.007926583 0.07522839 -0.9971655 0.001342773 0.07772445 -0.9969475 -0.007398128 0.08949112 -0.9959517 -0.008476316 0.07742691 -0.9969978 8.24016e-4 0.08073484 -0.9966864 -0.009907007 0.07620632 -0.9970918 6.71422e-4 0.07580959 -0.997122 8.85056e-4 0.08157265 -0.9966343 -0.00813049 0.0795989 -0.9967973 -0.007700026 0.08091944 -0.9966778 -0.009254574 0.0809161 -0.9966902 -0.007828712 0.08252334 -0.9965577 -0.007917106 0.07670462 -0.9970538 4.52425e-4 0.0840705 -0.9964211 -0.008781731 0.08094018 -0.9966883 -0.007827758 0.08296281 -0.996517 -0.008443892 0.08482831 -0.9963519 -0.009340524 0.08536082 -0.9963442 -0.003448605 0.08335548 -0.9964728 -0.009692966 0.0855323 -0.9963033 -0.008006215 0.0786888 -0.996899 -8.59435e-4 0.07799339 -0.9969539 -3.81886e-4 0.08264052 -0.9965406 -0.008811414 0.08498269 -0.9963439 -0.008769571 0.08254134 -0.9965541 -0.008181929 0.08402585 -0.9964199 -0.009342849 0.0840258 -0.9964311 -0.008047699 0.08847302 -0.9960329 -0.009539544 0.08482533 -0.9963622 -0.008204877 0.08180785 -0.9966449 -0.002548635 0.08199113 -0.9966295 -0.00266838 0.08046442 -0.9967559 -0.001812875 0.08578336 -0.9962728 -0.009055018 0.08713573 -0.9961605 -0.008472025 0.08596247 -0.9962561 -0.009183704 0.0871368 -0.9961526 -0.009342432 0.08190715 -0.9966368 -0.002542734 0.08258903 -0.99658 -0.002769291 0.08722895 -0.9961513 -0.008597373 0.08551228 -0.9963002 -0.008580982 0.09019774 -0.9958825 -0.009077787 0.08714383 -0.9961578 -0.008694946 0.08962535 -0.9959399 -0.008432447 0.08949273 -0.9959675 -0.006318867 0.0896272 -0.9959306 -0.009447932 0.08981877 -0.9959415 -0.00576812 0.08713287 -0.996184 -0.005035698 0.08289211 -0.9965543 -0.002932548 0.0890432 -0.9960176 -0.004501938 0.08335351 -0.9965151 -0.003155946 0.08731049 -0.9961444 -0.008566558 0.08725798 -0.9961479 -0.008686125 0.09082263 -0.995844 -0.006801664 0.08629757 -0.9962583 -0.004727184 0.08450806 -0.9964129 -0.004450023 0.0890423 -0.9960075 -0.006372749 0.0854119 -0.9963354 -0.00454694 0.08876729 -0.996012 -0.008969604 0.09019762 -0.9958785 -0.009519994 0.09083819 -0.9958207 -0.009459018 0.09083771 -0.9958279 -0.008680939 0.0911675 -0.9957982 -0.008628726 0.09116739 -0.9958127 -0.006768524 0.09082001 -0.9958515 -0.005628824 0.08770406 -0.996133 -0.005201339 0.08789509 -0.9961158 -0.005285561 0.09041416 -0.9958653 -0.008818984 0.09149789 -0.9957636 -0.009114265 0.08768302 -0.9961093 -0.008830368 0.09033989 -0.9958697 -0.009070336 0.08847898 -0.9960408 -0.008622705 0.09098118 -0.9958075 -0.009474992 0.09436851 -0.9955004 -0.008578538 0.0953952 -0.9953975 -0.009145438 0.09819996 -0.9951309 -0.008445084 0.09639054 -0.9953149 -0.007563233 0.09574663 -0.995376 -0.007694125 0.08954524 -0.9959662 -0.005759 0.0892803 -0.99599 -0.0057258 -0.1081766 7.75915e-6 0.9941317 -0.1081865 0 0.9941307 -0.1081462 -2.68104e-5 0.9941351 -0.108155 -3.32983e-5 0.9941341 -0.108203 0 0.9941288 -0.1082143 0 0.9941276 -0.1081739 -3.45896e-5 0.994132 -0.108187 4.48807e-6 0.9941306 -0.1081823 0 0.9941312 -0.1081507 0 0.9941346 -0.1081516 4.27806e-6 0.9941344 -0.1081654 0 0.994133 -0.1081658 0 0.9941329 -0.1082248 0 0.9941264 -0.108226 0 0.9941264 -0.1081345 -1.56227e-4 0.9941363 -0.1081933 0 0.99413 -0.1082029 0 0.9941289 -0.1081739 -1.55563e-4 0.9941321 -0.1081793 -2.73442e-5 0.9941315 -0.1082027 2.23566e-4 0.9941288 -0.1080921 8.67915e-4 0.9941405 -0.1081596 -1.50363e-4 0.9941337 -0.1081519 2.32252e-4 0.9941344 -0.1081957 1.82139e-4 0.9941297 -0.1081576 6.61785e-5 0.9941338 -0.1081943 1.8151e-4 0.9941298 -0.1081817 -1.39154e-5 0.9941312 -0.1082455 6.26673e-4 0.9941241 -0.1081708 1.04535e-5 0.9941324 -0.1080855 -8.67764e-4 0.9941413 -0.1081615 2.08095e-5 0.9941334 -0.1081585 -1.29443e-4 0.9941337 -0.1081641 -4.69801e-5 0.9941331 -0.1082583 6.30667e-4 0.9941226 -0.1078465 -4.36044e-4 0.9941675 -0.1081475 -2.32235e-4 0.9941349 -0.1081873 0 0.9941306 -0.108129 -6.10181e-5 0.9941369 -0.1081469 -1.21065e-4 0.9941349 -0.1081463 4.11162e-5 0.994135 -0.1081821 -2.61038e-6 0.9941312 -0.1081884 7.4393e-5 0.9941304 -0.1081236 -3.48301e-4 0.9941375 -0.1081705 -7.08084e-5 0.9941324 -0.1082525 2.71695e-4 0.9941235 -0.1081922 6.61785e-5 0.9941301 -0.1082148 4.6013e-5 0.9941275 -0.108235 -6.23637e-6 0.9941254 -0.1081576 -2.21872e-5 0.9941338 -0.1082246 -3.99304e-5 0.9941265 -0.1081628 4.69805e-5 0.9941332 -0.1084697 -3.98786e-4 0.9940997 -0.1081116 1.31932e-4 0.9941388 -0.1081153 1.16477e-4 0.9941384 -0.1078477 4.32325e-4 0.9941674 -0.1085151 -3.47792e-4 0.9940948 -0.1086551 -4.28955e-4 0.9940794 -0.1078357 3.4953e-4 0.9941688 -0.108117 3.21692e-4 0.9941382 -0.1086513 4.25881e-4 0.9940799 -0.1081565 -4.11162e-5 0.994134 -0.1078359 -3.49531e-4 0.9941687 -0.1081147 -1.16477e-4 0.9941385 -0.1085014 3.45326e-4 0.9940963 -0.1081074 -1.27233e-4 0.9941393 -0.1084749 3.98786e-4 0.9940992 -0.108218 3.99304e-5 0.9941272 -0.1082347 6.23635e-6 0.9941254 -0.1081386 5.97726e-5 0.9941359 -0.1082483 -2.61698e-4 0.9941239 -0.1081809 1.43574e-5 0.9941312 -0.108202 -1.57851e-4 0.994129 -0.1082584 -6.27166e-4 0.9941226 -0.108189 -7.43982e-5 0.9941304 -0.1082535 -6.33341e-4 0.9941232 -0.1081866 -8.15029e-5 0.9941306 -0.1081956 -1.82139e-4 0.9941297 -0.1081675 1.03694e-4 0.9941327 -0.108161 1.50363e-4 0.9941335 0.1698113 8.12565e-5 0.9854766 0.1701443 3.4145e-5 0.9854192 0.1687727 0.002117812 0.9856528 0.1702045 -2.11566e-4 0.9854088 0.1694414 9.994e-4 0.9855399 0.1705521 -0.001019656 0.9853482 0.1692041 0.001090288 0.9855805 0.169798 -1.02551e-4 0.9854789 0.1695904 2.49626e-4 0.9855147 0.1694976 5.30168e-4 0.9855304 0.1702935 -7.09118e-4 0.9853931 0.1699832 -3.11404e-4 0.985447 0.1699276 -1.36818e-4 0.9854566 0.169811 -4.42e-5 0.9854767 0.169418 5.91719e-4 0.9855442 0.1700835 -2.7674e-4 0.9854297 0.1692441 7.58635e-4 0.9855739 0.1694809 6.14574e-4 0.9855333 0.1718498 -0.003487229 0.9851171 0.169858 0 0.9854686 0.1696923 1.26487e-4 0.9854971 0.1687587 0.001353025 0.9856564 0.1692502 7.74732e-4 0.9855729 0.17 -7.94578e-5 0.9854441 0.1706137 -0.001004099 0.9853376 0.1697768 0 0.9854826 0.1702997 -6.39698e-4 0.9853921 0.1698511 3.89364e-5 0.9854698 0.1699092 -6.84029e-5 0.9854598 0.1693487 6.81619e-4 0.985556 0.170107 -3.23014e-4 0.9854256 0.1699443 -2.57852e-4 0.9854536 0.1697704 2.07211e-5 0.9854837 0.1697905 6.20454e-5 0.9854802 0.1694635 5.0349e-4 0.9855364 0.1701667 -4.34491e-4 0.9854152 0.9716736 -0.1668185 -0.1673983 0.9854828 0 -0.1697761 0.9854828 -6.10376e-5 -0.1697761 0.7780265 -0.6137721 -0.1340098 0.772264 -0.6212233 -0.1330037 0.86596 -0.4773553 -0.1491487 0.8634351 -0.4820294 -0.1487534 0.9301036 -0.3304926 -0.1602564 0.9315143 -0.3263748 -0.1605017 0.5397988 -0.8366317 -0.09308451 0.3959825 -0.915719 -0.06824022 0.3844758 -0.9207521 -0.0662868 0.6588199 -0.743694 -0.1134707 0.6683608 -0.7348611 -0.1152083 0.5288671 -0.8437947 -0.09116083 -0.09598135 -0.9952458 0.01654112 0.08115047 -0.9966039 -0.01397776 -0.08163791 -0.9965628 0.01406913 0.06680625 -0.9976996 -0.01150566 0.2284348 -0.9727629 -0.03936952 0.2416503 -0.9694702 -0.04162806 -0.5382987 -0.8376316 0.0927785 -0.5490725 -0.8303992 0.09464031 -0.3959559 -0.9157282 0.06827139 -0.242109 -0.9693518 0.04171973 -0.4080469 -0.9102467 0.0703476 -0.2552339 -0.9658787 0.04397845 -0.8702975 -0.4691476 0.1499429 -0.8672345 -0.4749403 0.1494526 -0.9340872 -0.3187072 0.1609559 -0.783057 -0.6071454 0.134894 -0.6670894 -0.7360629 0.1149049 -0.7779967 -0.6138032 0.1340405 -0.9724634 0.1620569 0.1674892 -0.9854878 -6.10379e-5 0.1697464 -0.9854878 0 0.1697464 -0.9717726 -0.1662704 0.1673691 -0.9724583 -0.1620255 0.1675494 -0.9324029 -0.3237515 0.1606549 -0.8672299 0.4749683 0.1493908 -0.7830978 0.6070923 0.1348958 -0.8703134 0.4691092 0.1499708 -0.9717528 0.1663281 0.1674267 -0.9323983 0.3237498 0.1606847 -0.9340964 0.3186798 0.1609574 -0.5490601 0.8304111 0.09460765 -0.5382077 0.8376935 0.0927481 -0.4080364 0.9102538 0.0703153 -0.676331 0.7273282 0.1164909 -0.7780677 0.6137195 0.1340117 -0.6670552 0.7360893 0.1149348 -0.09598135 0.9952462 0.0165106 -0.2413777 0.9695394 0.0415979 -0.08081454 0.9966316 0.01394718 -0.2552339 0.9658787 0.04397845 -0.3957957 0.9158021 0.06820905 0.06680625 0.9976996 -0.01150566 0.08145612 0.9965785 -0.01400834 0.228464 0.9727573 -0.03933876 0.2419588 0.9693919 -0.04165911 0.3844774 0.9207558 -0.06622606 0.5288096 0.8438307 -0.09116142 0.396206 0.9156199 -0.06827241 0.5399513 0.8365401 -0.09302347 0.6587831 0.7437176 -0.1135306 0.6668979 0.7362368 -0.1149035 0.7722578 0.6212183 -0.1330637 0.8634194 0.4820207 -0.1488727 0.7767003 0.6154701 -0.1339159 0.8671324 0.4751176 -0.1494814 0.9300993 0.3304605 -0.1603472 0.9323304 0.3239611 -0.1606529 0.971652 0.1669116 -0.1674304 0.9722182 0.1635216 -0.1674891 -0.6763578 -0.7272937 0.1165513 0.9722229 -0.1634613 -0.1675204 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + -0.9993399 -0.0256862 -0.02568598 -0.237433 1.50896e-7 -0.7071066 0.7071069 0.0199763 -0.03632561 0.7066402 0.70664 -0.0060656 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_tail_collision.stl b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_tail_collision.stl new file mode 100644 index 0000000000000000000000000000000000000000..8da95664e703c602c1dcc6f7f665ff4a87a14294 GIT binary patch literal 18984 zcmbW8d0b83_y0GV$kaeW3P~k2+*_%$_cjk1GiM$%6A==bm7z$4%q1da$WZs5eKLiJ z%u{AEdmAH>-?~1Z_xHDs-}kSdzk1l~xn66nz0cm~taEO=Ss_!VO&>kVA$Z!9Ne-1h#{J1c?=_UO# zs;IwglrG}o|9>XM>Ir!;=K4_sF(JwPD7IQU^tiACVvu{xU&Q5^F+RV4M=IAh#$z%(HdqU0|X z-$3tNYd4i1A<7W9KT&O;aP2Uz6((+eUMju=eZ#hq4v6cKN{tseM`z?&%ebNjdibs+ zsSM`B@c+Z$??9+DAvr+YE6VX64#eM9|IP>2hUy*+lMTzoEIN|o5kn*c!0%m%1bZT6 zI1tAiV>JfiZ>xV-$^VlFPcNzHefhjK{X5%#HPi&;!3|M`|3w(+Ac)Gkjhh~86SAjV zb2{|#XFv1Pk;?o0B;i!uj6N6{t8Z+yS=8@rPFGi6u5bQ!vls+){U^(zR@2%vq;ZXx zXFt9WsdW9i^Up{ReT*K{YNA)OVCs6{h!hYNsoV|QBEA(;=~k~5`a_+z3kz6%b4yq0 z+kvOSpz%;K%m+{CPZRt0qD5WQL~O$Z@$90Pl zwtcopO572tU@II6t|1{oAswX0`|SMcmqseMqJ!!siR<VA9Ou`MJjj%&l=VyWO6}6TDI(% z-+WjlI9^N`R>?r9)rddq%KLsH%X{F#j|5sNqdF#wvE|xGnjbNGZ~bv`_hlW{??(yE zOHUH_8hJ~fmK%1_j7H>4$xdRP>d0i63xv&bC;s@{9Edd0PLh&g{u@X~1QR`Cx9@FbOI~)$E#FUm?q=|oF9gL*W;|UY~DZ?BY+*WV+yY0s3fBtT7 zEemIt_fk!LN6;{wI0nKTi0`1GT~Z=-c8U3;VK}2sH;d7$2?2y@)=lq+=dEQtVujio41XK1S)o65Xtfx#w;G)_ zIs|6W*zXE;3aF`jzh|Bjl9MQ0CYaOF{g$h&Fips>^Bvf)wL7F}(>V(EHDYkIxb)qE z?pWMPkF^PDVYQIO=zr_75@ss1J}wmfAd;m|OjTANt1K3AmR9s`Z!3suRhOeov%A>e z&1Z^=z*Ze|=L^eHOKOpE6IT1!iEa59H)DOai=#5^!z@u`UyT-QT%P?XJxmOJT8U2F zT;S)s`@gG4wDyN}6*7+x4XP@Y|M5sR%z4dixsnFv{837%7y=P)x3iRzl~7UD>84a@ zTUjEcU&A@PbDvTEz6tFG9>GNDr%=(w7Xj5LnBe+)B6Cs;_O5CrZ(AQn(rd-j_5j~(jJNJ&!;YwpqaMD=X^P=p< zl5KQH<@Kisap|)KwfeqHMPN^a6o-Cf(~mCkD-^?38hD)j{J1XheWU z)dPuQNW?%|y(C}4guX0M#98;C_r4tkVjd8$fd~cyTVYzQv8(A-y=QqX_jsk@?YifQ z%)@Rh^@%yl>X9dw_jF_D+f-(kYUYXRi`-a{z@(V_tAAWyAA_)a+bmzBT-^sCL?g9q_Ek zp2y^ilUJIs@8``~%_Wz_)(uTq{P0RZbe+&!y!>8+cZ%)E$5*&0f||Ioagd=C{Jp}o zDSLj{TtyR7?o66kux12r_r~Wr+Cj32ns5#?nZ_p9Nmqn+#PV7>Efgo+0$zp>> zX=tZa!rq+_Vd>_~vB_0>{lRJBKCdD>MsLyhsC?02A<*4!z%>{a)>Jm@rcnaMY87mi z3mOt=yZ{X~(RNTXc^PQ51C0VZy=b_@ob7v9K)W~Bi^KO#S*y{vDb|L&rC!bCTL~KF zClFWzTVa}z3Py94hYn@*YHB9MS5Dlz4I+(=p|vZfNzQ{3h5uSYZSKawsb&F0M%^;{ zY;PvTBd*Xj7+p-Iehw@2*b^bPK zGR>A9*Lw2fSza9P$m_}_h=LDG>G9#eqz$GU#SP;q+OHgeRbsl|mVE?bJ`i|s$F!O# ztuU9%waaA7Bbl;c9~=O?s0r+%c<0P|mneLX4WSEI)7Z4qRm<0qLvD=m?Osb8i z8*U$vuqQ%J?zUw=Au2sYh4Hijh!jB>J*F#E*esr|GN+G!M#H+Q2}DaEOb%ws#SnY>#)Ig%4(n7W4%Q>&C)8?v z%`$mycBYI+um;v9q_V|)Ie*9uo*Ej%=A4Jq>y0UGKGj{{U{^An&LxsnpFO%%$Z2dm zq1H{~;fji;qvR@IBY04zC2MjyN%*ufqeD-|=rO&*c(ce2Gp8Y|4PDNQ`V9F=o!R`U z@j#UZrm-F&3-iMjeORe{sY3&?XM3{n-~UYt^4zOSi`gk^Pah@)4vo<_H901ZXVhcb ze#Nj7rvmYMW~p4gQv<rgSNZ%A9Oz3DvU!IQ9V;Y_ZfoQ$5R5tQyAn?dS z^JC&fv>mfb`cBmv5kRbjsHSyPM}_sUC+JATb!OAys@=5FUGX;05<;oVw!HmDTbX5v z{dMcH{N`V28_1*0zItrYFhd?&BfBuO2hEgEx4e`tV~z{o{5tGK^bcB8cwE@H*JW?o zlu*C6$Anm4mz8$;0Yv1^j_h@3PbK}hyW(5@n7GI6*b$A|O06+0KakludMW|l?h5v0 zERKnWC3V=YA3rG8hUZL^E^J&kPo-q0n!r)1HEh>*X44?^XviE};VP(!x%uJTWlAaS z+_?d3IUz+X8CZ^P397Hp&PWlxn|+m}kLkJ^uqxX|4wq(BH}uFh0}(i@lpbo^fcZV% zC1wsVrAb|4^_W%@1AyRTO6lD|(5R9n-a%(`Ro`zETVXwzkBi~_j`D+UN>&rt$_Zw3 zCCuhom`%9%*%>7dd=0p>-hRYLw&f{M#V=1=6e$@o&yhP^R=kU`bd{lW1Dwr>dzFX33 z4{zxf*e(`rD_hZ`ONM98k$aZO#f7uDb+2F*5m05W*j!>kJ=!nVVH%$9`fQNhN<#Sk zb$e7q*}z26aV4P#{)y9B*NzjfGK^@^qJFUZIOr1OL z_oapl-O^uDy$pZA|G;;NNO&ugAHJf-GblwY54;H%=>aXf;F zD95=Xx8#HLBJ>Opl^)iTKCMfT-hGVZTNf@A(_cT58kZ|j`JGpPz8J9Zl{Dj1J`gSa zv*bhjb6Cg96IF!gz@?(9|1GIx-&y~o@Dy&h{)!}yR+Hd>SYso@bAZnql>e|x zHclVHS2QkRL-x)WPtKZ9$2Pb9@Z4ZegbX}!Pzj@AivbQr|awJ@Ad`M`G*K1Vs zfoXV-vfn44dfbXD7aDOqf}_Ho2+140SN?vS@*1mLRjUMB;q^wyqVEUgRK=8^DC)=Y zYQSquy{;PBY?a>~dBM6*8mU?(cx7Okkb~2OJna2`7Q0~z$7`u;(Q?tx{jxM?`q97E z)!XMnwvA6^%Z7w->=zS8XV(bZ)U#5B;p<>N>YFL@S^Ff`d(KpD9hxhA*C$CG{Fdo3 zttReV%8}z+UuCnKjODHqH;JQbPD$%C+xuf$O$>I_%jLc;VY;s~_=HUH>7+cYIt{EE+(s&+}%VNZk<1|OD}?r6%D zTtDvZbxJJFyddqaeL+QFPlULBFcIs=wdOk8hALtfbpH9VLaFe113lIwB)xgG+-Acx zZu)Q=TLbSrvKJLeu?uSHH3w2el*dF5%YNlx8Qy>i58#pA^>;>7+JB zudZ(5{TSK%)eK(ebTq?OxIStkCvmAfGB$$SH?dWnYWTFocLVUXNS{M;uHKaX^JE^U z2Sdf69Z8bg8A}OYA2=sCqw?k|wgEA6x9v~mLr}#kP{qwq#R6EB!S)xWQ*n7Z-|SN& zeC!X&%(@2b)R(TzRn~rsmpin&FXNFJS*OHzrBre#+Mbu zp~gFCmW`G^J+ncavRgpIr?}GM(+R?+c|5I?(+%!@3{S%MY|7~4zlhblHi)Ihv2=Gb z^!*S`$l3k20-n5-#qg9`2qOa>7SI~wU1>ZJH_FG-yQx)ah_YU+_MK0gD$bzMHN#fC z17ai)Y1`Hd_b039@{lSjD@+qo7ov)UC;ILCGF5%UFGcHx)4FhK+_<5NCd3MePBqGC zN@k|2H;H?e`#}2*Xj@LH0#OYD!pyvkj)Tqwju%^D`ac@M5Y>frwFV~elQ&cso@;Hq zJ$WiTrS^HZK?F>Wpg!juDb7Q!(GH$#M*=Yp2t0y2sn`=C^&pQu)@5|t!A#m0`V299 z$I`*$)1^phlW5qXGp*V9m4u)4;VoH(xk^;MGTQP`CY=CLT^|xb@7;8ySVK)1dNNg@ zU*ZND*e|Bl#8=QLvM-~iu&!`a*lH7WCgwtC!mPZZGcjzZEvpQfe}>F)#{+i?k|C$# zzMZLc+gEV6w0Dm!8w^AbAn*t#j@{oSV)pc>^G6l~(Js}NU4*W|Z6NRnCQd55M6C_e zXz{9(K)eNw4M0@S_Tt#89`rH_>x`#elmn8QfVImlYn92@_h-siW0S>~1&gWP(~Z7? zNa~*MPji|UOU0lO5jBmb?>A`F1|kuNe}KRv{ii02xm(syYhp>UCqmNp*|O&l)fUJj zYF&!ZWG$grSW|il^p-DNOk+LVsDXaDc@5>|ETOu)p;L4ih!a5koS7o_O^&0@Zd*}I ztBHNknXqyxlYi?oW$(!;V#4Yunr!4nmw{dZ=xwA;X&HE`2A+cNSb;`)$YX$InVc&! zWjwN_M~WEUc^x%cYfG^wLOQ0|igwWP@`9bg2Q<#dM$sZ;FS;3sa$VL@vBs80j7=6L z1D4T`Upzn~8i)eeOLhbCyHm0Vo)u3Q3mcUcrvKBEi7?DZdZwH^Hc40&ZKO4O_M?&D zH!^4$ee=zO{s2$UX2;VtIvdcihdk_{C*zWlDdUme0ZAgQEQJO(q7-`~#A%PMs0exN zg{U$?qf+5U`e<}NY6V1$*>2j!g3^GDL?J(1M{CsT2^zsbltCVcfvC7TQ50;1#qgBl$J{U$8^X(40>tn zKTBcDlHe}mot>$inc&3ldbC!CKyM+=`m40XH$#VMHIe5qIQ!WZEw}Q~C_P~g+Lzl+ zT^#72d43BkX1Z)c1E7mDF1;QbH^9)vsr{u$p3uF8lFgg(9DAKGT5?{h_9IfaT7OC$ zUREN7u#Z{zq$b33);W3TK~E)ggO+0}OfSk#6Ag^dNavPX!+BoQ;ezZ}s!@{Ldhr8L zlgcbln*Sll7t?B@ca5raluI)ucDz5o*JYUq@Vgru16UbRurhMtZlFkt7Iqy?X~bs*q8fc> zG)s02;yKA*#i_J?qIEz$*7fyITJ$4XJPEDAO5I=6hjY_~br*Z~N>d6Np_N^wXV-mr z9CV}%{pjP+*}gk9U0M(Oc`5AYCeUdPhc0)|4rA!Jl6|nlRbA9Tx9zKz3rl!+0DIrt z?bGO$h?CNB=;=N=K7=}FZj>6qjv6zK&^80s!kiaIM(R(V(C~aot0J(~z-`IGYw0)1 zqH-D#b?&~%UVO)0(bQ_eAGD7Z17QXmciG`T1@1+j`pl>6bDaO2yPM*}>1?=vAf(yv zAf3lt59MvRFMkMkG6(G!(1;1H6cg&|e*Zo|UbWjxu_@H@BshzT+&a@e17AtSu($U< z*`K!cD3`SEZx;8{n}|%wZgO>&fTF0m(VHQn!?&G>9kWW9j{gD zhkL0AY^Bb8_M<5I_&beqxr>J5HHtOVQB58>Ne(N}C@EVsyb$gzF3(*|i~Zav*1$BJ z2BGcc77x6X1X;^F!FhgbWfZ+??nQAVn1*xkS+HEOoksEU(DFHOBEN%^-t?;neGjK- z&3kZ)j_F6SC+L1O36_03X_U`RwH#Yv4K>jqs=vIVvPP*iM@?L>c0|m4WXqb{|5imv z$kCGl@;}awilb>;9x*XX+@o#fo+rGNZN}cJ8N|CC-jxVhaJ-H5eXx^KcV%mi&y0a5GQ@+k zby&J_IfnHJx!-k|{^xcNWl|4cj`u!HtBI|bm+5!Zs;aCk>aD8PQ8yt9<~gx=ql&7! z5i;FWr*G@xsmzjnRJ$n7qc1#{#7&8y(BP}RCdMtsG`D=;I%-=3Nx-h z5mHfk@TDKekz}Ul3Fhalh%<-S zm}4f2!`${fyH}FX@3vqqJ>O8;d!Bf-{hf4VSDt^LH*>`HF<&JYGa1e(3|e&#d9G>#TDJRRAr)%BGNomz9Oj-$eLgJ0K7ETg}gSSp`Ica;YAi#-vd z8UBEpjtdjtUx%rxTfK%(Tybj5T1A+tDox1mW*2C>R7sp19>MW?#q)t_=;>?fu}eYa z6!V}URjqIpc1_(U3Z~a(H;(*<>fX?VvSrsRD*H;isa6Rl)OoDlX~$M?zbQsl9j(&9 ze(~JE`}68ytgM`k5`L@%k# zCr{HdANxSnd>kAOPuoE@tYF7SiX(*8-q@cx&Hl(X-WUWU#IImC=KIr};i|)) znC!vbdJh&AZ!}lsfv=+Tap7Wr!{3rm?iN_>%R0O9oWhx+*K1FXM;hnt6phDNvRBEk zD84pf2H!Q}_0B}m`kt*hjvdbjrlDI~&zMK_45P$h0LK|(`u3f@q6fEQ8BS#|=iaaD zaL>9!8Nh;oqvXZ|2CLfmCW zba_F4|4BYcqQ0#a+v)KVq8c;Mhj)DK$}P+H5O@Sff;|y({?sZmT|^<_=Eb>i1gSaWPuyf07ed+f&c=*=0fIw2uVrmCUNPpi#_$1@&0&qSV zSUb7h_=Z>26b>jtYHB}neFZM);SM5+b zY)%V)_k42&$Bug$I70X${?btT&9?;~>*B6lJ)0;#jZC6Ss1LjI6^{VI*z6fjRx|@rz$9T1ZS?!qv5Rf)TCVtZsYH+V0FX0 zkbnC#3GntLAKsq)hPNk#yfPp+4@Z~@C@bwPr?_eveM@Z)#jKR7wf@Q8}wFs{($kl zA+8GU>EXG-G$B;Jk^TF&Ki9r(s+vJeH-|5T;_TsjFIU4CLJ#+qmw2!@FWKUyU|+bm zh-pHcYkl%R>Eq2~^1W2m)xfu|HmeCerHj+yDiG4CT;J^7=e&8YO4kI9i{(POUqxsfG>+t#}pHWUjN}qan$y%;Vpp69$P(&(Q@aR z8YKwcK`enc7-sMW1IMl=ZWp!JZP=~lU5Bf?gIG^Zv|Bz<|6*24zW#)>g0DL~=kuqZ z5(D!aFzs{0{qDz~uKI5K{dtR;%@jO>3H6-6e{n*;eZPh`Z>?2jj`KK9Q^osA5j5QX z7F>guYBbajG;YP8I6A8|k|tjgUpF^lHAh!sI9ft}3)*H%=7JmP)~l`n(Fp)jqIObW#A z15OOSWMbF~)9}XROMrZXdvcfVKB}lZ;T!r2bIn;Ge6z1677PrQ6Tf@%R^i?%4Qz#J z`1QcDNpfrhPj1!PNA>>W0(=v2Ga_FaJq^AIK<`4}{YO@ae8FGC*EiKF)3;m}bgB!p z8*iq{1Lp_dk@>xoe@@bJ=Ip78>gD^(qUE>7EYQf5VNdW&);g&);j0&qzNO*A!n1_6 zMTwOC(MuN$k=PZKN8_rt2M^-$`IcsK9Hi8 z{gaJ75wi6D9vTN4p+Gztnl38mK9T&Aopl-TzD4-J`<6|?zK7uLQrOPV(#;&h+a*_% zR663b7q1L!3tL$pNEcJj+>??A-p+1OBSVyHP$*UIauxD$sGmxw0I~6ohT{<&l{$}i zkjIE(FP?Ezt$}GZadJW`ZBpjNujXrb-k5YTc*z54Z+8TvBV` zDqv6WJK@!-RDR~g*TZjquobS4oSH7aq!vkTZQ4MsYMQ4~N2snZR2Pq6BByGG*xT-f ze`0ky&-n85Q-$V7)!>hcZN)eSX)tyuRAF>3vDX}+-sXpFCyN8i<+wlucqnZ(YA}yzHPZG8hRNs zJBXrQo;?4IJI7WykK`ZwMYA1wl1X_TXw(McR&V$M;@6Y z*b3K8t+BCVuwpji18q6^mN*%oE>@62DJS|t_S6CCqQk+*($^ObI;X1XqS=O%Qr`PS zh-!B1OJ>!)wo+8ZnQt1AAy(~pCY`&}SQoFPi`H{5NY_SQ)QviwF6t({kPh7M2*eOC zGqGuwo3hEqkK++c462eY9#*?31=yVgV(HeFib;2CB|dyR!y`B<>J!ZMK@Qs@I2Yg{(cI8Y_4N6F5S+3%B=YA7=XUc79D1Y=!4WP5d8a15)Y$ literal 0 HcmV?d00001 diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_wing.dae b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_wing.dae new file mode 100644 index 00000000..5f4144c3 --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_wing.dae @@ -0,0 +1,167 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-04T11:51:51 + 2023-07-04T11:51:51 + + Z_UP + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.498039 0.498039 0.498039 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.647059 0.619608 0.584314 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.65098 0.619608 0.584314 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + + + + + + + 2.47738e-4 -0.002989709 0 -2.48736e-4 -0.00298959 0.3 -2.47738e-4 -0.002989709 0 0.002999961 0 0.3 0.002999961 0 0 0.002959072 4.93784e-4 0 -7.36456e-4 -0.00290817 0 -7.37425e-4 -0.002907872 0.3 -0.001205921 -0.00274682 0.3 -0.001205086 -0.002747297 0 -0.001641571 -0.002510845 0.3 -0.001640796 -0.002511441 0 -0.002031803 -0.002207159 0 -0.002032399 -0.002206504 0.3 -0.002367794 -0.001841962 0.3 -0.002367377 -0.001842617 0 -0.002638638 -0.001427233 0.3 -0.002638399 -0.001427829 0 -0.002837419 -9.74098e-4 0 -0.002837538 -9.73636e-4 0.3 -0.002959012 -4.93921e-4 0.3 -0.002959072 -4.93784e-4 0 -0.002999961 0 0.3 -0.002999961 0 0 2.46763e-4 -0.002989768 0.3 7.36456e-4 -0.00290817 0 7.35554e-4 -0.002908349 0.3 0.001205086 -0.002747297 0 0.001204252 -0.002747595 0.3 0.001640141 -0.002511858 0.3 0.001640796 -0.002511441 0 0.002031803 -0.002207159 0 0.002031326 -0.002207577 0.3 0.002367377 -0.001842617 0 0.002367079 -0.001843035 0.3 0.002638161 -0.001428186 0.3 0.002638399 -0.001427829 0 0.002837419 -9.74098e-4 0 0.002837359 -9.74359e-4 0.3 0.002959072 -4.93784e-4 0 0.002959012 -4.93921e-4 0.3 0.002837419 9.74098e-4 0.3 0.002959072 4.93784e-4 0.3 0.002837419 9.74098e-4 0 0.002031803 0.002207159 0.3 0.002367377 0.001842617 0.3 0.002031803 0.002207159 0 0.002638399 0.001427829 0.3 0.002638399 0.001427829 0 0.002367377 0.001842617 0 0.001205086 0.002747297 0.3 7.36456e-4 0.00290817 0 7.36456e-4 0.00290817 0.3 0.001640796 0.002511441 0 0.001205086 0.002747297 0 0.001640796 0.002511441 0.3 -7.36456e-4 0.00290817 0 -7.36456e-4 0.00290817 0.3 -2.47738e-4 0.002989709 0.3 -2.47738e-4 0.002989709 0 2.47738e-4 0.002989709 0.3 2.47738e-4 0.002989709 0 -0.002031803 0.002207159 0.3 -0.001640796 0.002511441 0.3 -0.002031803 0.002207159 0 -0.001205086 0.002747297 0.3 -0.001205086 0.002747297 0 -0.001640796 0.002511441 0 -0.002638399 0.001427829 0 -0.002367377 0.001842617 0.3 -0.002367377 0.001842617 0 -0.002837419 9.74098e-4 0 -0.002638399 0.001427829 0.3 -0.002837419 9.74098e-4 0.3 -0.002959072 4.93784e-4 0 -0.002959072 4.93784e-4 0.3 -2.48736e-4 -0.00298959 0.3 -4.90369e-4 -0.001938879 0.3 -7.37425e-4 -0.002907872 0.3 -0.001758933 9.51895e-4 0.3 -0.002638399 0.001427829 0.3 -0.001891613 6.49399e-4 0.3 -0.001205921 -0.00274682 0.3 -8.02865e-4 -0.00183171 0.3 2.46763e-4 -0.002989768 0.3 -1.64509e-4 -0.001993179 0.3 -0.001641571 -0.002510845 0.3 -0.001093447 -0.001674532 0.3 7.35554e-4 -0.002908349 0.3 1.65824e-4 -0.00199306 0.3 0.001204252 -0.002747595 0.3 4.91616e-4 -0.001938521 0.3 0.001640141 -0.002511858 0.3 8.03982e-4 -0.001831173 0.3 -0.002032399 -0.002206504 0.3 -0.001354217 -0.001471698 0.3 0.001094341 -0.001673877 0.3 0.002031326 -0.002207577 0.3 -0.001578032 -0.00122869 0.3 -0.002367794 -0.001841962 0.3 -0.002959012 -4.93921e-4 0.3 -0.001891553 -6.49572e-4 0.3 -0.001972675 -3.29281e-4 0.3 0.002367079 -0.001843035 0.3 0.001354932 -0.001470983 0.3 -0.002837419 9.74098e-4 0.3 -0.001972675 3.29189e-4 0.3 0.001891672 -6.4909e-4 0.3 0.002638161 -0.001428186 0.3 0.002837359 -9.74359e-4 0.3 -0.001640796 0.002511441 0.3 -0.002031803 0.002207159 0.3 -0.001093864 0.001674294 0.3 -0.001578271 0.001228392 0.3 -0.002367377 0.001842617 0.3 -7.36456e-4 0.00290817 0.3 -1.65159e-4 0.001993119 0.3 -2.47738e-4 0.002989709 0.3 0.001578271 0.001228392 0.3 0.002638399 0.001427829 0.3 0.002367377 0.001842617 0.3 1.65159e-4 0.001993119 0.3 2.47738e-4 0.002989709 0.3 7.36456e-4 0.00290817 0.3 4.90971e-4 0.00193876 0.3 8.03391e-4 0.001831531 0.3 0.001640796 0.002511441 0.3 0.001354515 0.0014714 0.3 0.002031803 0.002207159 0.3 0.001093864 0.001674294 0.3 0.001205086 0.002747297 0.3 -8.03391e-4 0.001831531 0.3 -0.001205086 0.002747297 0.3 -4.90971e-4 0.00193876 0.3 0.002959072 4.93784e-4 0.3 0.001972675 3.29189e-4 0.3 0.002999961 0 0.3 0.001758933 9.51895e-4 0.3 0.001891613 6.49399e-4 0.3 0.002837419 9.74098e-4 0.3 0.002959012 -4.93921e-4 0.3 0.001972675 -3.29281e-4 0.3 -0.001354515 0.0014714 0.3 -0.002959072 4.93784e-4 0.3 -0.001999974 0 0.3 -0.002999961 0 0.3 0.001578509 -0.001227974 0.3 0.001759052 -9.51493e-4 0.3 -0.002638638 -0.001427233 0.3 -0.001758754 -9.52132e-4 0.3 -0.002837538 -9.73636e-4 0.3 0.001999974 0 0.3 -2.47738e-4 -0.002989709 0 -1.65824e-4 -0.00199306 0 2.47738e-4 -0.002989709 0 -0.002367377 0.001842617 0 -0.001578271 0.001228392 0 -0.001758933 9.51895e-4 0 7.36456e-4 -0.00290817 0 1.64509e-4 -0.001993179 0 -7.36456e-4 -0.00290817 0 -4.91616e-4 -0.001938521 0 4.90369e-4 -0.001938879 0 0.001205086 -0.002747297 0 -0.001205086 -0.002747297 0 -8.03982e-4 -0.001831173 0 -0.001640796 -0.002511441 0 -0.001094341 -0.001673877 0 -0.002031803 -0.002207159 0 -0.001354932 -0.001470983 0 8.02865e-4 -0.00183171 0 0.001640796 -0.002511441 0 -0.002367377 -0.001842617 0 -0.001578509 -0.001227974 0 0.002031803 -0.002207159 0 0.001093447 -0.001674532 0 0.002367377 -0.001842617 0 0.001578032 -0.00122869 0 0.001758754 -9.52132e-4 0 0.001354217 -0.001471698 0 0.002837419 -9.74098e-4 0 0.001891553 -6.49572e-4 0 0.001972675 -3.29281e-4 0 -0.001891672 -6.4909e-4 0 -0.002959072 -4.93784e-4 0 -0.001972675 -3.29281e-4 0 0.001972675 3.29189e-4 0 0.002959072 4.93784e-4 0 0.002999961 0 0 -0.001972675 3.29189e-4 0 -0.002837419 9.74098e-4 0 -0.001891613 6.49399e-4 0 0.001093864 0.001674294 0 0.002031803 0.002207159 0 0.001354515 0.0014714 0 -0.002031803 0.002207159 0 -0.001640796 0.002511441 0 -0.001093864 0.001674294 0 1.65159e-4 0.001993119 0 -2.47738e-4 0.002989709 0 2.47738e-4 0.002989709 0 -7.36456e-4 0.00290817 0 -1.65159e-4 0.001993119 0 8.03391e-4 0.001831531 0 0.001205086 0.002747297 0 7.36456e-4 0.00290817 0 4.90971e-4 0.00193876 0 -0.001205086 0.002747297 0 -8.03391e-4 0.001831531 0 -4.90971e-4 0.00193876 0 0.001758933 9.51895e-4 0 0.002837419 9.74098e-4 0 0.001891613 6.49399e-4 0 0.001578271 0.001228392 0 0.002367377 0.001842617 0 0.002638399 0.001427829 0 -0.002638399 0.001427829 0 -0.001354515 0.0014714 0 -0.002959072 4.93784e-4 0 -0.001999974 0 0 0.002959072 -4.93784e-4 0 -0.002999961 0 0 0.002638399 -0.001427829 0 -0.002638399 -0.001427829 0 -0.001759052 -9.51493e-4 0 -0.002837419 -9.74098e-4 0 0.001999974 0 0 0.001640796 0.002511441 0 -0.001972675 3.29189e-4 0.3 -0.001999974 0 0.3 -0.001999974 0 0 -0.001578271 0.001228392 0.3 -0.001758933 9.51895e-4 0.3 -0.001758933 9.51895e-4 0 -0.001891613 6.49399e-4 0.3 -0.001972675 3.29189e-4 0 -0.001891613 6.49399e-4 0 -0.001093864 0.001674294 0 -8.03391e-4 0.001831531 0.3 -0.001093864 0.001674294 0.3 -0.001578271 0.001228392 0 -0.001354515 0.0014714 0 -0.001354515 0.0014714 0.3 -1.65159e-4 0.001993119 0.3 -1.65159e-4 0.001993119 0 1.65159e-4 0.001993119 0.3 -4.90971e-4 0.00193876 0.3 -8.03391e-4 0.001831531 0 -4.90971e-4 0.00193876 0 0.001093864 0.001674294 0.3 8.03391e-4 0.001831531 0.3 8.03391e-4 0.001831531 0 4.90971e-4 0.00193876 0 4.90971e-4 0.00193876 0.3 1.65159e-4 0.001993119 0 0.001578271 0.001228392 0 0.001758933 9.51895e-4 0.3 0.001578271 0.001228392 0.3 0.001093864 0.001674294 0 0.001354515 0.0014714 0 0.001354515 0.0014714 0.3 0.001972675 3.29189e-4 0.3 0.001972675 3.29189e-4 0 0.001999974 0 0.3 0.001891613 6.49399e-4 0.3 0.001758933 9.51895e-4 0 0.001891613 6.49399e-4 0 0.001759052 -9.51493e-4 0.3 0.001891672 -6.4909e-4 0.3 0.001891553 -6.49572e-4 0 0.001972675 -3.29281e-4 0 0.001972675 -3.29281e-4 0.3 0.001999974 0 0 0.001354217 -0.001471698 0 0.001094341 -0.001673877 0.3 0.001354932 -0.001470983 0.3 0.001758754 -9.52132e-4 0 0.001578032 -0.00122869 0 0.001578509 -0.001227974 0.3 4.91616e-4 -0.001938521 0.3 4.90369e-4 -0.001938879 0 1.65824e-4 -0.00199306 0.3 8.03982e-4 -0.001831173 0.3 0.001093447 -0.001674532 0 8.02865e-4 -0.00183171 0 -1.64509e-4 -0.001993179 0.3 -1.65824e-4 -0.00199306 0 -4.90369e-4 -0.001938879 0.3 1.64509e-4 -0.001993179 0 -4.91616e-4 -0.001938521 0 -8.02865e-4 -0.00183171 0.3 -0.001093447 -0.001674532 0.3 -8.03982e-4 -0.001831173 0 -0.001094341 -0.001673877 0 -0.001354217 -0.001471698 0.3 -0.001354932 -0.001470983 0 -0.001578032 -0.00122869 0.3 -0.001758754 -9.52132e-4 0.3 -0.001578509 -0.001227974 0 -0.001759052 -9.51493e-4 0 -0.001891553 -6.49572e-4 0.3 -0.001891672 -6.4909e-4 0 -0.001972675 -3.29281e-4 0.3 -0.001972675 -3.29281e-4 0 -0.1051196 0.004806756 0.1313477 -0.1051196 0.004806756 0.1463477 -0.1049911 0.004158556 0.1463477 -0.1049711 0.003498077 0.1463477 -0.1049711 0.003498077 0.1313477 -0.1049911 0.004158556 0.1313477 -0.1056852 0.005996286 0.1463477 -0.1061068 0.006505072 0.1313477 -0.1061068 0.006505072 0.1463477 -0.1056852 0.005996286 0.1313477 -0.1053531 0.005424976 0.1463477 -0.1053531 0.005424976 0.1313477 -0.1077832 0.007528603 0.1313477 -0.1077832 0.007528603 0.1463477 -0.1071703 0.007281839 0.1463477 -0.1071703 0.007281839 0.1313477 -0.1066064 0.006937563 0.1463477 -0.1066064 0.006937563 0.1313477 -0.1097446 0.007630705 0.1463477 -0.1090881 0.00770539 0.1463477 -0.1097446 0.007630705 0.1313477 -0.1084284 0.007671058 0.1463477 -0.1084284 0.007671058 0.1313477 -0.1090881 0.00770539 0.1313477 -0.1109762 0.007165193 0.1463477 -0.1115178 0.00678718 0.1313477 -0.1115178 0.00678718 0.1463477 -0.1103796 0.007448971 0.1313477 -0.1109762 0.007165193 0.1313477 -0.1103796 0.007448971 0.1463477 -0.1126759 0.005201756 0.1313477 -0.1126759 0.005201756 0.1463477 -0.1123794 0.005791902 0.1463477 -0.1123794 0.005791902 0.1313477 -0.1119898 0.006325185 0.1463477 -0.1119898 0.006325185 0.1313477 -0.1129401 0.00325638 0.1463477 -0.1129601 0.00391674 0.1463477 -0.1129401 0.00325638 0.1313477 -0.1128711 0.004571497 0.1463477 -0.1128711 0.004571497 0.1313477 -0.1129601 0.00391674 0.1313477 -0.1125783 0.001990318 0.1463477 -0.1122463 0.001419067 0.1313477 -0.1122463 0.001419067 0.1463477 -0.1128116 0.002608358 0.1313477 -0.1125783 0.001990318 0.1313477 -0.1128116 0.002608358 0.1463477 -0.1107618 1.33433e-4 0.1313477 -0.1107618 1.33435e-4 0.1463477 -0.1113256 4.77829e-4 0.1463477 -0.1113256 4.77827e-4 0.1313477 -0.111825 9.10326e-4 0.1463477 -0.111825 9.10324e-4 0.1313477 -0.1088443 -2.90742e-4 0.1463477 -0.1095041 -2.5617e-4 0.1463477 -0.1088443 -2.90744e-4 0.1313477 -0.1101491 -1.13479e-4 0.1463477 -0.1101491 -1.13481e-4 0.1313477 -0.1095041 -2.56172e-4 0.1313477 -0.1081879 -2.16253e-4 0.1313477 -0.1075527 -3.47355e-5 0.1313477 -0.1081879 -2.16251e-4 0.1463477 -0.1075527 -3.47337e-5 0.1463477 -0.106956 2.48849e-4 0.1313477 -0.1064141 6.26781e-4 0.1313477 -0.106956 2.48851e-4 0.1463477 -0.1059419 0.001088738 0.1313477 -0.1064141 6.26783e-4 0.1463477 -0.1059419 0.001088738 0.1463477 -0.1055521 0.00162214 0.1313477 -0.1052554 0.002212405 0.1313477 -0.1055521 0.00162214 0.1463477 -0.10506 0.002843439 0.1313477 -0.1052554 0.002212405 0.1463477 -0.10506 0.002843439 0.1463477 -0.1076005 0.008517384 0.1463477 -0.1084284 0.007671058 0.1463477 -0.1083331 0.008667111 0.1463477 -0.1054823 1.20476e-4 0.1463477 -0.1059419 0.001088738 0.1463477 -0.1049866 6.79692e-4 0.1463477 -0.1062424 0.007900774 0.1463477 -0.1071703 0.007281839 0.1463477 -0.1068984 0.008260011 0.1463477 -0.1077832 0.007528603 0.1463477 -0.1090795 0.008705973 0.1463477 -0.1090881 0.00770539 0.1463477 -0.1066064 0.006937563 0.1463477 -0.1056486 0.007448613 0.1463477 -0.1061068 0.006505072 0.1463477 -0.1056852 0.005996286 0.1463477 -0.1051284 0.006912887 0.1463477 -0.1097446 0.007630705 0.1463477 -0.1098231 0.008633196 0.1463477 -0.1053531 0.005424976 0.1463477 -0.1046936 0.006305336 0.1463477 -0.1103796 0.007448971 0.1463477 -0.1105471 0.008450567 0.1463477 -0.1109762 0.007165193 0.1463477 -0.1115178 0.00678718 0.1463477 -0.1118746 0.007773935 0.1463477 -0.1112355 0.008162438 0.1463477 -0.1133514 0.006108045 0.1463477 -0.1129446 0.006735026 0.1463477 -0.1123794 0.005791902 0.1463477 -0.1049911 0.004158556 0.1463477 -0.1039893 0.004193484 0.1463477 -0.1049711 0.003498077 0.1463477 -0.1138638 0.004710912 0.1463477 -0.1136602 0.005427658 0.1463477 -0.1128711 0.004571497 0.1463477 -0.1045799 0.001306414 0.1463477 -0.1052554 0.002212405 0.1463477 -0.1042711 0.001986622 0.1463477 -0.1138138 0.002484977 0.1463477 -0.1129401 0.00325638 0.1463477 -0.1128116 0.002608358 0.1463477 -0.1064141 6.26783e-4 0.1463477 -0.1060559 -3.58694e-4 0.1463477 -0.106956 2.48851e-4 0.1463477 -0.1122822 -3.41239e-5 0.1463477 -0.1113256 4.77829e-4 0.1463477 -0.1116875 -4.86603e-4 0.1463477 -0.1081091 -0.001218616 0.1463477 -0.1088443 -2.90742e-4 0.1463477 -0.1081879 -2.16251e-4 0.1463477 -0.1107618 1.33435e-4 0.1463477 -0.1110322 -8.45368e-4 0.1463477 -0.1101491 -1.13479e-4 0.1463477 -0.1103309 -0.001102447 0.1463477 -0.1088532 -0.001291275 0.1463477 -0.1095041 -2.5617e-4 0.1463477 -0.1095993 -0.001252174 0.1463477 -0.1135773 0.001775801 0.1463477 -0.1125783 0.001990318 0.1463477 -0.1132378 0.001109838 0.1463477 -0.1128028 5.02017e-4 0.1463477 -0.1122463 0.001419067 0.1463477 -0.111825 9.10326e-4 0.1463477 -0.1075527 -3.47337e-5 0.1463477 -0.1066946 -7.47053e-4 0.1463477 -0.1073842 -0.001035869 0.1463477 -0.1139587 0.003969073 0.1463477 -0.1129601 0.00391674 0.1463477 -0.1139419 0.003221571 0.1463477 -0.1055521 0.00162214 0.1463477 -0.1126759 0.005201756 0.1463477 -0.10506 0.002843439 0.1463477 -0.1040673 0.002704143 0.1463477 -0.1124486 0.007294535 0.1463477 -0.1119898 0.006325185 0.1463477 -0.1039724 0.003445744 0.1463477 -0.1051196 0.004806756 0.1463477 -0.1041175 0.004930257 0.1463477 -0.104354 0.005639493 0.1463477 -0.1041173 0.00492978 0.1234999 -0.1051196 0.004806756 0.1313477 -0.1049911 0.004158556 0.1313477 -0.1049711 0.003498077 0.1313477 -0.1039724 0.003445744 0.1234999 -0.1039892 0.004193186 0.1234999 -0.1056852 0.005996286 0.1313477 -0.1051283 0.006912767 0.1234999 -0.1061068 0.006505072 0.1313477 -0.1046933 0.006304979 0.1234999 -0.1053531 0.005424976 0.1313477 -0.1043538 0.005639016 0.1234999 -0.1062436 0.00790143 0.1234999 -0.1068989 0.00826019 0.1234999 -0.1071703 0.007281839 0.1313477 -0.1066064 0.006937563 0.1313477 -0.1056489 0.007448911 0.1234999 -0.1090881 0.00770539 0.1313477 -0.1084284 0.007671058 0.1313477 -0.1090779 0.008706092 0.1234999 -0.1077832 0.007528603 0.1313477 -0.1076002 0.008517265 0.1234999 -0.1103796 0.007448971 0.1313477 -0.1112365 0.008161842 0.1234999 -0.1109762 0.007165193 0.1313477 -0.109822 0.008633494 0.1234999 -0.110547 0.008450686 0.1234999 -0.1097446 0.007630705 0.1313477 -0.1124488 0.007294356 0.1234999 -0.1129445 0.006735146 0.1234999 -0.1119898 0.006325185 0.1313477 -0.1118752 0.007773518 0.1234999 -0.1115178 0.00678718 0.1313477 -0.1138639 0.004710674 0.1234999 -0.1128711 0.004571497 0.1313477 -0.11366 0.005428135 0.1234999 -0.1126759 0.005201756 0.1313477 -0.1123794 0.005791902 0.1313477 -0.1133512 0.006108403 0.1234999 -0.1129401 0.00325638 0.1313477 -0.1139419 0.003221571 0.1234999 -0.1138138 0.002484977 0.1234999 -0.1139587 0.003969073 0.1234999 -0.1129601 0.00391674 0.1313477 -0.1132378 0.001109838 0.1234999 -0.1128028 5.02015e-4 0.1234999 -0.1122463 0.001419067 0.1313477 -0.1135773 0.001775801 0.1234999 -0.1125783 0.001990318 0.1313477 -0.1128116 0.002608358 0.1313477 -0.1110322 -8.45371e-4 0.1234999 -0.1107618 1.33433e-4 0.1313477 -0.1116875 -4.86606e-4 0.1234999 -0.1113256 4.77827e-4 0.1313477 -0.111825 9.10324e-4 0.1313477 -0.1122822 -3.41267e-5 0.1234999 -0.1095041 -2.56172e-4 0.1313477 -0.1095993 -0.001252174 0.1234999 -0.1088532 -0.001291275 0.1234999 -0.1101491 -1.13481e-4 0.1313477 -0.1103309 -0.001102447 0.1234999 -0.1088443 -2.90744e-4 0.1313477 -0.1081091 -0.001218616 0.1234999 -0.1081879 -2.16253e-4 0.1313477 -0.1073842 -0.001035869 0.1234999 -0.1075527 -3.47355e-5 0.1313477 -0.106956 2.48849e-4 0.1313477 -0.1066946 -7.47056e-4 0.1234999 -0.1060559 -3.58696e-4 0.1234999 -0.1064141 6.26781e-4 0.1313477 -0.1054823 1.20474e-4 0.1234999 -0.1059419 0.001088738 0.1313477 -0.1055521 0.00162214 0.1313477 -0.1049866 6.7969e-4 0.1234999 -0.1045799 0.001306414 0.1234999 -0.1052554 0.002212405 0.1313477 -0.1042711 0.001986622 0.1234999 -0.10506 0.002843439 0.1313477 -0.1040673 0.002704143 0.1234999 -0.1083318 0.008667051 0.1234999 -0.1083331 0.008667111 0.1463477 -0.1090795 0.008705973 0.1313477 -0.1083331 0.008667111 0.1313477 -0.1139587 0.003969073 0.1463477 -0.1139419 0.003221571 0.1313477 -0.1139587 0.003969073 0.1313477 -0.1076005 0.008517384 0.1313477 -0.1076005 0.008517384 0.1463477 -0.1068984 0.008260011 0.1313477 -0.1068984 0.008260011 0.1463477 -0.1062424 0.007900774 0.1463477 -0.1062424 0.007900774 0.1313477 -0.1056486 0.007448613 0.1313477 -0.1056486 0.007448613 0.1463477 -0.1051284 0.006912887 0.1313477 -0.1051284 0.006912887 0.1463477 -0.1046936 0.006305336 0.1463477 -0.1046936 0.006305336 0.1313477 -0.104354 0.005639493 0.1313477 -0.104354 0.005639493 0.1463477 -0.1041175 0.004930257 0.1313477 -0.1041175 0.004930257 0.1463477 -0.1039893 0.004193484 0.1463477 -0.1039893 0.004193484 0.1313477 -0.1039724 0.003445744 0.1463477 -0.1039724 0.003445744 0.1313477 -0.1090795 0.008705973 0.1463477 -0.1098231 0.008633196 0.1463477 -0.1098231 0.008633196 0.1313477 -0.1105471 0.008450567 0.1313477 -0.1105471 0.008450567 0.1463477 -0.1112355 0.008162438 0.1463477 -0.1112355 0.008162438 0.1313477 -0.1118746 0.007773935 0.1463477 -0.1118746 0.007773935 0.1313477 -0.1124486 0.007294535 0.1313477 -0.1124486 0.007294535 0.1463477 -0.1129446 0.006735026 0.1463477 -0.1129446 0.006735026 0.1313477 -0.1133514 0.006108045 0.1463477 -0.1133514 0.006108045 0.1313477 -0.1136602 0.005427658 0.1313477 -0.1136602 0.005427658 0.1463477 -0.1138638 0.004710912 0.1463477 -0.1138638 0.004710912 0.1313477 -0.1138138 0.002484977 0.1463477 -0.1138138 0.002484977 0.1313477 -0.1139419 0.003221571 0.1463477 -0.1128028 5.02017e-4 0.1463477 -0.1128028 5.02015e-4 0.1313477 -0.1132378 0.001109838 0.1463477 -0.1135773 0.001775801 0.1463477 -0.1132378 0.001109838 0.1313477 -0.1135773 0.001775801 0.1313477 -0.1116875 -4.86603e-4 0.1463477 -0.1110322 -8.45368e-4 0.1463477 -0.1110322 -8.4537e-4 0.1313477 -0.1122822 -3.41258e-5 0.1313477 -0.1122822 -3.41239e-5 0.1463477 -0.1116875 -4.86605e-4 0.1313477 -0.1088532 -0.001291275 0.1313477 -0.1095993 -0.001252174 0.1463477 -0.1088532 -0.001291275 0.1463477 -0.1095993 -0.001252174 0.1313477 -0.1103309 -0.001102447 0.1313477 -0.1103309 -0.001102447 0.1463477 -0.1066946 -7.47053e-4 0.1463477 -0.1066946 -7.47055e-4 0.1313477 -0.1073842 -0.001035869 0.1463477 -0.1081091 -0.001218616 0.1463477 -0.1073842 -0.001035869 0.1313477 -0.1081091 -0.001218616 0.1313477 -0.1054823 1.20476e-4 0.1463477 -0.1049866 6.79691e-4 0.1313477 -0.1054823 1.20474e-4 0.1313477 -0.1060559 -3.58695e-4 0.1313477 -0.1060559 -3.58694e-4 0.1463477 -0.1045799 0.001306414 0.1313477 -0.1049866 6.79692e-4 0.1463477 -0.1045799 0.001306414 0.1463477 -0.1042711 0.001986622 0.1313477 -0.1042711 0.001986622 0.1463477 -0.1040673 0.002704143 0.1313477 -0.1040673 0.002704143 0.1463477 -0.11366 0.005428135 0.1234999 -0.1136593 0.005430221 0.1034999 -0.1138638 0.004710912 0.1034999 -0.1139587 0.003969013 0.1034999 -0.1139587 0.003969073 0.1234999 -0.1138639 0.004710674 0.1234999 -0.1129426 0.006737589 0.1034999 -0.1124488 0.007294356 0.1234999 -0.1124466 0.007296383 0.1034999 -0.1129445 0.006735146 0.1234999 -0.1133499 0.006110906 0.1034999 -0.1133512 0.006108403 0.1234999 -0.110547 0.008450686 0.1234999 -0.1105456 0.008451163 0.1034999 -0.1112355 0.008162438 0.1034999 -0.1112365 0.008161842 0.1234999 -0.1118733 0.007774829 0.1034999 -0.1118752 0.007773518 0.1234999 -0.1083298 0.008666694 0.1034999 -0.1090762 0.008706092 0.1034999 -0.1083318 0.008667051 0.1234999 -0.1098204 0.008633732 0.1034999 -0.109822 0.008633494 0.1234999 -0.1090779 0.008706092 0.1234999 -0.1068969 0.008259296 0.1034999 -0.1062436 0.00790143 0.1234999 -0.1062424 0.007900774 0.1034999 -0.1076002 0.008517265 0.1234999 -0.1068989 0.00826019 0.1234999 -0.107598 0.00851655 0.1034999 -0.1046933 0.006304979 0.1234999 -0.1046919 0.006302595 0.1034999 -0.1051266 0.00691086 0.1034999 -0.1051283 0.006912767 0.1234999 -0.1056473 0.0074476 0.1034999 -0.1056489 0.007448911 0.1234999 -0.1039893 0.004193484 0.1034999 -0.1041169 0.004927575 0.1034999 -0.1039892 0.004193186 0.1234999 -0.1043528 0.005636453 0.1034999 -0.1043538 0.005639016 0.1234999 -0.1041173 0.00492978 0.1234999 -0.1040673 0.002704143 0.1034999 -0.1042711 0.001986622 0.1234999 -0.1042716 0.001984953 0.1034999 -0.1039724 0.003445744 0.1234999 -0.1040673 0.002704143 0.1234999 -0.1039724 0.003445744 0.1034999 -0.1054823 1.20474e-4 0.1234999 -0.1054843 1.18503e-4 0.1034999 -0.1049882 6.77546e-4 0.1034999 -0.1049866 6.7969e-4 0.1234999 -0.1045809 0.001304328 0.1034999 -0.1045799 0.001306414 0.1234999 -0.1073861 -0.001036405 0.1034999 -0.1066969 -7.48131e-4 0.1034999 -0.1073842 -0.001035869 0.1234999 -0.1060582 -3.60283e-4 0.1034999 -0.1060559 -3.58696e-4 0.1234999 -0.1066946 -7.47056e-4 0.1234999 -0.1088537 -0.001291275 0.1034999 -0.1095993 -0.001252174 0.1234999 -0.1095998 -0.001252174 0.1034999 -0.1081091 -0.001218616 0.1234999 -0.1088532 -0.001291275 0.1234999 -0.1081104 -0.001218795 0.1034999 -0.1103309 -0.001102447 0.1234999 -0.1110322 -8.45371e-4 0.1234999 -0.1103323 -0.001102149 0.1034999 -0.1116875 -4.86606e-4 0.1234999 -0.1110341 -8.44613e-4 0.1034999 -0.1116896 -4.85304e-4 0.1034999 -0.1122822 -3.41267e-5 0.1234999 -0.1128028 5.02015e-4 0.1234999 -0.1122843 -3.23176e-5 0.1034999 -0.1132378 0.001109838 0.1234999 -0.1128046 5.04179e-4 0.1034999 -0.1132391 0.001112103 0.1034999 -0.1135773 0.001775801 0.1234999 -0.1138138 0.002484977 0.1234999 -0.1135782 0.001777946 0.1034999 -0.1139419 0.003221571 0.1234999 -0.1138142 0.002486705 0.1034999 -0.1139419 0.003221571 0.1034999 -0.1076005 0.008517384 0.1313477 -0.1083331 0.008667111 0.1313477 -0.1080724 0.009640395 0.1234999 -0.1139587 0.003969073 0.1313477 -0.114943 0.003187298 0.1234999 -0.1149573 0.004021346 0.1234999 -0.1072594 0.009459555 0.1234999 -0.1068984 0.008260011 0.1313477 -0.1064788 0.009167671 0.1234999 -0.1062424 0.007900774 0.1313477 -0.1057457 0.008770167 0.1234999 -0.1050746 0.008274734 0.1234999 -0.1044796 0.00769174 0.1234999 -0.1056486 0.007448613 0.1313477 -0.1039713 0.007032394 0.1234999 -0.1051284 0.006912887 0.1313477 -0.1046936 0.006305336 0.1313477 -0.1035588 0.006308555 0.1234999 -0.1032505 0.005533993 0.1234999 -0.104354 0.005639493 0.1313477 -0.1030523 0.004723787 0.1234999 -0.1041175 0.004930257 0.1313477 -0.1039893 0.004193484 0.1313477 -0.1029685 0.003893792 0.1234999 -0.1039724 0.003445744 0.1313477 -0.1029738 0.003393411 0.1234999 -0.1090795 0.008705973 0.1313477 -0.1089017 0.009707033 0.1234999 -0.1098231 0.008633196 0.1313477 -0.1097345 0.009657919 0.1234999 -0.1105522 0.009493708 0.1234999 -0.1105471 0.008450567 0.1313477 -0.1112355 0.008162438 0.1313477 -0.111339 0.009217858 0.1234999 -0.1118746 0.007773935 0.1313477 -0.1120794 0.008835911 0.1234999 -0.1127593 0.008355617 0.1234999 -0.1124486 0.007294535 0.1313477 -0.1129446 0.006735026 0.1313477 -0.1133666 0.007785439 0.1234999 -0.1133514 0.006108045 0.1313477 -0.1138896 0.007135629 0.1234999 -0.1143174 0.006419777 0.1234999 -0.1136602 0.005427658 0.1313477 -0.1138638 0.004710912 0.1313477 -0.1146416 0.00565195 0.1234999 -0.1148558 0.004849433 0.1234999 -0.1138138 0.002484977 0.1313477 -0.114813 0.002363383 0.1234999 -0.1139419 0.003221571 0.1313477 -0.1128028 5.02015e-4 0.1313477 -0.113768 1.10786e-4 0.1234999 -0.1132378 0.001109838 0.1313477 -0.1135773 0.001775801 0.1313477 -0.1142195 8.10153e-4 0.1234999 -0.1145702 0.001565873 0.1234999 -0.1116875 -4.86605e-4 0.1313477 -0.1110322 -8.4537e-4 0.1313477 -0.1118987 -0.001526594 0.1234999 -0.1132236 -5.19767e-4 0.1234999 -0.1122822 -3.41258e-5 0.1313477 -0.1125962 -0.001069426 0.1234999 -0.1103501 -0.002130508 0.1234999 -0.1095993 -0.001252174 0.1313477 -0.1095291 -0.002266049 0.1234999 -0.1111451 -0.001882493 0.1234999 -0.1103309 -0.001102447 0.1313477 -0.1070596 -0.001981675 0.1234999 -0.1078666 -0.002190947 0.1234999 -0.1073842 -0.001035869 0.1313477 -0.1081091 -0.001218616 0.1313477 -0.1086952 -0.002286434 0.1234999 -0.1088532 -0.001291275 0.1313477 -0.1060559 -3.58695e-4 0.1313477 -0.1054823 1.20474e-4 0.1313477 -0.1049196 -7.2319e-4 0.1234999 -0.1062899 -0.001662731 0.1234999 -0.1066946 -7.47055e-4 0.1313477 -0.1055724 -0.001240789 0.1234999 -0.1049866 6.79691e-4 0.1313477 -0.1043443 -1.19211e-4 0.1234999 -0.1038584 5.58501e-4 0.1234999 -0.1045799 0.001306414 0.1313477 -0.1042711 0.001986622 0.1313477 -0.1034713 0.001296579 0.1234999 -0.1040673 0.002704143 0.1313477 -0.1031909 0.002078473 0.1234999 -0.1030208 0.002895176 0.1234999 -0.1105456 0.008451163 0.1034999 -0.1105489 0.009494543 0.1034999 -0.1113356 0.009219348 0.1034999 -0.1110341 -8.44613e-4 0.1034999 -0.1116896 -4.85304e-4 0.1034999 -0.1119019 -0.001524806 0.1034999 -0.1112355 0.008162438 0.1034999 -0.1098204 0.008633732 0.1034999 -0.1097323 0.009658038 0.1034999 -0.1118733 0.007774829 0.1034999 -0.112077 0.008837521 0.1034999 -0.1089017 0.009707033 0.1034999 -0.1090762 0.008706092 0.1034999 -0.1083298 0.008666694 0.1034999 -0.1080702 0.009640157 0.1034999 -0.1072561 0.009458661 0.1034999 -0.107598 0.00851655 0.1034999 -0.1124466 0.007296383 0.1034999 -0.1127585 0.008356451 0.1034999 -0.1068969 0.008259296 0.1034999 -0.1064754 0.009166121 0.1034999 -0.1129426 0.006737589 0.1034999 -0.1133658 0.007786273 0.1034999 -0.1050738 0.008273839 0.1034999 -0.1062424 0.007900774 0.1034999 -0.1056473 0.0074476 0.1034999 -0.1057433 0.008768498 0.1034999 -0.1046919 0.006302595 0.1034999 -0.1039696 0.007030069 0.1034999 -0.1051266 0.00691086 0.1034999 -0.1044787 0.007690846 0.1034999 -0.1043528 0.005636453 0.1034999 -0.1041169 0.004927575 0.1034999 -0.1032495 0.005530714 0.1034999 -0.1035572 0.006305277 0.1034999 -0.1030523 0.004723787 0.1034999 -0.1039893 0.004193484 0.1034999 -0.1034482 0.003918945 0.1034999 -0.1039724 0.003445744 0.1034999 -0.1133499 0.006110906 0.1034999 -0.1138879 0.007137894 0.1034999 -0.1029685 0.003893792 0.1034999 -0.1034727 0.00129342 0.1034999 -0.1042716 0.001984953 0.1034999 -0.1045809 0.001304328 0.1034999 -0.1148137 0.002366721 0.1034999 -0.1145716 0.001569271 0.1034999 -0.1138142 0.002486705 0.1034999 -0.1038603 5.55426e-4 0.1034999 -0.1049882 6.77546e-4 0.1034999 -0.1043462 -1.21385e-4 0.1034999 -0.1035005 0.002920329 0.1034999 -0.1031909 0.002078473 0.1034999 -0.1030208 0.002895176 0.1034999 -0.1066969 -7.48131e-4 0.1034999 -0.1062925 -0.001664161 0.1034999 -0.1055733 -0.001241564 0.1034999 -0.1049206 -7.23954e-4 0.1034999 -0.1054843 1.18503e-4 0.1034999 -0.1060582 -3.60283e-4 0.1034999 -0.1081104 -0.001218795 0.1034999 -0.1078699 -0.002191543 0.1034999 -0.1073861 -0.001036405 0.1034999 -0.1070631 -0.001982808 0.1034999 -0.1088537 -0.001291275 0.1034999 -0.1095998 -0.001252174 0.1034999 -0.1095291 -0.002266049 0.1034999 -0.1086974 -0.002286434 0.1034999 -0.1111483 -0.001881361 0.1034999 -0.1103323 -0.001102149 0.1034999 -0.1103522 -0.002130091 0.1034999 -0.1122843 -3.23176e-5 0.1034999 -0.1125984 -0.001067578 0.1034999 -0.1137688 1.11706e-4 0.1034999 -0.1132244 -5.18856e-4 0.1034999 -0.1128046 5.04179e-4 0.1034999 -0.114221 8.12633e-4 0.1034999 -0.1135782 0.001777946 0.1034999 -0.1132391 0.001112103 0.1034999 -0.1139419 0.003221571 0.1034999 -0.114943 0.003187239 0.1034999 -0.1138638 0.004710912 0.1034999 -0.1148558 0.004849433 0.1034999 -0.1139587 0.003969013 0.1034999 -0.1143157 0.006422996 0.1034999 -0.1136593 0.005430221 0.1034999 -0.1146405 0.005655169 0.1034999 -0.1149573 0.004021346 0.1034999 -0.1040673 0.002704143 0.1034999 -0.1149573 0.004021346 0.1034999 -0.1149573 0.004021346 0.1234999 -0.114943 0.003187239 0.1034999 -0.114943 0.003187298 0.1234999 -0.1148137 0.002366721 0.1034999 -0.1145716 0.001569271 0.1034999 -0.114813 0.002363383 0.1234999 -0.1145702 0.001565873 0.1234999 -0.114221 8.12633e-4 0.1034999 -0.1142195 8.10153e-4 0.1234999 -0.1137688 1.11706e-4 0.1034999 -0.1132244 -5.18856e-4 0.1034999 -0.113768 1.10786e-4 0.1234999 -0.1132236 -5.19767e-4 0.1234999 -0.1125984 -0.001067578 0.1034999 -0.1125962 -0.001069426 0.1234999 -0.1119019 -0.001524806 0.1034999 -0.1111483 -0.001881361 0.1034999 -0.1118987 -0.001526594 0.1234999 -0.1111451 -0.001882493 0.1234999 -0.1103522 -0.002130091 0.1034999 -0.1103501 -0.002130508 0.1234999 -0.1095291 -0.002266049 0.1034999 -0.1086974 -0.002286434 0.1034999 -0.1095291 -0.002266049 0.1234999 -0.1086952 -0.002286434 0.1234999 -0.1078699 -0.002191543 0.1034999 -0.1078666 -0.002190947 0.1234999 -0.1070631 -0.001982808 0.1034999 -0.1062925 -0.001664161 0.1034999 -0.1070596 -0.001981675 0.1234999 -0.1062899 -0.001662731 0.1234999 -0.1055733 -0.001241564 0.1034999 -0.1055724 -0.001240789 0.1234999 -0.1049206 -7.23954e-4 0.1034999 -0.1043462 -1.21385e-4 0.1034999 -0.1049196 -7.2319e-4 0.1234999 -0.1043443 -1.19211e-4 0.1234999 -0.1038603 5.55426e-4 0.1034999 -0.1038584 5.58501e-4 0.1234999 -0.1034727 0.00129342 0.1034999 -0.1031909 0.002078473 0.1034999 -0.1034713 0.001296579 0.1234999 -0.1031909 0.002078473 0.1234999 -0.1030208 0.002895176 0.1034999 -0.1030208 0.002895176 0.1234999 -0.1148558 0.004849433 0.1234999 -0.1146416 0.00565195 0.1234999 -0.1148558 0.004849433 0.1034999 -0.1146405 0.005655169 0.1034999 -0.1143174 0.006419777 0.1234999 -0.1143157 0.006422996 0.1034999 -0.1138896 0.007135629 0.1234999 -0.1133666 0.007785439 0.1234999 -0.1138879 0.007137894 0.1034999 -0.1133658 0.007786273 0.1034999 -0.1127593 0.008355617 0.1234999 -0.1127585 0.008356451 0.1034999 -0.1120794 0.008835911 0.1234999 -0.111339 0.009217858 0.1234999 -0.112077 0.008837521 0.1034999 -0.1113356 0.009219348 0.1034999 -0.1105522 0.009493708 0.1234999 -0.1105489 0.009494543 0.1034999 -0.1097345 0.009657919 0.1234999 -0.1089017 0.009707033 0.1234999 -0.1097323 0.009658038 0.1034999 -0.1089017 0.009707033 0.1034999 -0.1080724 0.009640395 0.1234999 -0.1080702 0.009640157 0.1034999 -0.1072594 0.009459555 0.1234999 -0.1064788 0.009167671 0.1234999 -0.1072561 0.009458661 0.1034999 -0.1064754 0.009166121 0.1034999 -0.1057457 0.008770167 0.1234999 -0.1057433 0.008768498 0.1034999 -0.1050746 0.008274734 0.1234999 -0.1044796 0.00769174 0.1234999 -0.1050738 0.008273839 0.1034999 -0.1044787 0.007690846 0.1034999 -0.1039713 0.007032394 0.1234999 -0.1039696 0.007030069 0.1034999 -0.1035588 0.006308555 0.1234999 -0.1032505 0.005533993 0.1234999 -0.1035572 0.006305277 0.1034999 -0.1032495 0.005530714 0.1034999 -0.1030523 0.004723787 0.1234999 -0.1030523 0.004723787 0.1034999 -0.1029685 0.003893792 0.1234999 -0.1029685 0.003893792 0.1034999 -0.1029738 0.003393411 0.1234999 -0.09351414 0.002397 0.1234999 -0.1030208 0.002895176 0.1234999 -0.1029685 0.003893792 0.1234999 -0.09346181 0.003395617 0.1234999 -0.1181974 0.005693197 0.09691452 -0.1182361 0.004693865 0.0967499 -0.1181838 0.005692481 0.0967499 -0.1183943 0.005703568 0.09736412 -0.1183565 0.004700183 0.0972259 -0.1183041 0.0056988 0.0972259 -0.1182379 0.005695343 0.09707462 -0.1182903 0.004696726 0.09707462 -0.1182497 0.004694581 0.09691452 -0.1186885 0.004717588 0.0975871 -0.1186362 0.005716204 0.0975871 -0.1187813 0.005723834 0.09766572 -0.1184467 0.004704892 0.09736412 -0.1185061 0.005709409 0.0974856 -0.1185584 0.004710793 0.0974856 -0.1191 0.005740523 0.09774649 -0.1192649 0.005749166 0.09774649 -0.1191523 0.004741907 0.09774649 -0.1189373 0.005731999 0.09771931 -0.1189896 0.004733383 0.09771931 -0.1188336 0.004725158 0.09766572 -0.1197286 0.005773484 0.0975871 -0.1196359 0.004767239 0.09766572 -0.1195836 0.005765855 0.09766572 -0.11948 0.004759073 0.09771931 -0.1193172 0.004750549 0.09774649 -0.1194276 0.005757689 0.09771931 -0.1200228 0.004787504 0.09736412 -0.1199705 0.00578612 0.09736412 -0.1200606 0.005790829 0.0972259 -0.1197809 0.004774808 0.0975871 -0.1198588 0.005780279 0.0974856 -0.1199111 0.004781663 0.0974856 -0.1201674 0.005796432 0.09691452 -0.1201811 0.005797147 0.0967499 -0.1202197 0.004797816 0.09691452 -0.120127 0.005794346 0.09707462 -0.1201793 0.00479573 0.09707462 -0.120113 0.004792213 0.0972259 -0.1200606 0.005790829 0.09627401 -0.1201793 0.00479573 0.09642523 -0.120127 0.005794346 0.09642523 -0.1202197 0.004797816 0.09658533 -0.1202334 0.004798531 0.0967499 -0.1201674 0.005796432 0.09658533 -0.1199111 0.004781663 0.0960142 -0.1198588 0.005780279 0.0960142 -0.1197286 0.005773484 0.09591269 -0.120113 0.004792213 0.09627401 -0.1199705 0.00578612 0.09613573 -0.1200228 0.004787504 0.09613573 -0.1194276 0.005757689 0.09578049 -0.1192649 0.005749166 0.09575331 -0.11948 0.004759073 0.09578049 -0.1195836 0.005765855 0.09583413 -0.1196359 0.004767239 0.09583413 -0.1197809 0.004774808 0.09591269 -0.1191 0.005740523 0.09575331 -0.1189373 0.005731999 0.09578049 -0.1191523 0.004741907 0.09575331 -0.1193172 0.004750549 0.09575331 -0.1189896 0.004733383 0.09578049 -0.1187813 0.005723834 0.09583413 -0.1186362 0.005716204 0.09591269 -0.1188336 0.004725158 0.09583413 -0.1185061 0.005709409 0.0960142 -0.1186885 0.004717588 0.09591269 -0.1185584 0.004710793 0.0960142 -0.1183943 0.005703568 0.09613573 -0.1183041 0.0056988 0.09627401 -0.1184467 0.004704892 0.09613573 -0.1182379 0.005695343 0.09642523 -0.1183565 0.004700183 0.09627401 -0.1182903 0.004696726 0.09642523 -0.1181974 0.005693197 0.09658533 -0.1182497 0.004694581 0.09658533 -0.09351414 0.002397 0.1234999 -0.09346181 0.003395617 0.0909999 -0.09351414 0.002397 0.0909999 -0.09346181 0.003395617 0.1234999 -0.1030208 0.002895176 0.1034999 -0.09351414 0.002397 0.1234999 -0.09351414 0.002397 0.0909999 -0.1030208 0.002895176 0.1024999 -0.1035005 0.002920329 0.1024999 -0.1035005 0.002920329 0.1034999 -0.1030208 0.002895176 0.0909999 -0.1030208 0.002895176 0.1234999 -0.1035005 0.002920329 0.1024999 -0.1034482 0.003918945 0.1034999 -0.1035005 0.002920329 0.1034999 -0.1034482 0.003918945 0.1024999 -0.1029685 0.003893792 0.1024999 -0.1029685 0.003893792 0.0909999 -0.09346181 0.003395617 0.0909999 -0.1029685 0.003893792 0.1034999 -0.1034482 0.003918945 0.1024999 -0.1034482 0.003918945 0.1034999 -0.1029685 0.003893792 0.1234999 -0.09346181 0.003395617 0.1234999 -0.1032542 0.005545437 0.0909999 -0.1030536 0.004731118 0.1024999 -0.1032542 0.005545437 0.1024999 -0.1029685 0.003893792 0.1024999 -0.1030536 0.004731118 0.0909999 -0.1029685 0.003893792 0.0909999 -0.1039864 0.007055103 0.1024999 -0.1045036 0.007718741 0.1024999 -0.1045036 0.007718741 0.0909999 -0.1039864 0.007055103 0.0909999 -0.1035672 0.00632584 0.0909999 -0.1035672 0.00632584 0.1024999 -0.1065315 0.009191334 0.0909999 -0.1057893 0.008797645 0.1024999 -0.1065315 0.009191334 0.1024999 -0.1057893 0.008797645 0.0909999 -0.1051087 0.008303582 0.0909999 -0.1051087 0.008303582 0.1024999 -0.1089839 0.009707331 0.1024999 -0.1089839 0.009707272 0.0909999 -0.1081446 0.009650826 0.1024999 -0.1073217 0.009477674 0.1024999 -0.1081446 0.009650826 0.0909999 -0.1073217 0.009477674 0.0909999 -0.1106456 0.009467363 0.1024999 -0.1114339 0.009176015 0.1024999 -0.1114339 0.009176015 0.0909999 -0.1098232 0.00964576 0.0909999 -0.1098232 0.00964576 0.1024999 -0.1106457 0.009467363 0.0909999 -0.1121737 0.008777558 0.1024999 -0.1128509 0.008279383 0.1024999 -0.1128509 0.008279383 0.0909999 -0.1121737 0.008777558 0.0909999 -0.113452 0.007691204 0.1024999 -0.113452 0.007691204 0.0909999 -0.1139652 0.007024526 0.0909999 -0.1139652 0.007024526 0.1024999 -0.1143801 0.006292402 0.1024999 -0.1143801 0.006292402 0.0909999 -0.1146886 0.005509376 0.1024999 -0.1146886 0.005509316 0.0909999 -0.1181974 0.005693197 0.09658533 -0.1182379 0.005695343 0.09642523 -0.1146886 0.005509316 0.0909999 -0.1241756 0.006006479 0.0909999 -0.1195836 0.005765855 0.09583413 -0.1197286 0.005773484 0.09591269 -0.1201811 0.005797147 0.0967499 -0.1241756 0.006006479 0.1024999 -0.1146886 0.005509376 0.1024999 -0.1182379 0.005695343 0.09707462 -0.1181974 0.005693197 0.09691452 -0.120127 0.005794346 0.09642523 -0.1201674 0.005796432 0.09658533 -0.1199705 0.00578612 0.09613573 -0.1200606 0.005790829 0.09627401 -0.1198588 0.005780279 0.0960142 -0.1192649 0.005749166 0.09575331 -0.1194276 0.005757689 0.09578049 -0.1191 0.005740523 0.09575331 -0.1187813 0.005723834 0.09583413 -0.1189373 0.005731999 0.09578049 -0.1185061 0.005709409 0.0960142 -0.1186362 0.005716204 0.09591269 -0.1183041 0.0056988 0.09627401 -0.1183943 0.005703568 0.09613573 -0.1181838 0.005692481 0.0967499 -0.1187813 0.005723834 0.09766572 -0.1186362 0.005716204 0.0975871 -0.1183943 0.005703568 0.09736412 -0.1183041 0.0056988 0.0972259 -0.1185061 0.005709409 0.0974856 -0.1191 0.005740523 0.09774649 -0.1189373 0.005731999 0.09771931 -0.1192649 0.005749166 0.09774649 -0.1195836 0.005765855 0.09766572 -0.1194276 0.005757689 0.09771931 -0.1198588 0.005780279 0.0974856 -0.1197286 0.005773484 0.0975871 -0.1200606 0.005790829 0.0972259 -0.1199705 0.00578612 0.09736412 -0.1201674 0.005796432 0.09691452 -0.120127 0.005794346 0.09707462 -0.124228 0.005007863 0.1024999 -0.124228 0.005007863 0.0909999 -0.1241756 0.006006479 0.0909999 -0.1241756 0.006006479 0.1024999 -0.1202334 0.004798531 0.0967499 -0.124228 0.005007863 0.1024999 -0.1202197 0.004797816 0.09691452 -0.1196359 0.004767239 0.09766572 -0.1197809 0.004774808 0.0975871 -0.124228 0.005007863 0.0909999 -0.1139075 0.00446707 0.1024999 -0.1182903 0.004696726 0.09707462 -0.1183565 0.004700183 0.0972259 -0.120113 0.004792213 0.0972259 -0.1201793 0.00479573 0.09707462 -0.1199111 0.004781663 0.0974856 -0.1200228 0.004787504 0.09736412 -0.1193172 0.004750549 0.09774649 -0.11948 0.004759073 0.09771931 -0.1191523 0.004741907 0.09774649 -0.1188336 0.004725158 0.09766572 -0.1189896 0.004733383 0.09771931 -0.1185584 0.004710793 0.0974856 -0.1186885 0.004717588 0.0975871 -0.1184467 0.004704892 0.09736412 -0.1182361 0.004693865 0.0967499 -0.1182497 0.004694581 0.09691452 -0.1139075 0.00446707 0.0909999 -0.1188336 0.004725158 0.09583413 -0.1186885 0.004717588 0.09591269 -0.1182903 0.004696726 0.09642523 -0.1182497 0.004694581 0.09658533 -0.1184467 0.004704892 0.09613573 -0.1183565 0.004700183 0.09627401 -0.1185584 0.004710793 0.0960142 -0.1191523 0.004741907 0.09575331 -0.1189896 0.004733383 0.09578049 -0.1193172 0.004750549 0.09575331 -0.1196359 0.004767239 0.09583413 -0.11948 0.004759073 0.09578049 -0.1199111 0.004781663 0.0960142 -0.1197809 0.004774808 0.09591269 -0.120113 0.004792213 0.09627401 -0.1200228 0.004787504 0.09613573 -0.1202197 0.004797816 0.09658533 -0.1201793 0.00479573 0.09642523 -0.109214 0.008701205 0.0909999 -0.1084542 0.008681178 0.1024999 -0.1084543 0.008681178 0.0909999 -0.1040723 0.002679705 0.1024999 -0.1039724 0.003445744 0.0909999 -0.1039724 0.003445744 0.1024999 -0.109968 0.008605837 0.0909999 -0.109214 0.008701205 0.1024999 -0.109968 0.008605837 0.1024999 -0.1106988 0.00839734 0.0909999 -0.1113895 0.008080482 0.0909999 -0.1106988 0.00839734 0.1024999 -0.1120241 0.007662713 0.0909999 -0.1113895 0.008080482 0.1024999 -0.112024 0.007662713 0.1024999 -0.1125879 0.007153749 0.0909999 -0.1130681 0.006565272 0.0909999 -0.1125879 0.007153749 0.1024999 -0.1134536 0.005911111 0.0909999 -0.1130681 0.006565272 0.1024999 -0.1134536 0.005911111 0.1024999 -0.1137353 0.0052073 0.0909999 -0.1139075 0.00446707 0.0909999 -0.1137353 0.0052073 0.1024999 -0.1139075 0.00446707 0.1024999 -0.1077074 0.008546411 0.1024999 -0.1069893 0.008300125 0.1024999 -0.1077074 0.008546411 0.0909999 -0.1063166 0.007947862 0.1024999 -0.1069893 0.008300125 0.0909999 -0.1063166 0.007947862 0.0909999 -0.1057049 0.007497727 0.1024999 -0.1051683 0.006960034 0.1024999 -0.1057049 0.007497727 0.0909999 -0.1047193 0.006347179 0.1024999 -0.1051683 0.006960034 0.0909999 -0.1047193 0.006347179 0.0909999 -0.1043683 0.005673229 0.1024999 -0.1041234 0.004953801 0.1024999 -0.1043683 0.005673229 0.0909999 -0.1039904 0.004205524 0.1024999 -0.1041234 0.004953801 0.0909999 -0.1039904 0.004205524 0.0909999 -0.1050477 6.01211e-4 0.1024999 -0.1046162 0.001241326 0.0909999 -0.1046162 0.001241326 0.1024999 -0.1042884 0.001940131 0.1024999 -0.1042885 0.001940131 0.0909999 -0.1040723 0.002679705 0.0909999 -0.1061786 -4.43737e-4 0.0909999 -0.1061786 -4.43736e-4 0.1024999 -0.1068512 -8.23469e-4 0.1024999 -0.1050477 6.01209e-4 0.0909999 -0.1055726 3.4977e-5 0.1024999 -0.1055726 3.49756e-5 0.0909999 -0.1083307 -0.001252055 0.1024999 -0.1091023 -0.001290678 0.1024999 -0.1083307 -0.001252055 0.0909999 -0.1075743 -0.001095056 0.1024999 -0.1075743 -0.001095056 0.0909999 -0.1068512 -8.2347e-4 0.0909999 -0.1113221 -7.02287e-4 0.1024999 -0.1106153 -0.001012384 0.0909999 -0.1106153 -0.001012384 0.1024999 -0.1098694 -0.001210093 0.0909999 -0.1091023 -0.001290678 0.0909999 -0.1098694 -0.001210093 0.1024999 -0.112552 2.23673e-4 0.0909999 -0.112552 2.23674e-4 0.1024999 -0.1130457 8.17506e-4 0.1024999 -0.1113221 -7.02288e-4 0.0909999 -0.1119728 -2.86974e-4 0.1024999 -0.1119728 -2.86975e-4 0.0909999 -0.1134421 0.00148034 0.1024999 -0.1130457 8.17504e-4 0.0909999 -0.1137318 0.00219649 0.1024999 -0.1134421 0.00148034 0.0909999 -0.1137318 0.00219649 0.0909999 -0.1139076 0.002948701 0.1024999 -0.1139656 0.003719031 0.1024999 -0.1139076 0.002948701 0.0909999 -0.1139656 0.003719031 0.0909999 -0.09351414 0.002397 0.0909999 -0.09346181 0.003395617 0.0909999 -0.1029685 0.003893792 0.0909999 -0.109214 0.008701205 0.0909999 -0.1098232 0.00964576 0.0909999 -0.1106457 0.009467363 0.0909999 -0.1114339 0.009176015 0.0909999 -0.109968 0.008605837 0.0909999 -0.1031855 0.002097964 0.0909999 -0.1040723 0.002679705 0.0909999 -0.1042885 0.001940131 0.0909999 -0.1030208 0.002895176 0.0909999 -0.1106988 0.00839734 0.0909999 -0.1121737 0.008777558 0.0909999 -0.1089839 0.009707272 0.0909999 -0.1128509 0.008279383 0.0909999 -0.1113895 0.008080482 0.0909999 -0.113452 0.007691204 0.0909999 -0.1120241 0.007662713 0.0909999 -0.1125879 0.007153749 0.0909999 -0.1139652 0.007024526 0.0909999 -0.1130681 0.006565272 0.0909999 -0.1143801 0.006292402 0.0909999 -0.1134536 0.005911111 0.0909999 -0.1146886 0.005509316 0.0909999 -0.1137353 0.0052073 0.0909999 -0.1139075 0.00446707 0.0909999 -0.1041234 0.004953801 0.0909999 -0.1030536 0.004731118 0.0909999 -0.1032542 0.005545437 0.0909999 -0.1043683 0.005673229 0.0909999 -0.1035672 0.00632584 0.0909999 -0.1241756 0.006006479 0.0909999 -0.124228 0.005007863 0.0909999 -0.1130457 8.17504e-4 0.0909999 -0.114423 0.001214504 0.0909999 -0.1140358 4.99318e-4 0.0909999 -0.1109013 -0.001971602 0.0909999 -0.1101151 -0.002181351 0.0909999 -0.1098694 -0.001210093 0.0909999 -0.1039724 0.003445744 0.0909999 -0.1039904 0.004205524 0.0909999 -0.1047193 0.006347179 0.0909999 -0.1039864 0.007055103 0.0909999 -0.1057049 0.007497727 0.0909999 -0.1045036 0.007718741 0.0909999 -0.1063166 0.007947862 0.0909999 -0.1051087 0.008303582 0.0909999 -0.1069893 0.008300125 0.0909999 -0.1077074 0.008546411 0.0909999 -0.1057893 0.008797645 0.0909999 -0.1051683 0.006960034 0.0909999 -0.1065315 0.009191334 0.0909999 -0.1073217 0.009477674 0.0909999 -0.1081446 0.009650826 0.0909999 -0.1084543 0.008681178 0.0909999 -0.1046162 0.001241326 0.0909999 -0.1038287 6.07318e-4 0.0909999 -0.1034565 0.001330614 0.0909999 -0.1061786 -4.43737e-4 0.0909999 -0.1048461 -6.54857e-4 0.0909999 -0.1055726 3.49756e-5 0.0909999 -0.1042948 -5.85592e-5 0.0909999 -0.1050477 6.01209e-4 0.0909999 -0.1069102 -0.001929402 0.0909999 -0.1075743 -0.001095056 0.0909999 -0.1083307 -0.001252055 0.0909999 -0.1054739 -0.001171946 0.0909999 -0.1068512 -8.2347e-4 0.0909999 -0.1061665 -0.00159955 0.0909999 -0.1084947 -0.002273976 0.0909999 -0.1091023 -0.001290678 0.0909999 -0.1093075 -0.002282798 0.0909999 -0.1076911 -0.002155482 0.0909999 -0.1129898 -7.42952e-4 0.0909999 -0.1119728 -2.86975e-4 0.0909999 -0.1135551 -1.57286e-4 0.0909999 -0.1106153 -0.001012384 0.0909999 -0.1113221 -7.02288e-4 0.0909999 -0.1123517 -0.001245617 0.0909999 -0.1116514 -0.001657664 0.0909999 -0.112552 2.23673e-4 0.0909999 -0.1148913 0.002766191 0.0909999 -0.1147093 0.001972734 0.0909999 -0.1137318 0.00219649 0.0909999 -0.1134421 0.00148034 0.0909999 -0.1242672 0.004258871 0.0909999 -0.1243195 0.003260254 0.0909999 -0.1139656 0.003719031 0.0909999 -0.1139076 0.002948701 0.0909999 -0.1101151 -0.002181351 0.1024999 -0.1093075 -0.002282798 0.1024999 -0.1093075 -0.002282798 0.0909999 -0.1101151 -0.002181351 0.0909999 -0.1109013 -0.001971602 0.1024999 -0.1109013 -0.001971602 0.0909999 -0.1116514 -0.001657664 0.1024999 -0.1123517 -0.001245617 0.1024999 -0.1116514 -0.001657664 0.0909999 -0.1123517 -0.001245617 0.0909999 -0.1129898 -7.42951e-4 0.1024999 -0.1129898 -7.42952e-4 0.0909999 -0.1135551 -1.57285e-4 0.1024999 -0.1140358 4.9932e-4 0.1024999 -0.1135551 -1.57286e-4 0.0909999 -0.1140358 4.99318e-4 0.0909999 -0.114423 0.001214504 0.1024999 -0.114423 0.001214504 0.0909999 -0.1147093 0.001972734 0.1024999 -0.1148913 0.002766191 0.1024999 -0.1147093 0.001972734 0.0909999 -0.1148913 0.002766191 0.0909999 -0.1084947 -0.002273976 0.0909999 -0.1084947 -0.002273976 0.1024999 -0.1076911 -0.002155482 0.1024999 -0.1076911 -0.002155482 0.0909999 -0.1069102 -0.001929402 0.0909999 -0.1069102 -0.001929402 0.1024999 -0.1061665 -0.00159955 0.1024999 -0.1061665 -0.00159955 0.0909999 -0.1054739 -0.001171946 0.1024999 -0.1054739 -0.001171946 0.0909999 -0.1048461 -6.54857e-4 0.0909999 -0.1048461 -6.54856e-4 0.1024999 -0.1042948 -5.85578e-5 0.1024999 -0.1042948 -5.85592e-5 0.0909999 -0.1038287 6.07319e-4 0.1024999 -0.1038287 6.07318e-4 0.0909999 -0.1034565 0.001330614 0.0909999 -0.1034565 0.001330614 0.1024999 -0.1031855 0.002097964 0.1024999 -0.1031855 0.002097964 0.0909999 -0.1030208 0.002895176 0.0909999 -0.1030208 0.002895176 0.1024999 -0.1031855 0.002097964 0.1024999 -0.1042884 0.001940131 0.1024999 -0.1040723 0.002679705 0.1024999 -0.1046162 0.001241326 0.1024999 -0.1038287 6.07319e-4 0.1024999 -0.1050477 6.01211e-4 0.1024999 -0.1076911 -0.002155482 0.1024999 -0.1083307 -0.001252055 0.1024999 -0.1069102 -0.001929402 0.1024999 -0.1075743 -0.001095056 0.1024999 -0.1061665 -0.00159955 0.1024999 -0.1068512 -8.23469e-4 0.1024999 -0.1093075 -0.002282798 0.1024999 -0.1101151 -0.002181351 0.1024999 -0.1091023 -0.001290678 0.1024999 -0.1054739 -0.001171946 0.1024999 -0.1048461 -6.54856e-4 0.1024999 -0.1061786 -4.43736e-4 0.1024999 -0.1055726 3.4977e-5 0.1024999 -0.1042948 -5.85578e-5 0.1024999 -0.1123517 -0.001245617 0.1024999 -0.1113221 -7.02287e-4 0.1024999 -0.1116514 -0.001657664 0.1024999 -0.1034565 0.001330614 0.1024999 -0.1035005 0.002920329 0.1024999 -0.1039724 0.003445744 0.1024999 -0.1030208 0.002895176 0.1024999 -0.1029685 0.003893792 0.1024999 -0.1034482 0.003918945 0.1024999 -0.1030536 0.004731118 0.1024999 -0.1039904 0.004205524 0.1024999 -0.1043683 0.005673229 0.1024999 -0.1035672 0.00632584 0.1024999 -0.1032542 0.005545437 0.1024999 -0.1143801 0.006292402 0.1024999 -0.1130681 0.006565272 0.1024999 -0.1134536 0.005911111 0.1024999 -0.1084542 0.008681178 0.1024999 -0.1081446 0.009650826 0.1024999 -0.1073217 0.009477674 0.1024999 -0.1139652 0.007024526 0.1024999 -0.1125879 0.007153749 0.1024999 -0.109968 0.008605837 0.1024999 -0.1114339 0.009176015 0.1024999 -0.1106456 0.009467363 0.1024999 -0.1128509 0.008279383 0.1024999 -0.1121737 0.008777558 0.1024999 -0.1113895 0.008080482 0.1024999 -0.1106988 0.00839734 0.1024999 -0.109214 0.008701205 0.1024999 -0.1098232 0.00964576 0.1024999 -0.112024 0.007662713 0.1024999 -0.113452 0.007691204 0.1024999 -0.1146886 0.005509376 0.1024999 -0.1137353 0.0052073 0.1024999 -0.1045036 0.007718741 0.1024999 -0.1039864 0.007055103 0.1024999 -0.1051683 0.006960034 0.1024999 -0.1139075 0.00446707 0.1024999 -0.124228 0.005007863 0.1024999 -0.1241756 0.006006479 0.1024999 -0.1047193 0.006347179 0.1024999 -0.114423 0.001214504 0.1024999 -0.1134421 0.00148034 0.1024999 -0.1130457 8.17506e-4 0.1024999 -0.1057049 0.007497727 0.1024999 -0.1051087 0.008303582 0.1024999 -0.1041234 0.004953801 0.1024999 -0.1063166 0.007947862 0.1024999 -0.1057893 0.008797645 0.1024999 -0.1069893 0.008300125 0.1024999 -0.1065315 0.009191334 0.1024999 -0.1077074 0.008546411 0.1024999 -0.1089839 0.009707331 0.1024999 -0.1147093 0.001972734 0.1024999 -0.112552 2.23674e-4 0.1024999 -0.1140358 4.9932e-4 0.1024999 -0.1119728 -2.86974e-4 0.1024999 -0.1135551 -1.57285e-4 0.1024999 -0.1129898 -7.42951e-4 0.1024999 -0.1106153 -0.001012384 0.1024999 -0.1109013 -0.001971602 0.1024999 -0.1098694 -0.001210093 0.1024999 -0.1084947 -0.002273976 0.1024999 -0.1148913 0.002766191 0.1024999 -0.1137318 0.00219649 0.1024999 -0.1139076 0.002948701 0.1024999 -0.1139656 0.003719031 0.1024999 -0.1243195 0.003260254 0.1024999 -0.1242672 0.004258871 0.1024999 -0.1243195 0.003260254 0.1024999 -0.1243195 0.003260254 0.0909999 -0.1242672 0.004258871 0.0909999 -0.1242672 0.004258871 0.1024999 -0.1183958 0.003951191 0.09627383 -0.1139656 0.003719031 0.0909999 -0.1183295 0.003947734 0.09642511 -0.1242672 0.004258871 0.0909999 -0.1196755 0.004018247 0.09583431 -0.1198205 0.004025876 0.09591293 -0.1202726 0.004049539 0.0967499 -0.1242672 0.004258871 0.1024999 -0.1202185 0.004046738 0.09642541 -0.120259 0.004048824 0.09658533 -0.1200622 0.004038512 0.09613591 -0.1201523 0.004043281 0.09627419 -0.1199506 0.004032671 0.09601438 -0.1193568 0.004001557 0.09575343 -0.1195195 0.004010081 0.09578061 -0.1191918 0.003992915 0.09575331 -0.1188731 0.003976225 0.09583401 -0.1190292 0.003984391 0.09578049 -0.1185978 0.003961801 0.09601402 -0.118728 0.003968596 0.09591263 -0.1184861 0.00395596 0.09613561 -0.1182754 0.003944933 0.0967499 -0.118289 0.003945589 0.09658533 -0.1139656 0.003719031 0.1024999 -0.1188728 0.003976225 0.09766572 -0.1187278 0.003968596 0.0975871 -0.1183295 0.003947734 0.09707462 -0.118289 0.003945589 0.09691452 -0.1184859 0.00395596 0.09736412 -0.1183957 0.003951191 0.0972259 -0.1185976 0.003961801 0.0974856 -0.1191915 0.003992915 0.09774649 -0.1190289 0.003984391 0.09771931 -0.1193565 0.004001557 0.09774649 -0.1196752 0.004018247 0.09766572 -0.1195192 0.004010081 0.09771931 -0.1199504 0.004032671 0.0974856 -0.1198202 0.004025876 0.0975871 -0.1201522 0.004043281 0.0972259 -0.1200621 0.004038512 0.09736412 -0.120259 0.004048824 0.09691452 -0.1202185 0.004046738 0.09707462 -0.120325 0.003050923 0.0967499 -0.1243195 0.003260254 0.1024999 -0.1203113 0.003050208 0.09691452 -0.1197275 0.00301963 0.09766572 -0.1198725 0.0030272 0.0975871 -0.1243195 0.003260254 0.0909999 -0.1183818 0.002949118 0.09707462 -0.1148913 0.002766191 0.1024999 -0.1183413 0.002946972 0.09691452 -0.1202045 0.003044605 0.0972259 -0.1202709 0.003048121 0.09707462 -0.1200027 0.003034055 0.0974856 -0.1201144 0.003039896 0.09736412 -0.1194089 0.003002941 0.09774649 -0.1195715 0.003011465 0.09771931 -0.1192439 0.002994298 0.09774649 -0.1189252 0.002977609 0.09766572 -0.1190812 0.002985775 0.09771931 -0.11865 0.002963185 0.0974856 -0.1187801 0.00296998 0.0975871 -0.118448 0.002952575 0.0972259 -0.1185383 0.002957284 0.09736412 -0.1183277 0.002946257 0.0967499 -0.1148913 0.002766191 0.0909999 -0.1183817 0.002949118 0.09642541 -0.1183413 0.002946972 0.09658533 -0.1187798 0.00296998 0.09591293 -0.1189249 0.00297755 0.09583431 -0.1185382 0.002957284 0.09613591 -0.118448 0.002952575 0.09627419 -0.1186498 0.002963125 0.09601438 -0.1192436 0.002994239 0.09575343 -0.1190809 0.002985715 0.09578061 -0.1194084 0.003002882 0.09575331 -0.1197272 0.00301963 0.09583401 -0.1195712 0.003011465 0.09578049 -0.1200025 0.003034055 0.09601402 -0.1198723 0.0030272 0.09591263 -0.1202046 0.003044605 0.09627383 -0.1201143 0.003039896 0.09613561 -0.1203113 0.003050208 0.09658533 -0.1202709 0.003048121 0.09642511 -0.118289 0.003945589 0.09691452 -0.1183277 0.002946257 0.0967499 -0.1182754 0.003944933 0.0967499 -0.1184859 0.00395596 0.09736412 -0.118448 0.002952575 0.0972259 -0.1183957 0.003951191 0.0972259 -0.1183295 0.003947734 0.09707462 -0.1183818 0.002949118 0.09707462 -0.1183413 0.002946972 0.09691452 -0.1187801 0.00296998 0.0975871 -0.1187278 0.003968596 0.0975871 -0.1188728 0.003976225 0.09766572 -0.1185383 0.002957284 0.09736412 -0.1185976 0.003961801 0.0974856 -0.11865 0.002963185 0.0974856 -0.1191915 0.003992915 0.09774649 -0.1193565 0.004001557 0.09774649 -0.1192439 0.002994298 0.09774649 -0.1190289 0.003984391 0.09771931 -0.1190812 0.002985775 0.09771931 -0.1189252 0.002977609 0.09766572 -0.1198202 0.004025876 0.0975871 -0.1197275 0.00301963 0.09766572 -0.1196752 0.004018247 0.09766572 -0.1195715 0.003011465 0.09771931 -0.1194089 0.003002941 0.09774649 -0.1195192 0.004010081 0.09771931 -0.1201144 0.003039896 0.09736412 -0.1200621 0.004038512 0.09736412 -0.1201522 0.004043281 0.0972259 -0.1198725 0.0030272 0.0975871 -0.1199504 0.004032671 0.0974856 -0.1200027 0.003034055 0.0974856 -0.120259 0.004048824 0.09691452 -0.1202726 0.004049539 0.0967499 -0.1203113 0.003050208 0.09691452 -0.1202185 0.004046738 0.09707462 -0.1202709 0.003048121 0.09707462 -0.1202045 0.003044605 0.0972259 -0.1201523 0.004043281 0.09627419 -0.1202709 0.003048121 0.09642511 -0.1202185 0.004046738 0.09642541 -0.1203113 0.003050208 0.09658533 -0.120325 0.003050923 0.0967499 -0.120259 0.004048824 0.09658533 -0.1200025 0.003034055 0.09601402 -0.1199506 0.004032671 0.09601438 -0.1198205 0.004025876 0.09591293 -0.1202046 0.003044605 0.09627383 -0.1200622 0.004038512 0.09613591 -0.1201143 0.003039896 0.09613561 -0.1195195 0.004010081 0.09578061 -0.1193568 0.004001557 0.09575343 -0.1195712 0.003011465 0.09578049 -0.1196755 0.004018247 0.09583431 -0.1197272 0.00301963 0.09583401 -0.1198723 0.0030272 0.09591263 -0.1191918 0.003992915 0.09575331 -0.1190292 0.003984391 0.09578049 -0.1192436 0.002994239 0.09575343 -0.1194084 0.003002882 0.09575331 -0.1190809 0.002985715 0.09578061 -0.1188731 0.003976225 0.09583401 -0.118728 0.003968596 0.09591263 -0.1189249 0.00297755 0.09583431 -0.1185978 0.003961801 0.09601402 -0.1187798 0.00296998 0.09591293 -0.1186498 0.002963125 0.09601438 -0.1184861 0.00395596 0.09613561 -0.1183958 0.003951191 0.09627383 -0.1185382 0.002957284 0.09613591 -0.1183295 0.003947734 0.09642511 -0.118448 0.002952575 0.09627419 -0.1183817 0.002949118 0.09642541 -0.118289 0.003945589 0.09658533 -0.1183413 0.002946972 0.09658533 -0.1175536 0.005659461 0.09436792 -0.1203232 0.007807374 0.09414625 -0.1204279 0.005810081 0.09414625 -0.1174489 0.007656753 0.09436792 -0.1163082 0.005594193 0.09697139 -0.1174489 0.007656753 0.09436792 -0.1175536 0.005659461 0.09436792 -0.1162035 0.007591485 0.09697139 -0.117937 0.005679547 0.09935313 -0.1162035 0.007591485 0.09697139 -0.1163082 0.005594193 0.09697139 -0.1178323 0.007676839 0.09935313 -0.1208113 0.005830168 0.09913146 -0.1178323 0.007676839 0.09935313 -0.117937 0.005679547 0.09935313 -0.1207066 0.00782746 0.09913146 -0.1220567 0.005895435 0.09652805 -0.1207066 0.00782746 0.09913146 -0.1208113 0.005830168 0.09913146 -0.1219521 0.007892727 0.09652805 -0.1204279 0.005810081 0.09414625 -0.1219521 0.007892727 0.09652805 -0.1220567 0.005895435 0.09652805 -0.1203232 0.007807374 0.09414625 -0.1181844 0.005692541 0.09671485 -0.1181923 0.005692958 0.09687983 -0.1163082 0.005594193 0.09697139 -0.1201378 0.005794882 0.09645849 -0.1220567 0.005895435 0.09652805 -0.1201726 0.00579673 0.0966199 -0.117937 0.005679547 0.09935313 -0.1186074 0.005714714 0.09756726 -0.1187496 0.005722165 0.09765082 -0.1197577 0.005774974 0.0959323 -0.1196155 0.005767524 0.09584861 -0.1204279 0.005810081 0.09414625 -0.1208113 0.005830168 0.09913146 -0.1192298 0.005747318 0.09774857 -0.1188136 0.005725502 0.09582042 -0.1186659 0.005717754 0.09589385 -0.1175536 0.005659461 0.09436792 -0.1189035 0.005730211 0.09770989 -0.1190649 0.005738675 0.09774273 -0.1183735 0.005702435 0.09733599 -0.1184809 0.005708038 0.09746134 -0.1182882 0.005697965 0.09719467 -0.1182272 0.005694746 0.09704124 -0.1182498 0.005695939 0.09639221 -0.1182038 0.005693554 0.09655082 -0.1183213 0.005699694 0.09624332 -0.1185322 0.00571078 0.09599071 -0.1184163 0.0057047 0.09610825 -0.119135 0.005742371 0.0957508 -0.1189715 0.005733788 0.09577226 -0.1194615 0.005759477 0.09578955 -0.1192998 0.005750954 0.09575664 -0.1199916 0.005787253 0.09616363 -0.1198842 0.00578159 0.09603828 -0.1200768 0.005791723 0.09630501 -0.1201804 0.005797147 0.09678488 -0.1201149 0.00579369 0.09710747 -0.1201611 0.005796134 0.09694892 -0.1200434 0.005789935 0.0972563 -0.1198325 0.005778908 0.09750878 -0.1199484 0.005784988 0.0973913 -0.1195511 0.005764126 0.09767901 -0.1196989 0.005771875 0.09760558 -0.1193934 0.005755901 0.09772711 -0.1185023 0.007711946 0.09756702 -0.1178323 0.007676839 0.09935313 -0.1186445 0.007719397 0.0976507 -0.1191251 0.00774455 0.09774857 -0.1207066 0.00782746 0.09913146 -0.1180875 0.007690191 0.09687918 -0.1180798 0.007689774 0.09671419 -0.1162035 0.007591485 0.09697139 -0.1219521 0.007892727 0.09652805 -0.1200331 0.007792174 0.09645849 -0.120068 0.007793962 0.0966199 -0.1187092 0.007722795 0.0958203 -0.1174489 0.007656753 0.09436792 -0.1185615 0.007715046 0.09589374 -0.1203232 0.007807374 0.09414625 -0.1195108 0.007764756 0.09584861 -0.1196531 0.007772207 0.0959323 -0.1187986 0.007727444 0.09770983 -0.1189603 0.007735908 0.09774273 -0.1183758 0.00770533 0.09746098 -0.1182685 0.007699668 0.09733557 -0.1181832 0.007695198 0.09719413 -0.1181223 0.007692039 0.09704065 -0.1180992 0.007690787 0.09655016 -0.1181454 0.007693231 0.09639161 -0.1182169 0.007696986 0.09624284 -0.1184279 0.007708013 0.09599047 -0.118312 0.007701933 0.0961079 -0.1188668 0.00773102 0.09577226 -0.1190304 0.007739603 0.0957508 -0.1191952 0.007748246 0.09575664 -0.1193568 0.00775671 0.09578955 -0.1197795 0.007778882 0.09603828 -0.1198869 0.007784485 0.09616363 -0.1199722 0.007788956 0.09630501 -0.1200758 0.00779438 0.09678488 -0.1200564 0.007793366 0.09694892 -0.1200103 0.007790923 0.09710747 -0.1199387 0.007787227 0.0972563 -0.1197279 0.007776141 0.09750878 -0.1198437 0.00778222 0.0973913 -0.1194465 0.007761418 0.09767901 -0.1195942 0.007769167 0.09760558 -0.1192887 0.007753133 0.09772711 -0.1192998 0.005750954 0.09575664 -0.1190304 0.007739603 0.0957508 -0.119135 0.005742371 0.0957508 -0.1197577 0.005774974 0.0959323 -0.1195108 0.007764756 0.09584861 -0.1196155 0.005767524 0.09584861 -0.1194615 0.005759477 0.09578955 -0.1193568 0.00775671 0.09578955 -0.1191952 0.007748246 0.09575664 -0.1198869 0.007784485 0.09616363 -0.1199916 0.005787253 0.09616363 -0.1200768 0.005791723 0.09630501 -0.1196531 0.007772207 0.0959323 -0.1198842 0.00578159 0.09603828 -0.1197795 0.007778882 0.09603828 -0.1201726 0.00579673 0.0966199 -0.1201804 0.005797147 0.09678488 -0.120068 0.007793962 0.0966199 -0.1201378 0.005794882 0.09645849 -0.1200331 0.007792174 0.09645849 -0.1199722 0.007788956 0.09630501 -0.1200434 0.005789935 0.0972563 -0.1200103 0.007790923 0.09710747 -0.1201149 0.00579369 0.09710747 -0.1200564 0.007793366 0.09694892 -0.1200758 0.00779438 0.09678488 -0.1201611 0.005796134 0.09694892 -0.1197279 0.007776141 0.09750878 -0.1198325 0.005778908 0.09750878 -0.1196989 0.005771875 0.09760558 -0.1199387 0.007787227 0.0972563 -0.1199484 0.005784988 0.0973913 -0.1198437 0.00778222 0.0973913 -0.1193934 0.005755901 0.09772711 -0.1192298 0.005747318 0.09774857 -0.1192887 0.007753133 0.09772711 -0.1195511 0.005764126 0.09767901 -0.1194465 0.007761418 0.09767901 -0.1195942 0.007769167 0.09760558 -0.1187496 0.005722165 0.09765082 -0.1187986 0.007727444 0.09770983 -0.1189035 0.005730211 0.09770989 -0.1189603 0.007735908 0.09774273 -0.1191251 0.00774455 0.09774857 -0.1190649 0.005738675 0.09774273 -0.1183758 0.00770533 0.09746098 -0.1184809 0.005708038 0.09746134 -0.1183735 0.005702435 0.09733599 -0.1186445 0.007719397 0.0976507 -0.1186074 0.005714714 0.09756726 -0.1185023 0.007711946 0.09756702 -0.1182272 0.005694746 0.09704124 -0.1181923 0.005692958 0.09687983 -0.1181223 0.007692039 0.09704065 -0.1182882 0.005697965 0.09719467 -0.1181832 0.007695198 0.09719413 -0.1182685 0.007699668 0.09733557 -0.1181844 0.005692541 0.09671485 -0.1182038 0.005693554 0.09655082 -0.1180798 0.007689774 0.09671419 -0.1180875 0.007690191 0.09687918 -0.1180992 0.007690787 0.09655016 -0.1182498 0.005695939 0.09639221 -0.1183213 0.005699694 0.09624332 -0.1181454 0.007693231 0.09639161 -0.1184163 0.0057047 0.09610825 -0.1182169 0.007696986 0.09624284 -0.118312 0.007701933 0.0961079 -0.1185322 0.00571078 0.09599071 -0.1186659 0.005717754 0.09589385 -0.1184279 0.007708013 0.09599047 -0.1188136 0.005725502 0.09582042 -0.1185615 0.007715046 0.09589374 -0.1187092 0.007722795 0.0958203 -0.1189715 0.005733788 0.09577226 -0.1188668 0.00773102 0.09577226 -0.1086353 -2.78942e-4 -0.005999982 -0.1092972 -2.78732e-4 0.403 -0.1092959 -2.78942e-4 -0.005999982 -0.1049656 0.003707349 0.403 -0.1049656 0.003707349 -0.005999982 -0.1050201 0.004365742 -0.005999982 -0.1099475 -1.70202e-4 -0.005999982 -0.1099488 -1.69772e-4 0.403 -0.1105735 4.4948e-5 0.403 -0.1105723 4.43079e-5 -0.005999982 -0.1111544 3.59528e-4 0.403 -0.1111534 3.58728e-4 -0.005999982 -0.1116747 7.64498e-4 -0.005999982 -0.1116755 7.65388e-4 0.403 -0.1121227 0.001251399 0.403 -0.1121221 0.001250505 -0.005999982 -0.1124838 0.001804351 0.403 -0.1124835 0.001803576 -0.005999982 -0.1127489 0.002408564 -0.005999982 -0.112749 0.00240916 0.403 -0.112911 0.003048837 0.403 -0.1129111 0.003049015 -0.005999982 -0.1129656 0.003707349 0.403 -0.1129656 0.003707349 -0.005999982 -0.1086366 -2.78962e-4 0.403 -0.1079837 -1.70202e-4 -0.005999982 -0.1079849 -1.70442e-4 0.403 -0.1073588 4.43079e-5 -0.005999982 -0.1073598 4.38979e-5 0.403 -0.1067786 3.58218e-4 0.403 -0.1067778 3.58728e-4 -0.005999982 -0.1062564 7.64498e-4 -0.005999982 -0.1062571 7.63938e-4 0.403 -0.105809 0.001250505 -0.005999982 -0.1058095 0.001249969 0.403 -0.105448 0.0018031 0.403 -0.1054477 0.001803576 -0.005999982 -0.1051823 0.002408564 -0.005999982 -0.1051824 0.002408206 0.403 -0.1050201 0.003049015 -0.005999982 -0.1050202 0.003048837 0.403 -0.1051823 0.005006194 0.403 -0.1050201 0.004365742 0.403 -0.1051823 0.005006194 -0.005999982 -0.1062564 0.006650269 0.403 -0.105809 0.006164193 0.403 -0.1062564 0.006650269 -0.005999982 -0.1054477 0.005611181 0.403 -0.1054477 0.005611181 -0.005999982 -0.105809 0.006164193 -0.005999982 -0.1073588 0.007370471 0.403 -0.1079837 0.007584989 -0.005999982 -0.1079837 0.007584989 0.403 -0.1067778 0.007056057 -0.005999982 -0.1073588 0.007370471 -0.005999982 -0.1067778 0.007056057 0.403 -0.1099475 0.007584989 -0.005999982 -0.1099475 0.007584989 0.403 -0.1092959 0.007693707 0.403 -0.1092959 0.007693707 -0.005999982 -0.1086353 0.007693707 0.403 -0.1086353 0.007693707 -0.005999982 -0.1116747 0.006650269 0.403 -0.1111534 0.007056057 0.403 -0.1116747 0.006650269 -0.005999982 -0.1105723 0.007370471 0.403 -0.1105723 0.007370471 -0.005999982 -0.1111534 0.007056057 -0.005999982 -0.1124835 0.005611181 -0.005999982 -0.1121221 0.006164193 0.403 -0.1121221 0.006164193 -0.005999982 -0.1127489 0.005006194 -0.005999982 -0.1124835 0.005611181 0.403 -0.1127489 0.005006194 0.403 -0.1129111 0.004365742 -0.005999982 -0.1129111 0.004365742 0.403 -0.1097011 7.99018e-4 0.403 -0.1101699 9.59778e-4 0.403 -0.1099488 -1.69772e-4 0.403 -0.1121221 0.006164193 0.403 -0.1124835 0.005611181 0.403 -0.111604 0.005135238 0.403 -0.1105735 4.4948e-5 0.403 -0.1106058 0.00119549 0.403 -0.1092972 -2.78732e-4 0.403 -0.1092123 7.17628e-4 0.403 -0.1111544 3.59528e-4 0.403 -0.1109969 0.001499772 0.403 -0.1087169 7.17798e-4 0.403 -0.1086366 -2.78962e-4 0.403 -0.1082282 7.99518e-4 0.403 -0.1079849 -1.70442e-4 0.403 -0.1077596 9.60558e-4 0.403 -0.1073598 4.38979e-5 0.403 -0.1121227 0.001251399 0.403 -0.1116755 7.65388e-4 0.403 -0.1067786 3.58218e-4 0.403 -0.107324 0.001196444 0.403 -0.1124838 0.001804351 0.403 -0.1113327 0.001864314 0.403 -0.1119247 0.003213465 0.403 -0.1129656 0.003707349 0.403 -0.112911 0.003048837 0.403 -0.1062571 7.63938e-4 0.403 -0.1069331 0.001500844 0.403 -0.1127489 0.005006194 0.403 -0.111803 0.004681468 0.403 -0.1067778 0.007056057 0.403 -0.1073247 0.00621885 0.403 -0.1069337 0.005914509 0.403 -0.1111534 0.007056057 0.403 -0.1106064 0.00621885 0.403 -0.1101707 0.006454706 0.403 -0.1109974 0.005914509 0.403 -0.111333 0.005550026 0.403 -0.1092133 0.006697118 0.403 -0.1087179 0.006697118 0.403 -0.1092959 0.007693707 0.403 -0.1065981 0.005550026 0.403 -0.1054477 0.005611181 0.403 -0.105809 0.006164193 0.403 -0.1082291 0.006615579 0.403 -0.1086353 0.007693707 0.403 -0.1077605 0.006454706 0.403 -0.1079837 0.007584989 0.403 -0.1062564 0.006650269 0.403 -0.1073588 0.007370471 0.403 -0.1097021 0.006615579 0.403 -0.1105723 0.007370471 0.403 -0.1099475 0.007584989 0.403 -0.1050201 0.004365742 0.403 -0.1060065 0.004201173 0.403 -0.1049656 0.003707349 0.403 -0.1063272 0.005135238 0.403 -0.1061281 0.004681468 0.403 -0.1051823 0.005006194 0.403 -0.1051824 0.002408206 0.403 -0.1050202 0.003048837 0.403 -0.1060065 0.003213465 0.403 -0.1116747 0.006650269 0.403 -0.1129111 0.004365742 0.403 -0.1119247 0.004201173 0.403 -0.106128 0.002733707 0.403 -0.1119656 0.003707349 0.403 -0.1058095 0.001249969 0.403 -0.1065977 0.001865386 0.403 -0.1063269 0.002280116 0.403 -0.105448 0.0018031 0.403 -0.1116038 0.002279162 0.403 -0.112749 0.00240916 0.403 -0.1118029 0.002732992 0.403 -0.1059656 0.003707349 0.403 -0.1092959 -2.78942e-4 -0.005999982 -0.109703 7.99518e-4 -0.005999982 -0.1092143 7.17798e-4 -0.005999982 -0.111604 0.005135238 -0.005999982 -0.1124835 0.005611181 -0.005999982 -0.1121221 0.006164193 -0.005999982 -0.1087188 7.17628e-4 -0.005999982 -0.1086353 -2.78942e-4 -0.005999982 -0.1099475 -1.70202e-4 -0.005999982 -0.1101716 9.60558e-4 -0.005999982 -0.10823 7.99018e-4 -0.005999982 -0.1079837 -1.70202e-4 -0.005999982 -0.1105723 4.43079e-5 -0.005999982 -0.1106072 0.001196444 -0.005999982 -0.1116747 7.64498e-4 -0.005999982 -0.1111534 3.58728e-4 -0.005999982 -0.110998 0.001500844 -0.005999982 -0.1121221 0.001250505 -0.005999982 -0.1073588 4.43079e-5 -0.005999982 -0.1077613 9.59778e-4 -0.005999982 -0.1113334 0.001865386 -0.005999982 -0.1124835 0.001803576 -0.005999982 -0.1073254 0.00119549 -0.005999982 -0.1067778 3.58728e-4 -0.005999982 -0.1065985 0.001864314 -0.005999982 -0.105809 0.001250505 -0.005999982 -0.1069343 0.001499772 -0.005999982 -0.1062564 7.64498e-4 -0.005999982 -0.1051823 0.002408564 -0.005999982 -0.1061282 0.002732992 -0.005999982 -0.1060065 0.003213465 -0.005999982 -0.1129656 0.003707349 -0.005999982 -0.1119247 0.003213465 -0.005999982 -0.1129111 0.003049015 -0.005999982 -0.1060065 0.004201173 -0.005999982 -0.1050201 0.004365742 -0.005999982 -0.1049656 0.003707349 -0.005999982 -0.111803 0.004681468 -0.005999982 -0.1127489 0.005006194 -0.005999982 -0.1073247 0.00621885 -0.005999982 -0.1062564 0.006650269 -0.005999982 -0.1069337 0.005914509 -0.005999982 -0.1106064 0.00621885 -0.005999982 -0.1111534 0.007056057 -0.005999982 -0.1101707 0.006454706 -0.005999982 -0.1082291 0.006615579 -0.005999982 -0.1087179 0.006697118 -0.005999982 -0.1086353 0.007693707 -0.005999982 -0.1092133 0.006697118 -0.005999982 -0.1092959 0.007693707 -0.005999982 -0.1073588 0.007370471 -0.005999982 -0.1077605 0.006454706 -0.005999982 -0.1079837 0.007584989 -0.005999982 -0.1105723 0.007370471 -0.005999982 -0.1097021 0.006615579 -0.005999982 -0.1099475 0.007584989 -0.005999982 -0.1063272 0.005135238 -0.005999982 -0.1051823 0.005006194 -0.005999982 -0.1061281 0.004681468 -0.005999982 -0.1065981 0.005550026 -0.005999982 -0.105809 0.006164193 -0.005999982 -0.1054477 0.005611181 -0.005999982 -0.1059656 0.003707349 -0.005999982 -0.1050201 0.003049015 -0.005999982 -0.1109974 0.005914509 -0.005999982 -0.1116747 0.006650269 -0.005999982 -0.1129111 0.004365742 -0.005999982 -0.1119247 0.004201173 -0.005999982 -0.1119656 0.003707349 -0.005999982 -0.1063274 0.002279162 -0.005999982 -0.1054477 0.001803576 -0.005999982 -0.1067778 0.007056057 -0.005999982 -0.1127489 0.002408564 -0.005999982 -0.1116042 0.002280116 -0.005999982 -0.1118031 0.002733707 -0.005999982 -0.111333 0.005550026 -0.005999982 -0.1119247 0.004201173 0.403 -0.1119656 0.003707349 0.403 -0.1119656 0.003707349 -0.005999982 -0.111333 0.005550026 0.403 -0.111604 0.005135238 0.403 -0.111604 0.005135238 -0.005999982 -0.111803 0.004681468 0.403 -0.1119247 0.004201173 -0.005999982 -0.111803 0.004681468 -0.005999982 -0.1106064 0.00621885 -0.005999982 -0.1101707 0.006454706 0.403 -0.1106064 0.00621885 0.403 -0.111333 0.005550026 -0.005999982 -0.1109974 0.005914509 -0.005999982 -0.1109974 0.005914509 0.403 -0.1092133 0.006697118 0.403 -0.1092133 0.006697118 -0.005999982 -0.1087179 0.006697118 0.403 -0.1097021 0.006615579 0.403 -0.1101707 0.006454706 -0.005999982 -0.1097021 0.006615579 -0.005999982 -0.1073247 0.00621885 0.403 -0.1077605 0.006454706 0.403 -0.1077605 0.006454706 -0.005999982 -0.1082291 0.006615579 -0.005999982 -0.1082291 0.006615579 0.403 -0.1087179 0.006697118 -0.005999982 -0.1065981 0.005550026 -0.005999982 -0.1063272 0.005135238 0.403 -0.1065981 0.005550026 0.403 -0.1073247 0.00621885 -0.005999982 -0.1069337 0.005914509 -0.005999982 -0.1069337 0.005914509 0.403 -0.1060065 0.004201173 0.403 -0.1060065 0.004201173 -0.005999982 -0.1059656 0.003707349 0.403 -0.1061281 0.004681468 0.403 -0.1063272 0.005135238 -0.005999982 -0.1061281 0.004681468 -0.005999982 -0.1063269 0.002280116 0.403 -0.106128 0.002733707 0.403 -0.1061282 0.002732992 -0.005999982 -0.1060065 0.003213465 -0.005999982 -0.1060065 0.003213465 0.403 -0.1059656 0.003707349 -0.005999982 -0.1069343 0.001499772 -0.005999982 -0.107324 0.001196444 0.403 -0.1069331 0.001500844 0.403 -0.1063274 0.002279162 -0.005999982 -0.1065985 0.001864314 -0.005999982 -0.1065977 0.001865386 0.403 -0.1082282 7.99518e-4 0.403 -0.10823 7.99018e-4 -0.005999982 -0.1087169 7.17798e-4 0.403 -0.1077596 9.60558e-4 0.403 -0.1073254 0.00119549 -0.005999982 -0.1077613 9.59778e-4 -0.005999982 -0.1092123 7.17628e-4 0.403 -0.1092143 7.17798e-4 -0.005999982 -0.1097011 7.99018e-4 0.403 -0.1087188 7.17628e-4 -0.005999982 -0.109703 7.99518e-4 -0.005999982 -0.1101699 9.59778e-4 0.403 -0.1106058 0.00119549 0.403 -0.1101716 9.60558e-4 -0.005999982 -0.1106072 0.001196444 -0.005999982 -0.1109969 0.001499772 0.403 -0.110998 0.001500844 -0.005999982 -0.1113327 0.001864314 0.403 -0.1116038 0.002279162 0.403 -0.1113334 0.001865386 -0.005999982 -0.1116042 0.002280116 -0.005999982 -0.1118029 0.002732992 0.403 -0.1118031 0.002733707 -0.005999982 -0.1119247 0.003213465 0.403 -0.1119247 0.003213465 -0.005999982 -0.1128394 0.002077281 0.145 -0.1128394 0.002077341 0.4030001 -0.1129677 0.002725362 0.4030001 -0.1129878 0.003385663 0.4030001 -0.1129878 0.003385663 0.145 -0.1129678 0.002725303 0.145 -0.1122741 8.88089e-4 0.4030001 -0.1118527 3.79264e-4 0.145 -0.1118527 3.79287e-4 0.4030001 -0.1122742 8.88067e-4 0.145 -0.112606 0.00145924 0.4030001 -0.1126061 0.00145924 0.145 -0.1101768 -6.44542e-4 0.145 -0.1101768 -6.4452e-4 0.4030001 -0.1107896 -3.97604e-4 0.4030001 -0.1107896 -3.97626e-4 0.145 -0.1113533 -5.32032e-5 0.4030001 -0.1113533 -5.32255e-5 0.145 -0.1082156 -7.47287e-4 0.4030001 -0.1088721 -8.21776e-4 0.4030001 -0.1082157 -7.4731e-4 0.145 -0.1095318 -7.87207e-4 0.4030001 -0.1095318 -7.87229e-4 0.145 -0.1088721 -8.21799e-4 0.145 -0.1069837 -2.82183e-4 0.4030001 -0.1064419 9.57246e-5 0.145 -0.1064419 9.57469e-5 0.4030001 -0.1075804 -5.65797e-4 0.145 -0.1069838 -2.82205e-4 0.145 -0.1075804 -5.65775e-4 0.4030001 -0.1059696 5.57713e-4 0.4030001 -0.1059696 5.5769e-4 0.145 -0.1055799 0.001091063 0.145 -0.1052832 0.001681327 0.145 -0.1055799 0.001091063 0.4030001 -0.1050878 0.002312362 0.145 -0.1052832 0.001681327 0.4030001 -0.1050878 0.002312421 0.4030001 -0.1049988 0.002967 0.145 -0.1049988 0.002967059 0.4030001 -0.1082157 -7.4731e-4 0.145 -0.1081358 -0.001749396 0.145 -0.1074118 -0.001566767 0.145 -0.1088721 -8.21799e-4 0.145 -0.1067234 -0.001278638 0.145 -0.1060842 -8.90208e-4 0.145 -0.1075804 -5.65797e-4 0.145 -0.1055103 -4.10809e-4 0.145 -0.1069838 -2.82205e-4 0.145 -0.1064419 9.57246e-5 0.145 -0.1050143 1.48718e-4 0.145 -0.1110605 -0.001376271 0.145 -0.1103584 -0.001633644 0.145 -0.1101768 -6.44542e-4 0.145 -0.1059696 5.5769e-4 0.145 -0.1046075 7.75725e-4 0.145 -0.1042987 0.001456022 0.145 -0.1055799 0.001091063 0.145 -0.1040951 0.002172827 0.145 -0.1052832 0.001681327 0.145 -0.1050878 0.002312362 0.145 -0.1040002 0.002914667 0.145 -0.1049988 0.002967 0.145 -0.1126061 0.00145924 0.145 -0.1138415 0.001953482 0.145 -0.1136049 0.001244246 0.145 -0.1128394 0.002077281 0.145 -0.1139696 0.002690255 0.145 -0.1132652 5.78426e-4 0.145 -0.1118527 3.79264e-4 0.145 -0.1122742 8.88067e-4 0.145 -0.1129678 0.002725303 0.145 -0.1123102 -5.64878e-4 0.145 -0.1113533 -5.32255e-5 0.145 -0.1128304 -2.91255e-5 0.145 -0.1107896 -3.97626e-4 0.145 -0.1117165 -0.001016974 0.145 -0.1096258 -0.00178337 0.145 -0.1095318 -7.87229e-4 0.145 -0.1088795 -0.001822173 0.145 -0.1139865 0.003437995 0.145 -0.1129878 0.003385663 0.145 -0.09201174 0.002286434 0.123 -0.09201174 0.002286434 0.126 -0.09900212 0.002652764 0.126 -0.09900212 0.002652764 0.3 -0.1014987 0.002783596 0.2920001 -0.09900212 0.002652764 0.2920001 -0.09900212 0.002652764 0.287 -0.1014987 0.002783596 0.287 -0.1040002 0.002914667 0.123 -0.1029967 0.002862095 0.3 -0.1049988 0.002967 0.145 -0.1040002 0.002914667 0.145 -0.09900212 0.002652764 0.4030001 -0.1029967 0.002862095 0.3020001 -0.09900212 0.002652764 0.3020001 -0.1049988 0.002967059 0.4030001 -0.1040829 0.002234339 0.123 -0.09201174 0.002286434 0.123 -0.1040002 0.002914667 0.123 -0.1042578 0.001571714 0.123 -0.09211641 2.89216e-4 0.123 -0.1045217 9.39288e-4 0.123 -0.1045217 9.39285e-4 0.09100002 -0.09211641 2.89213e-4 0.09100002 -0.09211641 2.89216e-4 0.123 -0.1045217 9.39288e-4 0.123 -0.09211641 2.89213e-4 0.09100002 -0.1042578 0.001571714 0.09100002 -0.1040829 0.002234339 0.09100002 -0.09201174 0.002286434 0.09100002 -0.1045217 9.39285e-4 0.09100002 -0.1040002 0.002914667 0.09100002 -0.09900212 0.002652764 0.08700001 -0.1040002 0.002914667 0 -0.09900218 0.002652764 0 -0.09201174 0.002286434 0.08700001 -0.09201174 0.002286434 0.09100002 -0.1040002 0.002914667 0.09100002 -0.1249714 0.004013597 0.103 -0.1269638 0.004118025 0.11 -0.1269638 0.004118025 0.08700001 -0.1189748 0.003699362 0.11 -0.1139865 0.003437995 0.145 -0.1189747 0.003699421 0.4030001 -0.1249714 0.004013597 0.09100002 -0.1189748 0.003699362 0.08700001 -0.1139865 0.003437995 0.09100002 -0.1129878 0.003385663 0.145 -0.1129878 0.003385663 0.4030001 -0.1139865 0.003437995 0.103 -0.1189748 0.003699362 0 -0.1139865 0.003437995 0 -0.1029967 0.002862095 0.3020001 -0.09951549 -0.007144212 0.3020001 -0.09900212 0.002652764 0.3020001 -0.1035128 -0.006987452 0.3020001 -0.09948849 -0.006629168 0.327249 -0.09946787 -0.006234765 0.352498 -0.09900212 0.002652764 0.3020001 -0.09951549 -0.007144212 0.3020001 -0.09900212 0.002652764 0.4030001 -0.0994535 -0.005960881 0.377749 -0.09944546 -0.005807518 0.4030001 -0.1129677 0.002725362 0.4030001 -0.1128394 0.002077341 0.4030001 -0.1189747 0.003699421 0.4030001 -0.1194018 -0.004451334 0.4030001 -0.1107896 -3.97604e-4 0.4030001 -0.1127568 -0.005003511 0.4030001 -0.1129878 0.003385663 0.4030001 -0.1095318 -7.87207e-4 0.4030001 -0.1088721 -8.21776e-4 0.4030001 -0.09944546 -0.005807518 0.4030001 -0.1064419 9.57469e-5 0.4030001 -0.1059696 5.57713e-4 0.4030001 -0.1075804 -5.65775e-4 0.4030001 -0.1069837 -2.82183e-4 0.4030001 -0.112606 0.00145924 0.4030001 -0.1122741 8.88089e-4 0.4030001 -0.1118527 3.79287e-4 0.4030001 -0.1113533 -5.32032e-5 0.4030001 -0.1101768 -6.4452e-4 0.4030001 -0.1061047 -0.005455553 0.4030001 -0.1082156 -7.47287e-4 0.4030001 -0.1055799 0.001091063 0.4030001 -0.1052832 0.001681327 0.4030001 -0.09900212 0.002652764 0.4030001 -0.1050878 0.002312421 0.4030001 -0.1049988 0.002967059 0.4030001 -0.1189748 0.003699362 0.11 -0.1195045 -0.006410717 0.2355765 -0.1194896 -0.006125152 0.11 -0.119492 -0.006171584 0.2774354 -0.1189747 0.003699421 0.4030001 -0.1194018 -0.004451334 0.4030001 -0.1189748 0.003699362 0.11 -0.127478 -0.005693733 0.11 -0.1269638 0.004118025 0.11 -0.1194896 -0.006125152 0.11 -0.1269638 0.004118025 0.11 -0.1274784 -0.005702912 0.08700001 -0.1269638 0.004118025 0.08700001 -0.127478 -0.005693733 0.11 -0.1269638 0.004118025 0.08700001 -0.1194901 -0.006135404 0.08700001 -0.1189748 0.003699362 0.08700001 -0.1274784 -0.005702912 0.08700001 -0.1189748 0.003699362 0.08700001 -0.119493 -0.006190001 0.0435 -0.1189748 0.003699362 0 -0.1194901 -0.006135404 0.08700001 -0.1194971 -0.006269097 0 -0.1189748 0.003699362 0 -0.1139696 0.002690255 0 -0.1139865 0.003437995 0 -0.109629 -0.001782894 0 -0.1061757 -0.006851673 0 -0.1088827 -0.001822292 0 -0.1136061 0.001247227 0 -0.1138421 0.001956105 0 -0.113267 5.81169e-4 0 -0.1194971 -0.006269097 0 -0.1128323 -2.71306e-5 0 -0.111062 -0.001375496 0 -0.1117165 -0.001016974 0 -0.1128371 -0.006578803 0 -0.1123116 -5.63894e-4 0 -0.110361 -0.001632809 0 -0.1074134 -0.001567363 0 -0.1081385 -0.001749992 0 -0.09951257 -0.007087588 0 -0.1067234 -0.001278638 0 -0.1060856 -8.91081e-4 0 -0.1055123 -4.12631e-4 0 -0.09900218 0.002652764 0 -0.1050164 1.46148e-4 0 -0.1042996 0.001453459 0 -0.104609 7.7285e-4 0 -0.1040952 0.002172768 0 -0.1040002 0.002914667 0 -0.09900218 0.002652764 0 -0.0995078 -0.006996631 0.0435 -0.09900212 0.002652764 0.08700001 -0.09951257 -0.007087588 0 -0.09950453 -0.006934165 0.08700001 -0.09900212 0.002652764 0.08700001 -0.09250634 -0.007152497 0.08700001 -0.09201174 0.002286434 0.08700001 -0.09950453 -0.006934165 0.08700001 -0.09201174 0.002286434 0.08700001 -0.09250634 -0.007152497 0.08700001 -0.09211641 2.89213e-4 0.09100002 -0.09211641 2.89216e-4 0.123 -0.09201174 0.002286434 0.126 -0.09201174 0.002286434 0.123 -0.09250593 -0.007144153 0.126 -0.09201174 0.002286434 0.09100002 -0.09201174 0.002286434 0.126 -0.09950411 -0.006926 0.126 -0.09900212 0.002652764 0.126 -0.09250593 -0.007144153 0.126 -0.09900212 0.002652764 0.126 -0.09950411 -0.006926 0.126 -0.09951031 -0.007044732 0.1662499 -0.09951537 -0.00714147 0.2064999 -0.09951931 -0.007216215 0.2467499 -0.09900212 0.002652764 0.287 -0.09952205 -0.007268965 0.287 -0.09900212 0.002652764 0.287 -0.1020206 -0.007174789 0.287 -0.1014987 0.002783596 0.287 -0.09952205 -0.007268965 0.287 -0.1014987 0.002783596 0.287 -0.1020187 -0.007140457 0.2920001 -0.1014987 0.002783596 0.2920001 -0.1020206 -0.007174789 0.287 -0.1014987 0.002783596 0.2920001 -0.09952026 -0.007235348 0.2920001 -0.09900212 0.002652764 0.2920001 -0.1020187 -0.007140457 0.2920001 -0.09900212 0.002652764 0.2920001 -0.09952026 -0.007235348 0.2920001 -0.09951663 -0.007165133 0.3 -0.09900212 0.002652764 0.3 -0.09900212 0.002652764 0.3 -0.1035139 -0.00700891 0.3 -0.1029967 0.002862095 0.3 -0.09951663 -0.007165133 0.3 -0.1029967 0.002862095 0.3 -0.1035128 -0.006987452 0.3020001 -0.1029967 0.002862095 0.3020001 -0.1035139 -0.00700891 0.3 -0.1250761 0.002016365 0.103 -0.1139754 0.00275278 0.103 -0.1249714 0.004013597 0.103 -0.1138706 0.002075493 0.103 -0.1139865 0.003437995 0.103 -0.1136744 0.001418888 0.103 -0.1249714 0.004013597 0.09100002 -0.1250761 0.002016365 0.09100002 -0.1250761 0.002016365 0.103 -0.1249714 0.004013597 0.103 -0.1139754 0.002752721 0.09100002 -0.1249714 0.004013597 0.09100002 -0.1139865 0.003437995 0.09100002 -0.1250761 0.002016365 0.09100002 -0.1138706 0.002075493 0.09100002 -0.1136744 0.001418888 0.09100002 -0.1040829 0.002234339 0.09100002 -0.1040002 0.002914667 0 -0.1040002 0.002914667 0.09100002 -0.1040829 0.002234339 0.123 -0.1040951 0.002172827 0.145 -0.1042578 0.001571714 0.123 -0.1046075 7.75725e-4 0.145 -0.104609 7.7285e-4 0 -0.1045217 9.39285e-4 0.09100002 -0.1042578 0.001571714 0.09100002 -0.1042996 0.001453459 0 -0.1040952 0.002172768 0 -0.1045217 9.39288e-4 0.123 -0.1067234 -0.001278638 0.145 -0.1074118 -0.001566767 0.145 -0.1067234 -0.001278638 0 -0.1042987 0.001456022 0.145 -0.1040002 0.002914667 0.123 -0.1040002 0.002914667 0.145 -0.1060856 -8.91081e-4 0 -0.1055123 -4.12631e-4 0 -0.1060842 -8.90208e-4 0.145 -0.1050143 1.48718e-4 0.145 -0.1050164 1.46148e-4 0 -0.1088827 -0.001822292 0 -0.1088795 -0.001822173 0.145 -0.1096258 -0.00178337 0.145 -0.1081358 -0.001749396 0.145 -0.1081385 -0.001749992 0 -0.1110605 -0.001376271 0.145 -0.110361 -0.001632809 0 -0.1103584 -0.001633644 0.145 -0.109629 -0.001782894 0 -0.1123116 -5.63894e-4 0 -0.1123102 -5.64878e-4 0.145 -0.1128304 -2.91255e-5 0.145 -0.111062 -0.001375496 0 -0.1117165 -0.001016974 0.145 -0.1117165 -0.001016974 0 -0.1136744 0.001418888 0.09100002 -0.1138706 0.002075493 0.09100002 -0.1138421 0.001956105 0 -0.1132652 5.78426e-4 0.145 -0.113267 5.81169e-4 0 -0.1128323 -2.71306e-5 0 -0.1136049 0.001244246 0.145 -0.1136744 0.001418888 0.103 -0.1136061 0.001247227 0 -0.1138415 0.001953482 0.145 -0.1138706 0.002075493 0.103 -0.1139754 0.00275278 0.103 -0.1139696 0.002690255 0.145 -0.1139865 0.003437995 0.145 -0.1139865 0.003437995 0.103 -0.1139696 0.002690255 0 -0.1139754 0.002752721 0.09100002 -0.1139865 0.003437995 0.09100002 -0.1139865 0.003437995 0 -0.1074134 -0.001567363 0 -0.1055103 -4.10809e-4 0.145 -0.1106533 -0.00631839 0.282186 -0.1135895 -0.00640887 0.241898 -0.119492 -0.006171584 0.277435 -0.09948849 -0.006629168 0.327249 -0.106995 -0.006203413 0.322466 -0.09946787 -0.006234765 0.352498 -0.1194319 -0.00502479 0.361145 -0.1101738 -0.005637824 0.362737 -0.119462 -0.005598187 0.31929 -0.1061047 -0.005455553 0.4030001 -0.09944546 -0.005807518 0.4030001 -0.1194018 -0.004451334 0.4030001 -0.1127568 -0.005003511 0.4030001 -0.1195045 -0.006410717 0.235577 -0.1172965 -0.006516098 0.161298 -0.1194996 -0.006315529 0.193718 -0.115804 -0.006474733 0.201602 -0.1035128 -0.006987452 0.3020001 -0.09950453 -0.006934165 0.08700001 -0.09950411 -0.006926 0.126 -0.09250634 -0.007152497 0.08700001 -0.1089907 -0.006902813 0.161298 -0.1194901 -0.006135404 0.08700001 -0.1199882 -0.006105542 0.09440189 -0.119515 -0.006129086 0.094181 -0.1194896 -0.006125152 0.11 -0.1167286 -0.006258606 0.09942638 -0.1171298 -0.006239891 0.09967261 -0.1160777 -0.006290197 0.09522092 -0.1097701 -0.006913781 0.08066546 -0.1163755 -0.006277143 0.09487551 -0.1091322 -0.006879925 0.0403369 -0.1061757 -0.006851673 0 -0.1128371 -0.006578803 0 -0.1190108 -0.006153821 0.09404581 -0.109723 -0.00692147 0.120986 -0.1158335 -0.006300985 0.09561288 -0.09250593 -0.007144153 0.126 -0.1020187 -0.007140457 0.2920001 -0.09951663 -0.007165133 0.3 -0.09952026 -0.007235348 0.2920001 -0.1175644 -0.006219446 0.09985297 -0.1147758 -0.005764842 0.322466 -0.1026831 -0.006689488 0.282186 -0.1035139 -0.00700891 0.3 -0.09952205 -0.007268965 0.287 -0.1020206 -0.007174789 0.287 -0.1214414 -0.006031572 0.0964784 -0.1274784 -0.005702912 0.08700001 -0.1214873 -0.00602895 0.097 -0.118491 -0.006178915 0.09399998 -0.1204171 -0.006081819 0.09929847 -0.1199894 -0.006102979 0.09959828 -0.1204161 -0.006084024 0.0947017 -0.1210864 -0.00604856 0.09849989 -0.1207866 -0.006063461 0.09892857 -0.1210849 -0.00605005 0.09549939 -0.1207855 -0.006065309 0.09507137 -0.1213071 -0.006037592 0.09802579 -0.127478 -0.005693733 0.11 -0.1213058 -0.006038665 0.09597307 -0.1214419 -0.006031036 0.0975207 -0.1190116 -0.006150841 0.0999546 -0.1195162 -0.006126224 0.0998193 -0.1180216 -0.006197988 0.099963 -0.1184909 -0.006175935 0.1 -0.1163653 -0.006275415 0.09911412 -0.1160452 -0.006290197 0.09873229 -0.1157922 -0.00630182 0.09830582 -0.1156212 -0.006309688 0.09786689 -0.1154947 -0.006315767 0.09698307 -0.1155239 -0.006314218 0.09742701 -0.1155341 -0.006314158 0.09651619 -0.1156494 -0.006309151 0.0960462 -0.119493 -0.006190001 0.0435 -0.1167303 -0.006261348 0.09457248 -0.1171314 -0.00624305 0.09432661 -0.1175656 -0.006222784 0.0941466 -0.1180226 -0.006201267 0.09403687 -0.102615 -0.006063818 0.362737 -0.1194971 -0.006269097 0 -0.0995078 -0.006996631 0.0435 -0.1075733 -0.006857991 0.201602 -0.1054707 -0.006786882 0.241898 -0.0994535 -0.005960881 0.377749 -0.1013744 -0.007228434 0.120986 -0.09951031 -0.007044732 0.1662499 -0.09951537 -0.00714147 0.2064999 -0.09951931 -0.007216215 0.2467499 -0.09951549 -0.007144212 0.3020001 -0.09951257 -0.007087588 0 -0.1191055 0.0017035 0.09418088 -0.1250761 0.002016365 0.09100002 -0.118601 0.001677036 0.09404557 -0.1180808 0.001649796 0.1 -0.1175876 0.001623928 0.09995907 -0.1136744 0.001418888 0.103 -0.1150951 0.001493334 0.09675228 -0.1150951 0.001493334 0.09724771 -0.1250761 0.002016365 0.103 -0.118601 0.001677036 0.09995442 -0.1180808 0.001649796 0.09399998 -0.1136744 0.001418888 0.09100002 -0.1175876 0.001623928 0.09404087 -0.1166549 0.001575052 0.0996384 -0.117108 0.001598834 0.09983742 -0.1158766 0.001534283 0.0990318 -0.1162407 0.001553356 0.09936738 -0.1153373 0.00150603 0.09820508 -0.1155727 0.001518368 0.09864079 -0.1151766 0.001497626 0.09773647 -0.1151766 0.001497626 0.09626346 -0.1155727 0.001518368 0.0953592 -0.1153373 0.00150603 0.09579491 -0.1162407 0.001553356 0.09463262 -0.1158766 0.001534283 0.09496819 -0.117108 0.001598834 0.09416258 -0.1166549 0.001575052 0.0943616 -0.120896 0.001797318 0.0959739 -0.1210311 0.001804411 0.09647911 -0.1200065 0.001750707 0.09470188 -0.1195787 0.001728296 0.09440189 -0.1206753 0.001785755 0.09549999 -0.1203757 0.001770079 0.09507161 -0.1210767 0.001806795 0.097 -0.120896 0.001797318 0.09802609 -0.1210311 0.001804411 0.09752088 -0.1203757 0.001770079 0.09892839 -0.1206753 0.001785755 0.09850001 -0.1195787 0.001728296 0.0995981 -0.1200065 0.001750707 0.09929811 -0.1191055 0.0017035 0.09981912 -0.1150951 0.001493334 0.09724771 -0.1154947 -0.006315767 0.09698307 -0.1150951 0.001493334 0.09675228 -0.1151766 0.001497626 0.09626346 -0.1155341 -0.006314158 0.09651619 -0.1156494 -0.006309151 0.0960462 -0.1153373 0.00150603 0.09579491 -0.1158335 -0.006300985 0.09561288 -0.1155727 0.001518368 0.0953592 -0.1158766 0.001534283 0.09496819 -0.1160777 -0.006290197 0.09522092 -0.1163755 -0.006277143 0.09487551 -0.1162407 0.001553356 0.09463262 -0.1167303 -0.006261348 0.09457248 -0.1166549 0.001575052 0.0943616 -0.117108 0.001598834 0.09416258 -0.1171314 -0.00624305 0.09432661 -0.1175656 -0.006222784 0.0941466 -0.1180226 -0.006201267 0.09403687 -0.1175876 0.001623928 0.09404087 -0.118491 -0.006178915 0.09399998 -0.1180808 0.001649796 0.09399998 -0.1155239 -0.006314218 0.09742701 -0.1151766 0.001497626 0.09773647 -0.1156212 -0.006309688 0.09786689 -0.1153373 0.00150603 0.09820508 -0.1157922 -0.00630182 0.09830582 -0.1160452 -0.006290197 0.09873229 -0.1155727 0.001518368 0.09864079 -0.1158766 0.001534283 0.0990318 -0.1163653 -0.006275415 0.09911412 -0.1162407 0.001553356 0.09936738 -0.1167286 -0.006258606 0.09942638 -0.1171298 -0.006239891 0.09967261 -0.1166549 0.001575052 0.0996384 -0.117108 0.001598834 0.09983742 -0.1175644 -0.006219446 0.09985297 -0.1175876 0.001623928 0.09995907 -0.1180216 -0.006197988 0.099963 -0.1180808 0.001649796 0.1 -0.1184909 -0.006175935 0.1 -0.1190108 -0.006153821 0.09404581 -0.1180808 0.001649796 0.09399998 -0.118491 -0.006178915 0.09399998 -0.1204161 -0.006084024 0.0947017 -0.1195787 0.001728296 0.09440189 -0.1199882 -0.006105542 0.09440189 -0.119515 -0.006129086 0.094181 -0.1191055 0.0017035 0.09418088 -0.118601 0.001677036 0.09404557 -0.1206753 0.001785755 0.09549999 -0.1210849 -0.00605005 0.09549939 -0.1213058 -0.006038665 0.09597307 -0.1200065 0.001750707 0.09470188 -0.1207855 -0.006065309 0.09507137 -0.1203757 0.001770079 0.09507161 -0.1214873 -0.00602895 0.097 -0.1214419 -0.006031036 0.0975207 -0.1210767 0.001806795 0.097 -0.1214414 -0.006031572 0.0964784 -0.1210311 0.001804411 0.09647911 -0.120896 0.001797318 0.0959739 -0.1207866 -0.006063461 0.09892857 -0.1206753 0.001785755 0.09850001 -0.1210864 -0.00604856 0.09849989 -0.120896 0.001797318 0.09802609 -0.1210311 0.001804411 0.09752088 -0.1213071 -0.006037592 0.09802579 -0.1199894 -0.006102979 0.09959828 -0.1200065 0.001750707 0.09929811 -0.1204171 -0.006081819 0.09929847 -0.1203757 0.001770079 0.09892839 -0.1195162 -0.006126224 0.0998193 -0.1195787 0.001728296 0.0995981 -0.1191055 0.0017035 0.09981912 -0.1190116 -0.006150841 0.0999546 -0.1184909 -0.006175935 0.1 -0.118601 0.001677036 0.09995442 -0.1180808 0.001649796 0.1 -0.1136598 0.005428135 0.145 -0.1138637 0.004710614 0.145 -0.1126755 0.005202353 0.145 -0.1097429 0.007631003 0.145 -0.1105468 0.008450627 0.145 -0.1112362 0.008161783 0.145 -0.1098218 0.008633434 0.145 -0.1103782 0.007449507 0.145 -0.1090866 0.007705509 0.145 -0.1118749 0.007773458 0.145 -0.1109749 0.007165908 0.145 -0.1115167 0.006787955 0.145 -0.1124486 0.007294297 0.145 -0.1129443 0.006735086 0.145 -0.1068987 0.00826013 0.145 -0.1075999 0.008517205 0.145 -0.1077818 0.007528245 0.145 -0.111989 0.006326019 0.145 -0.113351 0.006108343 0.145 -0.1123788 0.005792617 0.145 -0.1043535 0.005638957 0.145 -0.1053526 0.005424439 0.145 -0.1041171 0.004929721 0.145 -0.1139585 0.003969013 0.145 -0.1128709 0.004571259 0.145 -0.1129598 0.00391668 0.145 -0.1051192 0.004806339 0.145 -0.103989 0.004193127 0.145 -0.104693 0.006304919 0.145 -0.1061059 0.006504416 0.145 -0.1056845 0.005995631 0.145 -0.1049908 0.004158318 0.145 -0.1056486 0.007448852 0.145 -0.1066053 0.006936907 0.145 -0.105128 0.006912708 0.145 -0.107169 0.007281303 0.145 -0.1062434 0.00790137 0.145 -0.1083316 0.008666992 0.145 -0.1084269 0.007670938 0.145 -0.1090777 0.008706092 0.145 -0.1039721 0.003445684 0.145 -0.1049708 0.003498017 0.145 -0.00214374 -0.002098262 0.3 -0.001769185 -0.002422571 0.3 -0.001346111 -0.002680778 0.3 -0.001059591 0.002806603 0.3 -0.001507341 0.002593934 0.3 0.002929091 -6.48064e-4 0.3 -8.86217e-4 -0.00286585 0.3 -0.002460181 -0.001716613 0.3 -4.02123e-4 -0.002972722 0.3 -0.00270909 -0.001288115 0.3 -0.002884089 -8.24535e-4 0.3 9.21935e-5 -0.002998471 0.3 -0.002980768 -3.38369e-4 0.3 5.84811e-4 -0.002942442 0.3 -0.002995908 1.5702e-4 0.3 0.001060545 -0.002806127 0.3 0.001508295 -0.002593338 0.3 -0.002929091 6.47977e-4 0.3 0.002560675 -0.00156331 0.3 -0.002267301 0.001963973 0.3 0.002268314 -0.001963317 0.3 -0.002559661 0.001563906 0.3 -0.002782106 0.001121222 0.3 0.00191468 -0.002309799 0.3 0.002995848 -1.56966e-4 0.3 -0.001913726 0.002310454 0.3 0.002783119 -0.001120746 0.3 0.002885043 8.24277e-4 0.3 0.002710103 0.001287758 0.3 4.04105e-4 0.002972662 0.3 0.002980768 3.38282e-4 0.3 -9.02116e-5 0.00299859 0.3 -5.82814e-4 0.00294274 0.3 0.001347124 0.00268048 0.3 0.002144694 0.002097785 0.3 0.001770138 0.002422153 0.3 0.002461135 0.001716196 0.3 8.88184e-4 0.002865672 0.3 0.02537071 -0.006553888 -0.003999948 0.0250374 -0.006608009 -0.003999948 0.02520632 -0.006595134 -0.003999948 0.01010185 1.73284e-4 -0.003999948 0.009936094 1.83e-4 -0.003999948 0.009771943 1.65175e-4 -0.003999948 0.02552551 -0.006485521 -0.003999948 0.0256676 -0.006391942 -0.003999948 0.02579081 -0.006275773 -0.003999948 0.02589303 -0.00614047 -0.003999948 0.02597004 -0.005989849 -0.003999948 0.02602159 -0.005828261 -0.003999948 0.02604538 -0.005660414 -0.003999948 0.02603995 -0.005496203 -0.003999948 0.02576416 -0.004911959 -0.003999948 0.02564066 -0.004803836 -0.003999948 0.02534908 -0.004654943 -0.003999948 0.02600836 -0.005335032 -0.003999948 0.02595037 -0.005181193 -0.003999948 0.02586871 -0.005038917 -0.003999948 0.02550101 -0.004717409 -0.003999948 0.008718311 -0.005419194 -0.003999948 0.01026314 1.36384e-4 -0.003999948 0.009206175 -1.60062e-4 -0.003999948 0.009108006 -2.93709e-4 -0.003999948 0.009611368 1.20446e-4 -0.003999948 0.009461522 4.9894e-5 -0.003999948 0.009325385 -4.44821e-5 -0.003999948 0.009034156 -4.41788e-4 -0.003999948 0.008984863 -6.00112e-4 -0.003999948 0.008962213 -7.64393e-4 -0.003999948 0.008722841 -0.005580425 -0.003999948 0.00970757 -0.006471455 -0.003999948 0.008808732 -0.00589019 -0.003999948 0.008753597 -0.005738794 -0.003999948 0.008988022 -0.006156623 -0.003999948 0.008887529 -0.006030678 -0.003999948 0.00924319 -0.006352365 -0.003999948 0.009108543 -0.006264865 -0.003999948 0.009547114 -0.00645703 -0.003999948 0.00939095 -0.006416976 -0.003999948 -0.05677491 0.005979239 -0.003999948 -0.0564689 0.005914211 -0.003999948 -0.05661976 0.005958795 -0.003999948 -0.07056647 -0.002249956 -0.003999948 -0.07022809 -0.002328038 -0.003999948 -0.07072043 -0.002168118 -0.003999948 -0.05632728 0.005846679 -0.003999948 -0.05608421 0.005649745 -0.003999948 -0.05619776 0.005757749 -0.003999948 -0.0559886 0.00552529 -0.003999948 -0.05591374 0.005387365 -0.003999948 -0.05586141 0.005239427 -0.003999948 -0.05583244 0.00508511 -0.003999948 -0.05582863 0.00492829 -0.003999948 -0.07080805 0.005713284 -0.003999948 -0.07106673 -0.00178343 -0.003999948 -0.07113206 -0.001621782 -0.003999948 -0.05678683 -0.00292325 -0.003999948 -0.05724591 -0.003008365 -0.003999948 -0.05693477 -0.002975642 -0.003999948 -0.0570895 -0.003004252 -0.003999948 -0.05664873 -0.002848386 -0.003999948 -0.05652457 -0.00275284 -0.003999948 -0.05641645 -0.002639055 -0.003999948 -0.05632758 -0.002509713 -0.003999948 -0.05626004 -0.002368092 -0.003999948 -0.0562151 -0.00221765 -0.003999948 -0.05619496 -0.002062082 -0.003999948 -0.07040065 -0.002303779 -0.003999948 -0.0711683 -0.001451313 -0.003999948 -0.07085776 -0.00206077 -0.003999948 -0.07097434 -0.00193125 -0.003999948 -0.07117438 -0.001277089 -0.003999948 -0.0697571 0.006659567 -0.003999948 -0.07074308 0.006019294 -0.003999948 -0.0707876 0.005868852 -0.003999948 -0.07058656 0.006290256 -0.003999948 -0.07067549 0.006160914 -0.003999948 -0.0703541 0.006499588 -0.003999948 -0.07047855 0.006404042 -0.003999948 -0.07006824 0.006626844 -0.003999948 -0.07021623 0.006574451 -0.003999948 -0.06991398 0.006655454 -0.003999948 -0.1316722 0.009904086 -0.003999948 -0.1313661 0.009839057 -0.003999948 -0.1315166 0.009883582 -0.003999948 -0.1454637 0.00167483 -0.003999948 -0.1451253 0.001596689 -0.003999948 -0.1456177 0.001756668 -0.003999948 -0.1312245 0.009771466 -0.003999948 -0.1309814 0.009574592 -0.003999948 -0.1310952 0.009682595 -0.003999948 -0.1308858 0.009450078 -0.003999948 -0.130811 0.009312212 -0.003999948 -0.1307585 0.009164273 -0.003999948 -0.13073 0.009009957 -0.003999948 -0.1307259 0.008853137 -0.003999948 -0.1457054 0.009638071 -0.003999948 -0.145964 0.002141356 -0.003999948 -0.1460293 0.002302944 -0.003999948 -0.1316841 0.001001477 -0.003999948 -0.1321431 9.16443e-4 -0.003999948 -0.131832 9.49149e-4 -0.003999948 -0.1319863 9.20553e-4 -0.003999948 -0.1315461 0.0010764 -0.003999948 -0.1314217 0.001171886 -0.003999948 -0.1313137 0.001285731 -0.003999948 -0.1312248 0.001415073 -0.003999948 -0.1311572 0.001556694 -0.003999948 -0.1311126 0.001707136 -0.003999948 -0.1310922 0.001862704 -0.003999948 -0.1452979 0.001620948 -0.003999948 -0.1460655 0.002473473 -0.003999948 -0.145755 0.001864016 -0.003999948 -0.1458716 0.001993536 -0.003999948 -0.1460716 0.002647697 -0.003999948 -0.1446543 0.01058441 -0.003999948 -0.1456403 0.00994414 -0.003999948 -0.1456848 0.009793639 -0.003999948 -0.1454838 0.0102151 -0.003999948 -0.1455727 0.01008576 -0.003999948 -0.1452513 0.01042443 -0.003999948 -0.1453758 0.01032888 -0.003999948 -0.1449655 0.01055169 -0.003999948 -0.1451134 0.01049929 -0.003999948 -0.1448112 0.0105803 -0.003999948 -0.1051192 0.004806339 0.145 -0.1051192 0.004806399 0.4030001 -0.1049908 0.004158377 0.4030001 -0.1049708 0.003498017 0.4030001 -0.1049708 0.003498017 0.145 -0.1049908 0.004158318 0.145 -0.1056844 0.005995631 0.4030001 -0.1061059 0.006504416 0.145 -0.1061059 0.006504476 0.4030001 -0.1056845 0.005995631 0.145 -0.1053526 0.005424439 0.4030001 -0.1053526 0.005424439 0.145 -0.1077818 0.007528245 0.145 -0.1077818 0.007528245 0.4030001 -0.107169 0.007281363 0.4030001 -0.107169 0.007281303 0.145 -0.1066052 0.006936967 0.4030001 -0.1066053 0.006936907 0.145 -0.1097429 0.007631003 0.4030001 -0.1090865 0.007705509 0.4030001 -0.1097429 0.007631003 0.145 -0.1084268 0.007670938 0.4030001 -0.1084269 0.007670938 0.145 -0.1090866 0.007705509 0.145 -0.1109749 0.007165908 0.4030001 -0.1115167 0.006787955 0.145 -0.1115167 0.006788015 0.4030001 -0.1103782 0.007449507 0.145 -0.1109749 0.007165908 0.145 -0.1103782 0.007449507 0.4030001 -0.111989 0.006326019 0.4030001 -0.111989 0.006326019 0.145 -0.1123788 0.005792617 0.145 -0.1126755 0.005202353 0.145 -0.1123787 0.005792617 0.4030001 -0.1128709 0.004571259 0.145 -0.1126754 0.005202353 0.4030001 -0.1128708 0.004571318 0.4030001 -0.1129598 0.00391668 0.145 -0.1129598 0.00391668 0.4030001 -0.07590097 0.003977417 0.303 -0.09886944 0.005181014 0.3160001 -0.07590097 0.003977417 0.3160001 -0.07590097 0.003977417 0.3010001 -0.07590097 0.003977417 0.285 -0.09886944 0.005181014 0.285 -0.07071048 0.003705441 0.303 -0.07071048 0.003705441 0.3010001 -0.09886944 0.005181014 0.285 -0.0989741 0.003183782 0.3160001 -0.09886944 0.005181014 0.3160001 -0.0989741 0.003183782 0.285 -0.0989741 0.003183782 0.08700001 -0.1039721 0.003445684 0.145 -0.0989741 0.003183782 0.126 -0.09198373 0.002817451 0.126 -0.09198373 0.002817451 0.08700001 -0.1039722 0.003445684 0 -0.0989741 0.003183782 0.4030001 -0.1049708 0.003498017 0.4030001 -0.09897416 0.003183782 0 -0.1049708 0.003498017 0.145 -0.1083316 0.008666992 0.145 -0.1083312 0.008666932 0 -0.1090772 0.008706033 0 -0.1075999 0.008517205 0.145 -0.1075987 0.008516907 0 -0.1068968 0.008259356 0 -0.1068987 0.00826013 0.145 -0.1062434 0.00790137 0.145 -0.1062413 0.007900059 0 -0.1056486 0.007448852 0.145 -0.1056467 0.007447063 0 -0.1051263 0.006910562 0 -0.105128 0.006912708 0.145 -0.104693 0.006304919 0.145 -0.1046918 0.006302595 0 -0.1043535 0.005638957 0.145 -0.1043527 0.005636751 0 -0.1041167 0.004927992 0 -0.1041171 0.004929721 0.145 -0.103989 0.004193127 0.145 -0.103989 0.004193127 0 -0.1039721 0.003445684 0.145 -0.1039722 0.003445684 0 -0.1090777 0.008706092 0.145 -0.1098218 0.008633434 0.145 -0.1098205 0.008633553 0 -0.1105448 0.008451163 0 -0.1105468 0.008450627 0.145 -0.111234 0.008162856 0 -0.1112362 0.008161783 0.145 -0.1118749 0.007773458 0.145 -0.1118727 0.007775008 0 -0.1124466 0.007296264 0 -0.1124486 0.007294297 0.145 -0.1129427 0.006737172 0 -0.1129443 0.006735086 0.145 -0.113351 0.006108343 0.145 -0.11335 0.00611037 0 -0.1136592 0.005429744 0 -0.1136598 0.005428135 0.145 -0.1138637 0.004710614 0 -0.1138637 0.004710614 0.145 -0.1139585 0.003968954 0 -0.1139585 0.003969013 0.145 -0.1139585 0.003968954 0 -0.1189467 0.00423038 0 -0.1189467 0.00423038 0.08700001 -0.1139585 0.003969013 0.145 -0.1189467 0.00423038 0.11 -0.1189467 0.00423038 0.4030001 -0.1129598 0.00391668 0.145 -0.1129598 0.00391668 0.4030001 -0.1269358 0.004649043 0.08700001 -0.1269358 0.004649043 0.11 -0.002884089 -8.23843e-4 0 -0.002884089 -8.24535e-4 0.3 -0.002980768 -3.38369e-4 0.3 -0.002995908 1.5702e-4 0.3 -0.002995908 1.56994e-4 0 -0.002980828 -3.38395e-4 0 -0.002460181 -0.001716613 0.3 -0.002144753 -0.002097129 0 -0.00214374 -0.002098262 0.3 -0.002461194 -0.001715481 0 -0.00270909 -0.001288115 0.3 -0.00270909 -0.001287221 0 -8.88228e-4 -0.002865314 0 -8.86217e-4 -0.00286585 0.3 -0.001346111 -0.002680778 0.3 -0.001348137 -0.002679944 0 -0.001769185 -0.002422571 0.3 -0.001770198 -0.002421557 0 5.84811e-4 -0.002942442 0.3 9.21935e-5 -0.002998471 0.3 5.8274e-4 -0.00294286 0 -4.02123e-4 -0.002972722 0.3 -4.04179e-4 -0.002972483 0 9.0152e-5 -0.00299859 0 0.001508295 -0.002593338 0.3 0.001913607 -0.002310872 0 0.00191468 -0.002309799 0.3 0.001059472 -0.002806901 0 0.001507222 -0.002594292 0 0.001060545 -0.002806127 0.3 0.002783 -0.00112152 0 0.002783119 -0.001120746 0.3 0.002560675 -0.00156331 0.3 0.002560555 -0.001564323 0 0.002268314 -0.001963317 0.3 0.002267241 -0.00196439 0 0.002980768 3.38282e-4 0.3 0.002995848 -1.56966e-4 0.3 0.002980709 3.38256e-4 0 0.002929091 -6.48064e-4 0.3 0.002929031 -6.48091e-4 0 0.002995789 -1.56992e-4 0 0.002710103 0.001287758 0.3 0.002461075 0.001716196 0 0.002461135 0.001716196 0.3 0.002884984 8.24251e-4 0 0.002710044 0.001287758 0 0.002885043 8.24277e-4 0.3 0.001347064 0.00268048 0 0.001347124 0.00268048 0.3 0.001770138 0.002422153 0.3 0.001770079 0.002422153 0 0.002144694 0.002097785 0.3 0.002144634 0.002097785 0 -9.02116e-5 0.00299859 0.3 4.04105e-4 0.002972662 0.3 -9.02563e-5 0.00299853 0 8.88184e-4 0.002865672 0.3 8.88139e-4 0.002865612 0 4.0406e-4 0.002972662 0 -5.82859e-4 0.002942681 0 -0.001059591 0.002806603 0 -5.82814e-4 0.00294274 0.3 -0.001059591 0.002806603 0.3 -0.001507341 0.002593934 0 -0.001913726 0.002310454 0 -0.001507341 0.002593934 0.3 -0.00226736 0.001963973 0 -0.001913726 0.002310454 0.3 -0.002267301 0.001963973 0.3 -0.002559721 0.001563906 0 -0.002782166 0.001121222 0 -0.002559661 0.001563906 0.3 -0.002929151 6.47951e-4 0 -0.002782106 0.001121222 0.3 -0.002929091 6.47977e-4 0.3 0.00970757 -0.006471455 0 0.0250374 -0.006608009 0 0.0250374 -0.006608009 -0.003999948 0.00970757 -0.006471455 -0.003999948 0.02586871 -0.005038917 -0.003999948 0.02586871 -0.005038917 0 0.02576416 -0.004911959 -0.003999948 0.02604538 -0.005660414 -0.003999948 0.02602159 -0.005828261 0 0.02604538 -0.005660414 0 0.02576416 -0.004911959 0 0.02564066 -0.004803836 -0.003999948 0.02550101 -0.004717409 -0.003999948 0.02564066 -0.004803836 0 0.02550101 -0.004717409 0 0.02534908 -0.004654943 -0.003999948 0.02534908 -0.004654943 0 0.02595037 -0.005181193 0 0.02600836 -0.005335032 0 0.02595037 -0.005181193 -0.003999948 0.02600836 -0.005335032 -0.003999948 0.02603995 -0.005496203 0 0.02603995 -0.005496203 -0.003999948 0.02597004 -0.005989849 -0.003999948 0.02597004 -0.005989849 0 0.02602159 -0.005828261 -0.003999948 0.0256676 -0.006391942 -0.003999948 0.0256676 -0.006391942 0 0.02579081 -0.006275773 -0.003999948 0.02589303 -0.00614047 -0.003999948 0.02579081 -0.006275773 0 0.02589303 -0.00614047 0 0.02537071 -0.006553888 -0.003999948 0.02520632 -0.006595134 0 0.02537071 -0.006553888 0 0.02552551 -0.006485521 0 0.02552551 -0.006485521 -0.003999948 0.0250374 -0.006608009 0 0.02520632 -0.006595134 -0.003999948 0.0250374 -0.006608009 -0.003999948 0.02534908 -0.004654943 0 0.01026314 1.36384e-4 0 0.01026314 1.36384e-4 -0.003999948 0.02534908 -0.004654943 -0.003999948 0.009034156 -4.41787e-4 0 0.008984863 -6.00112e-4 -0.003999948 0.009034156 -4.41788e-4 -0.003999948 0.008962213 -7.64393e-4 -0.003999948 0.008984863 -6.00112e-4 0 0.008962213 -7.64393e-4 0 0.009206175 -1.60062e-4 -0.003999948 0.009325385 -4.44821e-5 -0.003999948 0.009325385 -4.44816e-5 0 0.009206175 -1.60061e-4 0 0.009108006 -2.93709e-4 0 0.009108006 -2.93709e-4 -0.003999948 0.009771943 1.65176e-4 0 0.009611368 1.20446e-4 -0.003999948 0.009771943 1.65175e-4 -0.003999948 0.009611368 1.20447e-4 0 0.009461522 4.98944e-5 0 0.009461522 4.9894e-5 -0.003999948 0.009936094 1.83e-4 0 0.009936094 1.83e-4 -0.003999948 0.01010185 1.73284e-4 0 0.01010185 1.73284e-4 -0.003999948 0.01026314 1.36384e-4 0 0.01026314 1.36384e-4 -0.003999948 0.008718311 -0.005419194 0 0.008962213 -7.64393e-4 -0.003999948 0.008962213 -7.64393e-4 0 0.008718311 -0.005419194 -0.003999948 0.00939095 -0.006416976 0 0.009547114 -0.00645703 -0.003999948 0.00939095 -0.006416976 -0.003999948 0.00970757 -0.006471455 -0.003999948 0.009547114 -0.00645703 0 0.00970757 -0.006471455 0 0.009108543 -0.006264865 -0.003999948 0.008988022 -0.006156623 -0.003999948 0.008988022 -0.006156623 0 0.009108543 -0.006264865 0 0.00924319 -0.006352365 0 0.00924319 -0.006352365 -0.003999948 0.008753597 -0.005738794 0 0.008808732 -0.00589019 -0.003999948 0.008753597 -0.005738794 -0.003999948 0.008808732 -0.00589019 0 0.008887529 -0.006030678 0 0.008887529 -0.006030678 -0.003999948 0.008722841 -0.005580425 -0.003999948 0.008722841 -0.005580425 0 0.008718311 -0.005419194 -0.003999948 0.008718311 -0.005419194 0 -0.07022809 -0.002328038 0 -0.05724591 -0.003008365 -0.003999948 -0.07022809 -0.002328038 -0.003999948 -0.05724591 -0.003008365 0 -0.05626004 -0.002368092 0 -0.0562151 -0.00221765 -0.003999948 -0.05629515 -0.002454996 -0.003999948 -0.05619496 -0.002062082 -0.003999948 -0.0562151 -0.00221765 0 -0.05619496 -0.002062082 0 -0.05641645 -0.002639055 -0.003999948 -0.05652457 -0.00275284 -0.003999948 -0.05652457 -0.00275284 0 -0.05641645 -0.002639055 0 -0.05632758 -0.002509713 0 -0.05693477 -0.002975642 0 -0.05678683 -0.00292325 -0.003999948 -0.05693477 -0.002975642 -0.003999948 -0.05678683 -0.00292325 0 -0.05664873 -0.002848386 0 -0.05664873 -0.002848386 -0.003999948 -0.0570895 -0.003004252 -0.003999948 -0.0570895 -0.003004252 0 -0.05724591 -0.003008365 -0.003999948 -0.05724591 -0.003008365 0 -0.05619496 -0.002062082 -0.003999948 -0.05582863 0.00492829 0 -0.05582863 0.00492829 -0.003999948 -0.05619496 -0.002062082 0 -0.0564689 0.005914211 0 -0.05661976 0.005958795 -0.003999948 -0.0564689 0.005914211 -0.003999948 -0.05677491 0.005979239 -0.003999948 -0.05661976 0.005958795 0 -0.05677491 0.005979239 0 -0.05619776 0.005757749 -0.003999948 -0.05608421 0.005649745 -0.003999948 -0.05608421 0.005649745 0 -0.05619776 0.005757749 0 -0.05632728 0.005846679 0 -0.05632728 0.005846679 -0.003999948 -0.05586141 0.005239427 0 -0.05591374 0.005387365 -0.003999948 -0.05586141 0.005239427 -0.003999948 -0.05591374 0.005387365 0 -0.0559886 0.00552529 0 -0.0559886 0.00552529 -0.003999948 -0.05583244 0.00508511 -0.003999948 -0.05583244 0.00508511 0 -0.05582863 0.00492829 -0.003999948 -0.05582863 0.00492829 0 -0.05677491 0.005979239 0 -0.0697571 0.006659567 -0.003999948 -0.05677491 0.005979239 -0.003999948 -0.0697571 0.006659567 0 -0.07074308 0.006019294 0 -0.0707876 0.005868852 -0.003999948 -0.07074308 0.006019294 -0.003999948 -0.07080805 0.005713284 -0.003999948 -0.0707876 0.005868852 0 -0.07080805 0.005713284 0 -0.07058656 0.006290256 -0.003999948 -0.07047855 0.006404042 -0.003999948 -0.07047855 0.006404101 0 -0.07058656 0.006290256 0 -0.07067549 0.006160914 0 -0.07067549 0.006160914 -0.003999948 -0.07006824 0.006626844 0 -0.07021623 0.006574451 -0.003999948 -0.07006824 0.006626844 -0.003999948 -0.07021623 0.006574451 0 -0.0703541 0.006499588 0 -0.0703541 0.006499588 -0.003999948 -0.06991398 0.006655454 -0.003999948 -0.06991398 0.006655454 0 -0.0697571 0.006659567 -0.003999948 -0.0697571 0.006659567 0 -0.07117438 -0.001277089 0 -0.07080805 0.005713284 -0.003999948 -0.07080805 0.005713284 0 -0.07117438 -0.001277089 -0.003999948 -0.07056665 -0.002249836 0 -0.07040065 -0.002303779 -0.003999948 -0.07056647 -0.002249956 -0.003999948 -0.07022809 -0.002328038 -0.003999948 -0.07040089 -0.002303779 0 -0.07022809 -0.002328038 0 -0.07085776 -0.00206077 -0.003999948 -0.07097434 -0.00193125 -0.003999948 -0.07097452 -0.001931071 0 -0.070858 -0.002060592 0 -0.07072061 -0.00216794 0 -0.07072043 -0.002168118 -0.003999948 -0.07113206 -0.001621663 0 -0.07113206 -0.001621782 -0.003999948 -0.0711683 -0.001451253 0 -0.07106685 -0.001783251 0 -0.07106673 -0.00178343 -0.003999948 -0.0711683 -0.001451313 -0.003999948 -0.07117438 -0.001277089 0 -0.07117438 -0.001277089 -0.003999948 -0.1460716 0.002647697 0 -0.1457054 0.009638071 -0.003999948 -0.1457054 0.009638071 0 -0.1460716 0.002647697 -0.003999948 -0.1454639 0.00167495 0 -0.1452979 0.001620948 -0.003999948 -0.1454637 0.00167483 -0.003999948 -0.1451253 0.001596689 -0.003999948 -0.1452981 0.001621007 0 -0.1451253 0.001596689 0 -0.145755 0.001864016 -0.003999948 -0.1458716 0.001993536 -0.003999948 -0.1458718 0.001993715 0 -0.1457552 0.001864194 0 -0.1456179 0.001756846 0 -0.1456177 0.001756668 -0.003999948 -0.1460293 0.002303123 0 -0.1460293 0.002302944 -0.003999948 -0.1460655 0.002473533 0 -0.1459641 0.002141535 0 -0.145964 0.002141356 -0.003999948 -0.1460655 0.002473473 -0.003999948 -0.1460716 0.002647697 0 -0.1460716 0.002647697 -0.003999948 -0.1451253 0.001596689 0 -0.1321431 9.16443e-4 -0.003999948 -0.1451253 0.001596689 -0.003999948 -0.1321431 9.16443e-4 0 -0.1311572 0.001556694 0 -0.1311126 0.001707136 -0.003999948 -0.1311572 0.001556694 -0.003999948 -0.1310922 0.001862704 -0.003999948 -0.1311126 0.001707136 0 -0.1310922 0.001862704 0 -0.1313137 0.001285731 -0.003999948 -0.1314217 0.001171886 -0.003999948 -0.1314217 0.001171886 0 -0.1313137 0.001285731 0 -0.1312248 0.001415073 0 -0.1312248 0.001415073 -0.003999948 -0.131832 9.4915e-4 0 -0.1316841 0.001001477 -0.003999948 -0.131832 9.49149e-4 -0.003999948 -0.1316841 0.001001477 0 -0.1315461 0.0010764 0 -0.1315461 0.0010764 -0.003999948 -0.1319863 9.20553e-4 -0.003999948 -0.1319863 9.20554e-4 0 -0.1321431 9.16443e-4 -0.003999948 -0.1321431 9.16443e-4 0 -0.1310922 0.001862704 -0.003999948 -0.1307259 0.008853137 0 -0.1307259 0.008853137 -0.003999948 -0.1310922 0.001862704 0 -0.1313661 0.009839057 0 -0.1315166 0.009883582 -0.003999948 -0.1313661 0.009839057 -0.003999948 -0.1316722 0.009904086 -0.003999948 -0.1315166 0.009883582 0 -0.1316722 0.009904086 0 -0.1310952 0.009682595 -0.003999948 -0.1309814 0.009574592 -0.003999948 -0.1309814 0.009574592 0 -0.1310952 0.009682595 0 -0.1312245 0.009771466 0 -0.1312245 0.009771466 -0.003999948 -0.1307585 0.009164273 0 -0.130811 0.009312212 -0.003999948 -0.1307585 0.009164273 -0.003999948 -0.130811 0.009312212 0 -0.1308858 0.009450078 0 -0.1308858 0.009450078 -0.003999948 -0.13073 0.009009957 -0.003999948 -0.13073 0.009009957 0 -0.1307259 0.008853137 -0.003999948 -0.1307259 0.008853137 0 -0.1316722 0.009904086 0 -0.1446543 0.01058441 -0.003999948 -0.1316722 0.009904086 -0.003999948 -0.1446543 0.01058441 0 -0.1456403 0.00994414 0 -0.1456848 0.009793639 -0.003999948 -0.1456403 0.00994414 -0.003999948 -0.1457054 0.009638071 -0.003999948 -0.1456848 0.009793639 0 -0.1457054 0.009638071 0 -0.1454838 0.0102151 -0.003999948 -0.1453758 0.01032888 -0.003999948 -0.1453758 0.01032888 0 -0.1454838 0.0102151 0 -0.1455727 0.01008576 0 -0.1455727 0.01008576 -0.003999948 -0.1449655 0.01055169 0 -0.1451134 0.01049929 -0.003999948 -0.1449655 0.01055169 -0.003999948 -0.1451134 0.01049929 0 -0.1452513 0.01042443 0 -0.1452513 0.01042443 -0.003999948 -0.1448112 0.0105803 -0.003999948 -0.1448112 0.0105803 0 -0.1446543 0.01058441 -0.003999948 -0.1446543 0.01058441 0 -0.1194678 -0.005712985 0.01242858 -0.119466 -0.005678832 0.03107786 -0.1189467 0.00423038 0 -0.1194691 -0.005738079 0 -0.119464 -0.005640685 0.05588608 -0.1189467 0.00423038 0.08700001 -0.1194628 -0.005617499 0.07457137 -0.1194621 -0.005604445 0.08700001 -0.1189467 0.00423038 0.08700001 -0.1274504 -0.005171954 0.08700001 -0.1269358 0.004649043 0.08700001 -0.1194621 -0.005604445 0.08700001 -0.1269358 0.004649043 0.08700001 -0.1274501 -0.005165457 0.09872096 -0.1269358 0.004649043 0.11 -0.1274504 -0.005171954 0.08700001 -0.1274499 -0.005162715 0.11 -0.1269358 0.004649043 0.11 -0.1194615 -0.005594193 0.11 -0.1189467 0.00423038 0.11 -0.1274499 -0.005162715 0.11 -0.1194868 -0.006076276 0.207674 -0.1194862 -0.006063401 0.219883 -0.1189467 0.00423038 0.11 -0.1194677 -0.005711317 0.12221 -0.1194615 -0.005594193 0.11 -0.1194866 -0.006072878 0.195465 -0.1194846 -0.006034255 0.232091 -0.1194856 -0.006053268 0.183256 -0.1194822 -0.005988895 0.2443 -0.1194837 -0.006017327 0.171047 -0.119479 -0.005927324 0.256508 -0.119481 -0.005965232 0.158838 -0.1194749 -0.005849421 0.268716 -0.1194774 -0.005896806 0.146629 -0.11947 -0.005755305 0.280925 -0.119473 -0.005812227 0.134419 -0.1194642 -0.005644917 0.293133 -0.1194501 -0.005375444 0.317548 -0.1194576 -0.005518317 0.305341 -0.1194418 -0.00521636 0.329756 -0.1189467 0.00423038 0.4030001 -0.1194325 -0.005040943 0.341964 -0.1194225 -0.004849374 0.354171 -0.1194116 -0.004641473 0.366379 -0.1193999 -0.004417359 0.378586 -0.1193873 -0.004176974 0.390793 -0.1193738 -0.003920376 0.4030001 -0.1044126 -0.005021929 0.4030001 -0.0989741 0.003183782 0.4030001 -0.1049708 0.003498017 0.4030001 -0.1189467 0.00423038 0.4030001 -0.1143906 -0.004343867 0.4030001 -0.1129598 0.00391668 0.4030001 -0.1115167 0.006788015 0.4030001 -0.1061059 0.006504476 0.4030001 -0.1066052 0.006936967 0.4030001 -0.1077818 0.007528245 0.4030001 -0.1084268 0.007670938 0.4030001 -0.1097429 0.007631003 0.4030001 -0.1090865 0.007705509 0.4030001 -0.1103782 0.007449507 0.4030001 -0.107169 0.007281363 0.4030001 -0.1109749 0.007165908 0.4030001 -0.111989 0.006326019 0.4030001 -0.1056844 0.005995631 0.4030001 -0.1123787 0.005792617 0.4030001 -0.1053526 0.005424439 0.4030001 -0.1051192 0.004806399 0.4030001 -0.1126754 0.005202353 0.4030001 -0.1128708 0.004571318 0.4030001 -0.1049908 0.004158377 0.4030001 -0.09941744 -0.00527656 0.4030001 -0.1094036 -0.004711091 0.4030001 -0.1193738 -0.003920376 0.4030001 -0.0989741 0.003183782 0.4030001 -0.09941744 -0.00527656 0.4030001 -0.09941881 -0.005303204 0.39057 -0.09942263 -0.005375742 0.37814 -0.0989741 0.003183782 0.3160001 -0.09942883 -0.005493998 0.365711 -0.09944844 -0.005868017 0.340854 -0.09943741 -0.00565809 0.353282 -0.09947764 -0.006425261 0.3160001 -0.09946185 -0.006123721 0.328427 -0.07590097 0.003977417 0.3160001 -0.08798205 -0.006824076 0.3160001 -0.08223348 -0.006998002 0.3160001 -0.09373015 -0.006633162 0.3160001 -0.09886944 0.005181014 0.3160001 -0.07648432 -0.007155001 0.3160001 -0.09947764 -0.006425261 0.3160001 -0.07590097 0.003977417 0.303 -0.07590097 0.003977417 0.3160001 -0.07648432 -0.007155001 0.3160001 -0.07649296 -0.007319629 0.303 -0.07071048 0.003705441 0.303 -0.07590097 0.003977417 0.303 -0.07649296 -0.007319629 0.303 -0.0712952 -0.007452607 0.303 -0.07071048 0.003705441 0.3010001 -0.07071048 0.003705441 0.303 -0.0712952 -0.007452607 0.303 -0.07129621 -0.007472276 0.3010001 -0.07590097 0.003977417 0.3010001 -0.07071048 0.003705441 0.3010001 -0.07129621 -0.007472276 0.3010001 -0.07649397 -0.007339537 0.3010001 -0.07649749 -0.007405638 0.292996 -0.07590097 0.003977417 0.3010001 -0.07649397 -0.007339537 0.3010001 -0.07590097 0.003977417 0.285 -0.07649987 -0.007451772 0.285 -0.09886944 0.005181014 0.285 -0.08799815 -0.00713104 0.285 -0.09374666 -0.006947755 0.285 -0.08224928 -0.007299005 0.285 -0.07590097 0.003977417 0.285 -0.09949463 -0.006749272 0.285 -0.07649987 -0.007451772 0.285 -0.0989741 0.003183782 0.285 -0.0994932 -0.006722271 0.2666606 -0.099491 -0.006680488 0.2422248 -0.09949463 -0.006749272 0.285 -0.09948849 -0.006632328 0.2177658 -0.09948641 -0.006591737 0.199385 -0.09948408 -0.006548047 0.1810266 -0.0989741 0.003183782 0.126 -0.09948164 -0.006500482 0.162693 -0.09947896 -0.006449699 0.1443438 -0.09947609 -0.006395041 0.126 -0.0989741 0.003183782 0.126 -0.09247791 -0.006613135 0.126 -0.09198373 0.002817451 0.126 -0.09947609 -0.006395041 0.126 -0.09247773 -0.006609499 0.113 -0.09247785 -0.0066123 0.1 -0.09198373 0.002817451 0.126 -0.09247791 -0.006613135 0.126 -0.09198373 0.002817451 0.08700001 -0.09247833 -0.006621479 0.08700001 -0.09198373 0.002817451 0.08700001 -0.09947651 -0.006403148 0.08700001 -0.0989741 0.003183782 0.08700001 -0.09247833 -0.006621479 0.08700001 -0.09947729 -0.006418108 0.07457137 -0.09947872 -0.006444633 0.05592733 -0.0989741 0.003183782 0.08700001 -0.09947651 -0.006403148 0.08700001 -0.09948039 -0.006476879 0.03728568 -0.09897416 0.003183782 0 -0.09948235 -0.006513893 0.01860445 -0.09948456 -0.00655657 0 -0.07634687 0.01804083 0 -0.09915357 0.01896429 0 -0.1004967 0.01895606 0 -0.1018396 0.01894038 0 -0.1031824 0.01891726 0 -0.07367038 0.01781332 0 -0.1321431 9.16443e-4 0 -0.1337963 -0.004858493 0 -0.1309328 -0.005064547 0 -0.08170521 0.01842623 0 -0.09512448 0.01894462 0 -0.080365 0.01833879 0 -0.0978105 0.018965 0 -0.0790252 0.01824533 0 -0.09646749 0.01895838 0 -0.09109622 0.01886016 0 -0.09243881 0.01889538 0 -0.08975374 0.01881808 0 -0.0843867 0.01858258 0 -0.0857281 0.01865118 0 -0.1058678 0.01884806 0 -0.06832361 0.01729309 0 -0.06965953 0.01743113 0 -0.1083312 0.008666932 0 -0.1378966 0.01551282 0 -0.1392145 0.01525402 0 -0.0697571 0.006659567 0 -0.1272846 0.01718598 0 -0.1286164 0.01701194 0 -0.1418428 0.01469868 0 -0.1431526 0.01440095 0 -0.1090772 0.008706033 0 -0.1496405 0.01267248 0 -0.1509227 0.0122711 0 -0.1316722 0.009904086 0 -0.1654129 0.001220762 0 -0.1651126 9.49176e-4 0 -0.1451253 0.001596689 0 -0.1647815 7.16557e-4 0 -0.1660844 0.002660334 0 -0.1454639 0.00167495 0 -0.1456179 0.001756846 0 -0.1395183 -0.004383087 0 -0.1366583 -0.004632294 0 -0.1619318 0.007350802 0 -0.1630322 0.006576418 0 -0.1460716 0.002647697 0 -0.1659278 0.003447115 0 -0.1460655 0.002473533 0 -0.1625303 -3.07552e-4 0 -0.1615631 -6.77273e-4 0 -0.1138637 0.004710614 0 -0.1136592 0.005429744 0 -0.1189467 0.00423038 0 -0.1165958 0.0182687 0 -0.1179346 0.01816183 0 -0.05499446 0.01564931 0 -0.1537559 -0.002587556 0 -0.1509228 -0.003051996 0 -0.1139585 0.003968954 0 -0.1656692 0.001533687 0 -0.1452303 -0.003799676 0 -0.142376 -0.004107117 0 -0.1605848 -0.001016438 0 -0.1634877 8.6559e-5 0 -0.1644297 5.16171e-4 0 -0.1595944 -0.001318395 0 -0.1452981 0.001621007 0 -0.1658736 0.001883089 0 -0.14808 -0.003451764 0 -0.1660172 0.002261281 0 -0.1280682 -0.005253255 0 -0.1252025 -0.005427122 0 -0.1458718 0.001993715 0 -0.1457552 0.001864194 0 -0.1459641 0.002141535 0 -0.1460293 0.002303123 0 -0.1660531 0.003063082 0 -0.1655063 0.004136264 0 -0.1657369 0.003803789 0 -0.1649876 0.004757642 0 -0.1652526 0.004451692 0 -0.1640436 0.005706906 0 -0.1457054 0.009638071 0 -0.1596163 0.008721113 0 -0.1607914 0.008065223 0 -0.1456848 0.009793639 0 -0.1559691 0.01043003 0 -0.1453758 0.01032888 0 -0.1452513 0.01042443 0 -0.1547245 0.01093178 0 -0.1534656 0.01140224 0 -0.1451134 0.01049929 0 -0.1449655 0.01055169 0 -0.11335 0.00611037 0 -0.1307259 0.008853137 0 -0.1448112 0.0105803 0 -0.1129427 0.006737172 0 -0.1124466 0.007296264 0 -0.1446543 0.01058441 0 -0.1521989 0.01184946 0 -0.1118727 0.007775008 0 -0.1483522 0.01305299 0 -0.1309814 0.009574592 0 -0.1105448 0.008451163 0 -0.1310952 0.009682595 0 -0.147059 0.01341521 0 -0.1313661 0.009839057 0 -0.1098205 0.008633553 0 -0.1315166 0.009883582 0 -0.145761 0.01375985 0 -0.1444587 0.01408785 0 -0.1405303 0.01498341 0 -0.1365762 0.01575934 0 -0.1352539 0.01599454 0 -0.1339296 0.01621866 0 -0.1326035 0.01643198 0 -0.131276 0.01663517 0 -0.1299468 0.01682829 0 -0.1259517 0.01735103 0 -0.05765599 0.01601392 0 -0.05898761 0.01618987 0 -0.1152564 0.01836764 0 -0.05366545 0.01546114 0 -0.1192728 0.01804715 0 -0.05233573 0.0152688 0 -0.06565338 0.01700186 0 -0.06698817 0.01715004 0 -0.108552 0.01874858 0 -0.06165254 0.01652854 0 -0.06298488 0.01669108 0 -0.111235 0.01861882 0 -0.07500845 0.01792991 0 -0.07233291 0.01769137 0 -0.07099598 0.01756381 0 -0.08304584 0.01850754 0 -0.07768577 0.01814603 0 -0.08706963 0.01871347 0 -0.09378159 0.01892352 0 -0.08841156 0.01876908 0 -0.1045252 0.01888644 0 -0.10721 0.01880204 0 -0.06431943 0.01684886 0 -0.1098937 0.01868742 0 -0.112576 0.0185427 0 -0.06031948 0.01636147 0 -0.1139165 0.01845902 0 -0.05632561 0.01583373 0 -0.1206102 0.01792436 0 -0.05100715 0.015073 0 -0.1219469 0.01779365 0 -0.04967874 0.01487332 0 -0.04835158 0.01467037 0 -0.1232828 0.01765459 0 -0.1246178 0.01750701 0 -0.04702454 0.01446396 0 -0.04569768 0.01425433 0 -0.04375994 0.01394277 0 -0.0328527 0.01208406 0 -0.05677491 0.005979239 0 -0.04113703 0.01351082 0 -0.03907275 0.0131632 0 -0.02664065 0.01096594 0 -0.02974647 0.01152932 0 -0.01733267 0.009232282 0 -0.01423227 0.008642375 0 -0.02043431 0.009816586 0 -0.02353733 0.01039475 0 -0.004936516 0.006845772 0 -0.008034229 0.007448613 0 -0.05661976 0.005958795 0 -0.01113313 0.008047699 0 -5.10043e-4 0.005978643 0 -0.05632728 0.005846679 0 -0.001059591 0.002806603 0 -5.82859e-4 0.002942681 0 -0.0564689 0.005914211 0 -0.06991398 0.006655454 0 -0.05619776 0.005757749 0 -0.001507341 0.002593934 0 -0.0559886 0.00552529 0 -0.05591374 0.005387365 0 -0.05608421 0.005649745 0 0.005876064 0.004716813 0 -9.02563e-5 0.00299853 0 4.0406e-4 0.002972662 0 0.01203018 0.003490447 0 0.001347064 0.00268048 0 0.01780956 0.002331078 0 8.88139e-4 0.002865612 0 0.001770079 0.002422153 0 -0.1075987 0.008516907 0 -0.07058656 0.006290256 0 -0.07047855 0.006404101 0 -0.1062413 0.007900059 0 -0.002929151 6.47951e-4 0 -0.05582863 0.00492829 0 -0.002995908 1.56994e-4 0 0.002144634 0.002097785 0 0.002461075 0.001716196 0 0.01010185 1.73284e-4 0 0.02403932 0.001075565 0 0.002710044 0.001287758 0 -0.1043527 0.005636751 0 -0.1041167 0.004927992 0 -0.07080805 0.005713284 0 0.01026314 1.36384e-4 0 0.03022319 -1.73415e-4 0 -0.103989 0.004193127 0 -0.09897416 0.003183782 0 0.008962213 -7.64393e-4 0 0.002560555 -0.001564323 0 0.002267241 -0.00196439 0 0.002884984 8.24251e-4 0 0.002980709 3.38256e-4 0 0.009611368 1.20447e-4 0 0.008718311 -0.005419194 0 9.0152e-5 -0.00299859 0 -4.04179e-4 -0.002972483 0 0.008722841 -0.005580425 0 0.008753597 -0.005738794 0 0.0435965 -0.0096035 0 0.05630993 -0.009803473 0 0.0256676 -0.006391942 0 -0.05693477 -0.002975642 0 -0.0295391 -0.0082286 0 -0.01999294 -0.008430063 0 0.02552551 -0.006485521 0 0.001059472 -0.002806901 0 5.8274e-4 -0.00294286 0 0.02537071 -0.006553888 0 0.02520632 -0.006595134 0 0.0250374 -0.006608009 0 0.03089696 -0.009392201 0 0.06925284 -0.008235812 0 0.06620472 -0.007565319 0 0.06896346 -0.00999099 0 0.07243233 -0.008920848 0 0.0754171 -0.009557962 0 0.0631352 -0.006902992 0 0.07856774 -0.01012539 0 0.008887529 -0.006030678 0 0.008988022 -0.006156623 0 0.00970757 -0.006471455 0 0.02133339 -0.009225189 0 0.001507222 -0.002594292 0 0.02579081 -0.006275773 0 0.02597004 -0.005989849 0 0.02602159 -0.005828261 0 0.001913607 -0.002310872 0 -0.05678683 -0.00292325 0 -0.05664873 -0.002848386 0 -0.05641645 -0.002639055 0 0.008808732 -0.00589019 0 0.002783 -0.00112152 0 -0.05632758 -0.002509713 0 0.009936094 1.83e-4 0 -0.00270909 -0.001287221 0 -0.002884089 -8.23843e-4 0 -0.1039722 0.003445684 0 -0.05724591 -0.003008365 0 -0.06450998 -0.007436692 0 -0.05183285 -0.007734 0 -8.88228e-4 -0.002865314 0 -0.001348137 -0.002679944 0 -0.05619496 -0.002062082 0 -0.07723081 -0.007126808 0 -0.07022809 -0.002328038 0 -0.07072061 -0.00216794 0 -0.070858 -0.002060592 0 -0.08992749 -0.006806015 0 -0.07040089 -0.002303779 0 -0.09948456 -0.00655657 0 -0.07106685 -0.001783251 0 -0.07097452 -0.001931071 0 -0.07113206 -0.001621663 0 -0.0711683 -0.001451253 0 -0.07117438 -0.001277089 0 -0.05626004 -0.002368092 0 -0.001770198 -0.002421557 0 -0.05652457 -0.00275284 0 0.002929031 -6.48091e-4 0 -0.03912025 -0.008020579 0 0.02589303 -0.00614047 0 -0.0570895 -0.003004252 0 0.05384945 -0.00497353 0 0.02576416 -0.004911959 0 0.05693948 -0.005607426 0 0.03860133 -0.00187081 0 0.002995789 -1.56992e-4 0 -0.05586141 0.005239427 0 -0.05583244 0.00508511 0 -0.001913726 0.002310454 0 -0.07006824 0.006626844 0 -0.00226736 0.001963973 0 -0.1051263 0.006910562 0 -0.1056467 0.007447063 0 -0.1046918 0.006302595 0 -0.002782166 0.001121222 0 -0.002980828 -3.38395e-4 0 0.02534908 -0.004654943 0 0.0117371 -0.00905168 0 0.009547114 -0.00645703 0 -9.24746e-4 -0.008812248 0 0.009108543 -0.006264865 0 -0.01046264 -0.008623957 0 0.00939095 -0.006416976 0 0.00924319 -0.006352365 0 0.06003612 -0.006249666 0 0.02604538 -0.005660414 0 0.02603995 -0.005496203 0 0.02600836 -0.005335032 0 0.02595037 -0.005181193 0 0.02586871 -0.005038917 0 0.02564066 -0.004803836 0 0.02550101 -0.004717409 0 0.04936295 -0.004058361 0 0.009461522 4.98944e-5 0 0.009771943 1.65176e-4 0 0.009206175 -1.60061e-4 0 0.009325385 -4.44816e-5 0 0.009108006 -2.93709e-4 0 0.008984863 -6.00112e-4 0 0.009034156 -4.41787e-4 0 -0.002559721 0.001563906 0 -0.07056665 -0.002249836 0 -0.0562151 -0.00221765 0 -0.002144753 -0.002097129 0 -0.002461194 -0.001715481 0 -0.1068968 0.008259356 0 -0.03596144 0.01262909 0 -0.0703541 0.006499588 0 -0.07021623 0.006574451 0 -0.07067549 0.006160914 0 -0.07074308 0.006019294 0 -0.0707876 0.005868852 0 -0.1307585 0.009164273 0 -0.111234 0.008162856 0 -0.130811 0.009312212 0 -0.13073 0.009009957 0 -0.1454838 0.0102151 0 -0.1455727 0.01008576 0 -0.1456403 0.00994414 0 -0.1572011 0.009899199 0 -0.1584172 0.009330391 0 -0.1310922 0.001862704 0 -0.1315461 0.0010764 0 -0.1316841 0.001001477 0 -0.1194691 -0.005738079 0 -0.1575873 -0.001827955 0 -0.1585943 -0.001586675 0 -0.1565755 -0.002047836 0 -0.1223361 -0.005588233 0 -0.131832 9.4915e-4 0 -0.1319863 9.20554e-4 0 -0.1314217 0.001171886 0 -0.1312248 0.001415073 0 -0.1313137 0.001285731 0 -0.1311126 0.001707136 0 -0.1311572 0.001556694 0 -0.1308858 0.009450078 0 -0.1312245 0.009771466 0 0.05308437 -0.009733259 0.43 0.05798041 -0.009803235 0.43 0.05841958 -0.006699085 0.43 0.03721529 -0.009433686 0.43 0.04270184 -0.009548485 0.43 0.04427933 -0.003795027 0.43 0.05009108 -0.004983127 0.43 0.04799079 -0.009648323 0.43 0.03153228 -0.009303927 0.43 0.04028213 -0.002981483 0.43 0.05416858 -0.005821287 0.43 0.03600245 -0.002113759 0.43 0.0319519 -0.001296162 0.43 0.06397318 -0.007852256 0.43 0.06300592 -0.009848952 0.43 0.06824207 -0.009867966 0.43 0.06951361 -0.009010195 0.43 0.0735746 -0.009863674 0.43 0.03152346 -0.009472906 0.3648509 0.03152614 -0.009421527 0.3885209 0.03196966 -9.58217e-4 0.3874814 0.03197842 -7.90192e-4 0.3607019 0.03197568 -8.42568e-4 0.3696624 0.03197276 -8.98594e-4 0.378589 0.03196543 -0.001038551 0.3986878 0.03195995 -0.001143336 0.4121468 0.03152942 -0.009358882 0.4121997 0.03195506 -0.001237034 0.4233052 0.03153228 -0.009303927 0.43 0.0319519 -0.001296162 0.43 0.03152179 -0.009503722 0.34706 0.03198099 -7.41875e-4 0.3517745 0.03152048 -0.009528815 0.3292691 0.03198331 -6.97198e-4 0.3428078 0.03198546 -6.56425e-4 0.333844 0.03198736 -6.19608e-4 0.3249018 0.03151929 -0.009551882 0.3055589 0.03198951 -5.78882e-4 0.3137468 0.0319913 -5.44569e-4 0.3025958 0.03151869 -0.009563624 0.2818712 0.03199255 -5.21168e-4 0.2936335 0.03199356 -5.01679e-4 0.2846828 0.0319944 -4.86047e-4 0.2757399 0.03151863 -0.009564638 0.264109 0.03199499 -4.74258e-4 0.2667747 0.03199541 -4.66372e-4 0.2578543 0.03151887 -0.009559988 0.2463499 0.03199565 -4.61699e-4 0.2467079 0.03199553 -4.63444e-4 0.2355064 0.03151947 -0.009548187 0.2285559 0.03199523 -4.69014e-4 0.2265641 0.03199476 -4.78456e-4 0.2176041 0.03152036 -0.009530782 0.2107663 0.03199404 -4.91749e-4 0.2086616 0.03199315 -5.08796e-4 0.199761 0.03199237 -5.24417e-4 0.193 0.03152167 -0.009506285 0.193 0.03000718 2.76081e-4 0.3966267 0.03001052 3.41562e-4 0.3921691 0.03000277 8.73733e-5 0.4055591 0.03196364 -0.001072883 0.403177 0.03196179 -0.001107692 0.407647 0.03196543 -0.001039028 0.398706 0.03000456 1.91785e-4 0.4010831 0.03195995 -0.001143455 0.412118 0.03000545 -3.995e-5 0.4100098 0.03002518 -5.65749e-4 0.4234254 0.03001379 -3.63973e-4 0.4189527 0.03195601 -0.001217842 0.421059 0.03195798 -0.001180171 0.416589 0.03195399 -0.001256525 0.42553 0.0319668 -0.00100106 0.393422 0.03257602 -0.002135336 0.4413661 0.03713715 -0.004581332 0.46379 0.03434538 -0.003727912 0.4593086 0.06303745 -0.008903026 0.522314 0.06116926 -0.008762061 0.5209519 0.06356722 -0.009322822 0.5200849 0.03750151 -0.005502581 0.4816331 0.03435468 -0.00471121 0.4771832 0.06407463 -0.00971049 0.517848 0.06456363 -0.01006728 0.5156049 0.06207835 -0.00949186 0.5166599 0.06503421 -0.01039332 0.5133559 0.06291949 -0.01010322 0.512345 0.06369739 -0.0106036 0.5080099 0.06591546 -0.01094669 0.5088399 0.06548261 -0.01068347 0.511101 0.06633168 -0.01118296 0.5065739 0.06441456 -0.01100057 0.503654 0.06710958 -0.0115686 0.502026 0.06672942 -0.01138979 0.5043029 0.06507676 -0.01130181 0.49928 0.06747591 -0.01172435 0.499745 0.06816041 -0.01196223 0.495169 0.06782644 -0.01185697 0.49746 0.06568443 -0.0115146 0.494889 0.06848144 -0.01204675 0.492874 0.06624329 -0.01164668 0.490483 0.06908249 -0.01215678 0.488273 0.0687884 -0.01211202 0.490575 0.06936168 -0.01217937 0.485966 0.06963068 -0.01218658 0.483656 0.06675589 -0.01170557 0.486062 0.06988745 -0.01217842 0.481343 0.06722491 -0.01169872 0.481628 0.07013219 -0.01215142 0.479027 0.06765592 -0.01163375 0.477183 0.03245842 -0.003007888 0.4542974 0.03288441 -0.002524554 0.4461174 0.07036566 -0.01210981 0.476707 0.07058978 -0.0120567 0.474385 0.06804949 -0.01151812 0.472727 0.07080447 -0.01199209 0.472061 0.07100796 -0.01191091 0.469734 0.06841129 -0.01135945 0.468262 0.07120388 -0.01182216 0.467404 0.07139319 -0.01172578 0.465074 0.06566476 -0.01051533 0.4638484 0.06568646 -0.01016342 0.4583299 0.06920558 -0.01083296 0.4571396 0.07207238 -0.01126235 0.455733 0.06874489 -0.01116532 0.46379 0.07157301 -0.01161921 0.462741 0.07174527 -0.01150405 0.460406 0.07191175 -0.01138514 0.45807 0.07237553 -0.01099938 0.451056 0.0722264 -0.01113158 0.453395 0.07266181 -0.01073396 0.446376 0.07252067 -0.01086723 0.448716 0.05362164 -0.006115555 0.4368749 0.07003581 -0.009978711 0.4423413 0.07286119 -0.01053416 0.4429226 0.06468856 -0.01100558 0.4772158 0.06502133 -0.01087695 0.4727585 0.07306969 -0.01033174 0.4392541 0.07333832 -0.0100786 0.4344021 0.07032698 -0.009676754 0.436874 0.07055336 -0.00944513 0.432387 0.07357448 -0.00986427 0.4299999 0.06766647 -0.008832991 0.432387 0.06803488 -0.008700728 0.43 0.07841575 -0.01002043 0.1614897 0.074979 -0.009368479 0.1586487 0.03001511 3.89102e-4 0.3877309 0.03197336 -8.95793e-4 0.3783277 0.03002297 4.38332e-4 0.3788668 0.03001964 4.20769e-4 0.3832747 0.03002852 4.40901e-4 0.3743662 0.03002834 4.35202e-4 0.3699942 0.03197497 -8.56246e-4 0.37188 0.03003442 4.13842e-4 0.3654801 0.0319764 -8.29153e-4 0.367409 0.03197777 -8.0302e-4 0.362938 0.03003132 3.87617e-4 0.3610584 0.03003358 3.49249e-4 0.3565739 0.03197908 -7.77855e-4 0.358467 0.03198033 -7.53658e-4 0.353996 0.03002995 3.06757e-4 0.3521252 -0.06450045 0.01696288 0.03362166 -0.1564137 0.01030206 0.004358291 -0.153185 0.01155561 0.0044353 -0.153627 0.01164412 0.026636 -0.0817843 0.01855784 0.03630763 -0.07818996 0.01827359 0.02663683 -0.07507038 0.01809412 0.0523976 -0.06801253 0.01737254 0.03947532 -0.05434966 0.01566922 0.04708665 -0.06110286 0.01655805 0.03749775 -0.05793917 0.0161978 0.06306684 -0.06143003 0.01666325 0.06799513 -0.05762791 0.01609528 0.03368943 -0.05093717 0.01517164 0.04861426 -0.07474452 0.01799362 0.02695465 -0.07142001 0.0177136 0.03607875 -0.04408031 0.01409602 0.04855936 -0.04066061 0.01352918 0.04844963 -0.04747581 0.0146352 0.04641264 -0.03381955 0.01234704 0.04759758 -0.03054976 0.01179057 0.06629782 -0.04092329 0.01361989 0.08109885 -0.02713459 0.01117092 0.06629782 -0.0203095 0.009904801 0.06629782 -0.01673614 0.009197235 0.0425691 -0.0134896 0.008609533 0.06629782 -0.006666243 0.007288694 0.06462621 -0.01012802 0.007970809 0.0735411 0.005203545 0.004963338 0.0735411 0.01201361 0.0036062 0.0735411 0.05109739 -0.004284203 0.09527283 0.05449753 -0.004978895 0.09527283 0.04599261 -0.003245532 0.094437 0.05790513 -0.005684256 0.08600181 0.06133508 -0.006405115 0.08109259 0.06473088 -0.007129549 0.08116823 0.04859757 -0.003791809 0.0735411 0.06814938 -0.007902264 0.05905461 0.06808793 -0.007864773 0.0824564 0.07495695 -0.009357213 0.06411886 0.07832998 -0.009961247 0.06729954 0.05457204 -0.00501883 0.06629782 0.07834726 -0.009973108 0.05839002 0.0783742 -0.009992063 0.04709911 0.07846045 -0.01005154 0.02243006 0.07520645 -0.009500503 0.005072832 0.0784896 -0.01007157 0.01571291 0.07156413 -0.008636236 0.1539871 0.07492262 -0.009326875 0.1349704 0.07844096 -0.01003777 0.1683096 0.07506459 -0.009423077 0.176155 0.0784682 -0.01005679 0.175037 0.07850813 -0.0100845 0.1838943 0.07512646 -0.009467422 0.187254 0.07853102 -0.0100997 0.1885089 0.07509875 -0.009392201 0.193 0.07836216 -0.00998342 0.1437067 0.07838702 -0.01000052 0.1525859 0.07834625 -0.009972453 0.1368963 0.07116794 -0.008527278 0.1291854 0.0783329 -0.009963393 0.1301379 0.07831799 -0.009952902 0.1202213 0.07830542 -0.009944677 0.1059495 0.07490164 -0.009315311 0.1086846 0.07830482 -0.009943902 0.09432005 0.07491713 -0.009326815 0.08857417 0.07830917 -0.009946882 0.08433789 0.07832008 -0.009954273 0.07403153 0.07506847 -0.009428501 0.0307064 0.07842218 -0.01002496 0.03231084 0.07852202 -0.01009446 0.008809924 0.07189661 -0.008806645 0 0.0754171 -0.009557962 0 0.07856774 -0.01012539 0 0.03642457 -0.001428842 0 0.07158231 -0.008650124 0.05728572 -0.0852254 0.01875495 0.03492712 -0.07852548 0.01837551 0.05222254 -0.0886867 0.01891481 0.03485858 -0.09202539 0.0189954 0.02680003 -0.1025167 0.01908737 0.03325808 -0.09905546 0.01911598 0.03359472 -0.09565341 0.01911199 0.03765225 -0.105983 0.01901161 0.03360718 -0.1094447 0.0188834 0.03346812 -0.1089653 0.01875412 0.004402816 -0.1163637 0.01847869 0.03364396 -0.1129053 0.01870584 0.03350132 -0.1279978 0.01709473 0 -0.1261908 0.01735162 0.004367828 -0.1330386 0.01639622 0.004434287 -0.1198143 0.01819831 0.03341436 -0.1232613 0.01786547 0.03331184 -0.115869 0.01834934 0.004425883 -0.1451673 0.01391357 0 -0.1430265 0.01443207 0 -0.1465752 0.0135886 0.004448413 -0.122757 0.01773875 0.004411041 -0.1300482 0.01700872 0.02810513 -0.1345998 0.01610743 0 -0.1335464 0.01651507 0.03206551 -0.1490654 0.0128476 0 -0.147059 0.01341521 0 -0.1499013 0.01263886 0.004409134 -0.1295144 0.01689034 0 -0.1368895 0.01591938 0.02820593 -0.1403889 0.01528596 0.03358131 -0.1398448 0.01516306 0.00440675 -0.1363151 0.01580828 0 -0.1411148 0.01485925 0 -0.1470071 0.01368063 0.02670621 -0.1516909 0.01202237 0 -0.1547245 0.01093178 0 -0.1534656 0.01140224 0 -0.1559691 0.01043003 0 -0.1595394 0.008831977 0.004372298 -0.1628591 0.007113516 0.02130126 -0.1625118 0.007050812 0.004452705 -0.1596163 0.008721113 0 -0.1584172 0.009330391 0 -0.1652742 0.004805982 0.01358246 -0.1619318 0.007350802 0 -0.1607914 0.008065223 0 -0.1650703 0.00477159 0.003876864 -0.1630322 0.006576418 0 -0.1640436 0.005706906 0 -0.1649876 0.004757642 0 -0.02385067 0.01058912 0.08616334 -0.01701682 0.009305238 0.08601993 -0.03724884 0.01294887 0.04932755 0.003631591 0.005248904 0.05236876 0.01882308 0.00223869 0.07326251 0.007033646 0.004573822 0.05236876 0.01457005 0.003112018 0.0932852 0.03240317 -4.94816e-4 0.0824564 0.02558034 8.88072e-4 0.08691424 0.03922432 -0.001881897 0.07799869 0.04002988 -0.002032876 0.09583008 0.03545188 -0.001098275 0.117931 0.03238487 -4.86423e-4 0.1348437 0.04048585 -0.002134084 0.1398606 0.03244525 -5.14223e-4 0.1493375 0.02559638 8.80974e-4 0.1404179 0.02555245 9.00441e-4 0.1259254 0.03256589 -5.69686e-4 0.1671787 0.02569717 8.36404e-4 0.1582577 0.03314137 -7.25404e-4 0.1827926 0.03199237 -5.24368e-4 0.193 0.03199291 -5.13921e-4 0.1974729 0.02833777 2.07766e-4 0.1955206 0.0280292 2.14139e-4 0.2095665 0.02794528 2.48812e-4 0.2051029 0.03199386 -4.95805e-4 0.2064189 0.03199338 -5.04373e-4 0.201946 0.03199422 -4.88195e-4 0.210891 0.03199458 -4.81544e-4 0.2153639 0.02809894 1.81618e-4 0.214028 0.0278728 2.80745e-4 0.200641 0.02818024 1.46986e-4 0.218491 0.03199487 -4.75861e-4 0.219837 0.03199511 -4.71147e-4 0.2243099 0.02826875 1.11417e-4 0.2229525 0.02837288 7.38975e-5 0.2274049 0.03199535 -4.67392e-4 0.2287819 0.02844166 4.22562e-5 0.2318757 0.03199547 -4.64605e-4 0.233255 0.0285294 8.73234e-6 0.2363365 0.03199559 -4.62777e-4 0.2377269 0.02866357 -3.9204e-5 0.2428425 0.03199565 -4.61585e-4 0.244214 0.02883964 -9.75122e-5 0.2517232 0.03199553 -4.63409e-4 0.2529214 0.02901226 -1.46871e-4 0.2605723 0.03199529 -4.6867e-4 0.2613079 0.02918809 -1.86436e-4 0.2698273 0.03199398 -4.9361e-4 0.2810505 0.02936136 -2.11855e-4 0.2789815 0.02951604 -2.19448e-4 0.2880445 0.03199332 -5.06314e-4 0.286922 0.03199279 -5.1605e-4 0.291394 0.02960896 -2.11267e-4 0.2942928 0.03199225 -5.26755e-4 0.295866 0.02967381 -2.0012e-4 0.2987498 0.0319916 -5.38428e-4 0.300337 0.0298103 -1.64373e-4 0.3076214 0.02973365 -1.83297e-4 0.3032005 0.03199094 -5.51061e-4 0.304809 0.03199023 -5.64662e-4 0.309281 0.03198951 -5.79221e-4 0.313753 0.0298298 -1.2969e-4 0.3120931 0.03198868 -5.94749e-4 0.318224 0.02986705 -9.2463e-5 0.3165507 0.02990782 -5.08478e-5 0.3210003 0.03198778 -6.11236e-4 0.322696 0.03198689 -6.28692e-4 0.327167 0.02993929 -3.63877e-6 0.3254473 0.02996671 4.70699e-5 0.3298929 0.03198593 -6.47107e-4 0.331639 0.02998816 9.99613e-5 0.3343382 0.03198492 -6.6649e-4 0.33611 0.03000515 1.5374e-4 0.3387826 0.03198385 -6.86831e-4 0.340582 0.03001809 2.06834e-4 0.3432271 0.03002673 2.57944e-4 0.3476724 0.03198271 -7.08142e-4 0.345053 0.03198158 -7.3042e-4 0.349524 0.03000944 -1.90075e-4 0.4144781 -0.002732872 0.002494513 0.4816311 -0.004821777 0.00278306 0.4860643 -0.007990002 0.003487169 0.4816323 0.001911997 0.001759529 0.4771857 0.006904661 9.83409e-4 0.472734 0.03222984 -0.001491189 0.432387 0.0196861 -7.71234e-4 0.4593101 0.01480776 -8.19666e-5 0.4637925 0.01229614 1.53464e-4 0.468268 0.01851785 -0.001320004 0.4727244 0.02232021 -0.001850485 0.4682657 0.034303 -0.004269421 0.4682624 0.02245694 -0.002309381 0.4771859 0.03410917 -0.004463374 0.4727254 0.04678916 -0.007235944 0.4771806 0.03746223 -0.005646288 0.490485 0.04160326 -0.006439268 0.4860637 0.03612965 -0.005360662 0.4948887 0.03470224 -0.004984021 0.4992808 0.05105108 -0.008394956 0.4948901 0.0522058 -0.008648753 0.4904778 0.06018447 -0.007911026 0.5252149 0.06248044 -0.008449196 0.524532 0.0612964 -0.007444083 0.5289419 0.05910146 -0.006946086 0.5294349 0.06190013 -0.007962882 0.526741 0.06064909 -0.006898939 0.53112 0.05996209 -0.0063259 0.533279 0.05789583 -0.005875587 0.533594 0.05654406 -0.004708111 0.537675 0.05924159 -0.005723953 0.535421 0.0584805 -0.005094528 0.537544 0.05678945 -0.003771066 0.541696 0.05502277 -0.003452003 0.541661 0.05765938 -0.004445195 0.539632 0.05587279 -0.003072202 0.543734 0.05489403 -0.002353966 0.545736 0.05330729 -0.002115845 0.5455369 0.05137431 -7.08105e-4 0.5492839 0.05384612 -0.001617848 0.5476989 0.05273818 -8.61296e-4 0.5496289 0.05031675 7.03014e-4 0.5533679 0.04920035 7.62809e-4 0.552887 0.05157124 -8.42456e-5 0.5515249 0.04898995 0.001506268 0.5551689 0.04759091 0.002325654 0.556927 0.04647707 0.002358555 0.5563785 0.04381585 0.003899931 0.5596008 0.04612118 0.003152668 0.5586339 0.04457813 0.003975868 0.5602779 0.04127764 0.005639135 0.5634049 0.03839677 0.006738185 0.5650832 0.04296433 0.004804611 0.561868 0.03954273 0.00644946 0.5648649 0.03775274 0.007242798 0.566253 0.03446948 0.008431077 0.5679815 0.03590416 0.00802493 0.567573 0.03400158 0.0087893 0.568821 0.03100764 0.009792685 0.5702461 0.03206843 0.009506046 0.569973 0.03009074 0.0101943 0.571043 0.06902921 -0.008184671 0 0.05413216 -0.005030691 0 0.05804467 -0.005759418 0.04679739 0.07130348 -0.008561432 0.086515 0.07149404 -0.008593082 0.1055819 0.06486678 -0.007202208 0.1686018 0.06469064 -0.00713557 0.1528264 0.07166486 -0.008700251 0.1749852 0.07172393 -0.008745849 0.1872805 0.07855325 -0.01011556 0.193 0.06474173 -0.008196771 0.432387 0.06520527 -0.008108854 0.43 0.06681042 -0.009305596 0.4425073 0.06709843 -0.008987247 0.4368058 0.06654715 -0.01010894 0.454828 0.06536495 -0.0107153 0.4683055 0.06428033 -0.01107454 0.4816507 0.06385749 -0.01109099 0.4860813 0.05869704 -0.008236289 0.5209597 0.0595591 -0.008956253 0.5166707 0.06339532 -0.01104247 0.4905023 0.06287193 -0.01091766 0.4949051 0.06231313 -0.01071512 0.4992934 0.06171172 -0.0104264 0.5036678 0.06103104 -0.01003718 0.5080212 0.06031399 -0.009549558 0.5123541 0.05780941 -0.007405519 0.5252247 0.05678844 -0.006453633 0.5294436 0.05567109 -0.005401253 0.5336046 0.05441558 -0.004254221 0.5376844 0.05301082 -0.003022313 0.5416725 0.02736043 0.01103001 0.5721858 0.05141764 -0.001711785 0.5455492 0.04961168 -3.30508e-4 0.5492975 0.02601557 0.01146399 0.572924 0.02806746 0.01085418 0.572033 0.04755258 0.001115441 0.5528975 0.02357864 0.01210683 0.5737816 0.02394068 0.01201736 0.573711 0.03710049 0.007078945 0.5652984 0.01969665 0.01298707 0.5750001 0.02183437 0.01252496 0.574403 0.06505662 -0.007314622 0 0.06822532 -0.007948577 0.03732609 0.06805771 -0.007846415 0.117565 0.06471252 -0.007116854 0.129726 0.06831902 -0.00800383 0.1874302 0.06859368 -0.00803107 0.193 0.06189054 -0.007572233 0.432387 0.05273693 -0.007753551 0.4637989 0.05292093 -0.007505178 0.4593234 0.03536629 0.007426977 0.5651929 0.02274119 0.01228815 0.5737823 0.06192159 -0.006644606 0 0.06482923 -0.007187545 0.04877114 0.04865115 -0.003819286 0.05905449 0.05468904 -0.005081593 0.03788328 0.06470257 -0.007111907 0.1064185 0.0613377 -0.006406724 0.1429898 0.06503373 -0.007284641 0.1872381 0.0652703 -0.007339358 0.193 0.05952453 -0.006928563 0.43 0.06156027 -0.00815916 0.442527 0.06052124 -0.007558524 0.4369022 0.06076288 -0.0090667 0.4580292 0.05936503 -0.00913614 0.4637709 0.05915611 -0.009356677 0.4682343 0.05884325 -0.009527087 0.4727169 0.05856925 -0.009668767 0.4771714 0.05828034 -0.009764254 0.4816134 0.05503416 -0.008398771 0.5123391 0.0565871 -0.009066462 0.5080099 0.05791723 -0.009794414 0.4860523 0.05751669 -0.009759962 0.4904758 0.05710732 -0.009660184 0.4948806 0.0576694 -0.009700477 0.49928 0.05715084 -0.00943017 0.503654 0.05438119 -0.007828235 0.5166559 0.05459171 -0.007339894 0.5209519 0.05380988 -0.006532847 0.5252149 0.05208444 -0.005429744 0.5294308 0.05197769 -0.004596173 0.533594 0.05088436 -0.003484487 0.537675 0.04887837 -0.00212413 0.541659 0.04753899 -8.70591e-4 0.5455298 0.02906483 0.01021695 0.5702581 0.04597079 4.59661e-4 0.549282 0.04371017 0.001949071 0.5528867 0.02597403 0.01133191 0.5721924 0.04179531 0.003359317 0.556322 0.03959882 0.004812598 0.559589 0.0581969 -0.005866765 0 0.06145614 -0.006477117 0.04189735 0.06129634 -0.006382822 0.1119664 0.06144833 -0.006469905 0.1671787 0.05801969 -0.005743443 0.1629403 0.06159448 -0.006548464 0.1865045 0.06172358 -0.006603121 0.193 0.05899983 -0.006955623 0.432387 0.05872893 -0.00755304 0.4425017 0.05797529 -0.008471667 0.4580209 0.05339711 -0.008387982 0.5080023 0.05433458 -0.008990943 0.4992712 0.05386036 -0.008730173 0.5036479 0.05163049 -0.00671029 0.5209472 0.05096566 -0.005928635 0.5252074 0.04933059 -0.004034042 0.5335873 0.04831987 -0.002939999 0.5376696 0.03191286 0.008991479 0.5679991 0.05788862 -0.005673229 0.117565 0.05792403 -0.00569278 0.1398606 0.05457258 -0.005019068 0.1532401 0.05705785 -0.005601704 0.1863242 0.05296206 -0.00471872 0.1688514 0.05457568 -0.006042778 0.4325339 0.05088204 -0.005144774 0.43 0.05589556 -0.006958186 0.4424619 0.05308914 -0.007238388 0.4548527 0.05404025 -0.008285284 0.4682374 0.05239999 -0.008181989 0.4727314 0.0535764 -0.008623003 0.477167 0.05278909 -0.008615374 0.4816198 0.05301588 -0.008767962 0.4860526 0.04917854 -0.007175505 0.5123462 0.05010485 -0.006932616 0.5166566 0.04829847 -0.0046373 0.5294279 0.04555994 -0.001430571 0.5416536 0.04326689 2.4091e-5 0.5455403 0.04212361 0.001264631 0.549288 0.003320217 0.005224108 0 0.04619961 -0.003349483 0.03871893 0.03942692 -0.001978993 0.03509765 0.05278968 -0.004622936 0.1139425 0.05380588 -0.004845917 0.142827 0.04902029 -0.003981888 0.193 0.05130881 -0.00594151 0.4413712 0.05126166 -0.006260216 0.4461383 0.04920816 -0.007933318 0.4992766 0.0488429 -0.007695138 0.5036501 0.04847532 -0.007372379 0.5080069 0.04711782 -0.005779087 0.5209496 0.04647362 -0.005001008 0.5252135 0.04522943 -0.003187239 0.533591 0.04444235 -0.002139449 0.5376722 0.03982263 0.002752482 0.5528837 0.03835058 0.004072964 0.5563237 0.03677743 0.005383014 0.5595429 0.04772603 -0.003724753 0 0.05129754 -0.004388689 0.03788328 0.04853373 -0.003759086 0.122581 0.04287767 -0.002634942 0.1521248 0.04881143 -0.003901302 0.180562 0.04279315 -0.002654552 0.1716395 0.04712003 -0.006871759 0.4682602 0.04159098 -0.005194127 0.5166602 0.03923338 -0.002785384 0.5294374 0.03750658 2.14755e-4 0.5416616 0.02785444 0.009825229 0.5679994 0.02675545 0.01069164 0.570254 0.03280949 0.008017778 0.565378 0.04600495 -0.003251671 0.1354012 0.04272675 -0.002622008 0.1627179 0.04308307 -0.003692209 0.432387 0.04147017 -0.003222525 0.43 0.02232569 0.01207578 0.5721901 0.0325306 -5.53389e-4 0.05320441 0.03245502 -5.18717e-4 0.06852638 0.03457367 -0.004545867 0.5080096 0.03317779 -0.002945184 0.5209506 0.0340119 -0.002467036 0.5252167 0.03447264 -9.99396e-4 0.5335938 0.03421723 -5.97603e-5 0.5376747 0.03121876 0.004502356 0.552886 0.02981132 0.005810499 0.5563295 0.02815526 0.007149696 0.5595887 0.01907825 0.002129614 0.03119778 0.03929501 -0.001915812 0.06016886 0.03873741 -0.001887738 0.193 0.0341888 -0.002165198 0.4368773 0.03334349 -0.004544615 0.5036525 0.03140044 0.003442585 0.5492817 0.01401925 0.00313878 0.0267409 0.01897752 0.002096414 0 0.02579987 7.90876e-4 0.04178309 0.03279185 -5.64233e-4 0.09694457 0.02986842 -0.003254592 0.5123443 0.02912247 0.002895772 0.545539 0.02773451 3.30382e-4 0 0.0326355 -6.01649e-4 0.03509759 0.01894128 0.002188146 0.05153298 0.02566528 8.50444e-4 0.06574064 0.03195202 -0.001295685 0.43 0.02368175 -0.002814173 0.4860642 0.02383214 -0.002875804 0.4948913 0.02444577 0.009729921 0.5654281 0.01213538 0.003555655 0.05236876 0.02505123 -0.002137184 0.4637925 0.02107995 -0.002186357 0.4816278 0.02101737 -0.002223551 0.4992802 0.02920585 -0.002684831 0.5166593 0.02554464 9.0391e-4 0.1064185 0.02582049 7.81716e-4 0.1727547 0.03003883 -7.94365e-4 0.4279056 0.02299809 -0.002724468 0.4904828 0.02503424 8.6496e-5 0.5294363 0.02529531 0.002684235 0.5416596 0.01876461 0.002263784 0.1348437 0.01804494 0.002267658 0.1997287 0.02047592 0.001589298 0.2519555 0.01941514 0.001793026 0.2787085 0.02198165 0.001728951 0.3354488 0.01851773 0.002591967 0.3966175 0.01900625 8.97569e-4 0.4368652 0.01656818 0.001089632 0.4413447 0.02133727 -0.001875817 0.5080109 0.01903873 -0.001663267 0.5036545 0.02436196 0.001042544 0.5335953 0.02331006 0.002141952 0.5376744 0.02031791 0.01199293 0.5702565 0.01980382 0.01288187 0.5737822 -0.02988165 0.01155412 0 -0.001280188 0.006203651 0.04140037 0.008931756 0.004154086 0.02590525 0.01873064 0.002278268 0.117565 0.01880699 0.002245664 0.1448774 0.01888984 0.002210199 0.1577002 0.01899087 0.002166807 0.169409 0.01912367 0.002110123 0.1811196 0.0210756 0.001496315 0.2413603 0.01513826 0.002698779 0.2385717 0.01672387 0.002328693 0.2619645 0.01679462 0.002311885 0.2718247 0.01677161 0.002348005 0.287759 0.01705271 0.002331137 0.2966547 0.01995277 0.001805305 0.305432 0.01743203 0.002389192 0.3142229 0.01761448 0.002444863 0.3225512 0.01738071 0.002778828 0.3452657 0.01542448 0.003354609 0.365459 0.01822459 0.002820074 0.3743575 0.01818054 0.002807021 0.3832488 0.01835089 0.002740263 0.387712 0.01840728 0.00268042 0.3921537 0.01852637 0.002505362 0.4010765 0.0185666 0.002265572 0.410007 0.01886743 0.001683056 0.4234284 0.01881694 0.001467704 0.4278997 0.01276999 -3.72666e-4 0.4771848 0.01359516 -8.44233e-4 0.4904829 0.01332616 -7.42749e-4 0.4860618 0.0222215 -8.90622e-5 0.5252157 0.02304154 0.005128979 0.5492843 0.02311336 0.00613749 0.5528872 0.01028573 0.003839731 0 0.01192343 0.003643512 0.100288 0.01210403 0.003568768 0.1599305 0.01406866 0.003118157 0.1839079 0.01725161 0.002343475 0.2201645 0.01297968 0.003210306 0.2176542 0.01341438 0.003115832 0.305432 0.01552206 0.002982914 0.3321155 0.01578754 0.003195643 0.3541685 0.01553726 0.00335437 0.3787939 0.01617383 0.002422273 0.4189429 0.01862835 0.002103745 0.414476 0.01814806 0.001348793 0.4323935 0.01687341 7.00173e-4 0.4461129 0.02040177 -6.14225e-4 0.454828 0.01024699 -2.83033e-5 0.4816306 0.01981121 -7.94473e-4 0.516659 0.02002888 -2.96588e-4 0.5209519 0.02186018 0.007413029 0.5563325 0.02064347 0.01127886 0.5679979 -0.006464898 0.007211327 0.0384404 -0.002260684 0.006428241 0.06383502 0.01166045 0.003699362 0.1210386 0.01199966 0.003611922 0.1448774 0.0122317 0.003515839 0.1727547 0.01213926 0.003259122 0.2530707 0.0124129 0.003927648 0.3609937 0.01254957 0.003947317 0.3698998 0.01063984 0.003846049 0.410006 0.0159983 0.00290662 0.4055491 0.01160222 -3.48464e-4 0.4992801 0.01741498 -7.5247e-4 0.5123459 0.01092183 9.68498e-4 0.5166593 0.02003973 0.004720211 0.5455378 0.02102237 0.00857377 0.5595555 0.005108177 0.005001723 0.1002881 0.005104959 0.005003035 0.122581 0.009051442 0.004094123 0.1928821 0.005397975 0.004678487 0.2280663 0.008419036 0.004040539 0.2385717 0.007636308 0.004140198 0.2720225 0.008285284 0.004079699 0.2965285 0.0076617 0.004451572 0.3244548 0.009395003 0.004397928 0.347671 0.00872302 0.004613935 0.355314 0.006447196 0.005165755 0.3743404 0.006541728 0.003654658 0.4323831 0.008052647 0.003078103 0.4368755 -0.006253302 0.003521621 0.4727335 -8.68327e-4 0.002494275 0.4727318 -0.005781829 0.003231406 0.4771855 0.01178818 0.001107037 0.4548331 0.002498447 0.001487553 0.4816338 0.01387649 -8.84571e-4 0.4948887 0.01231372 -7.89465e-5 0.5080106 0.008037567 0.001098632 0.5123457 0.01672607 0.001748263 0.5294364 0.01720696 0.002472937 0.5335946 0.01800292 0.004143118 0.5416606 0.005133688 0.004991412 0.09025764 0.005097508 0.005006074 0.112549 0.005139291 0.004989206 0.1348437 0.003228724 0.005356907 0.1476045 0.005358755 0.004900932 0.1660634 0.005473971 0.00485444 0.1761004 0.001644432 0.005585432 0.1862374 0.007060348 0.004275202 0.2508403 0.005452275 0.004574477 0.263089 0.009502947 0.003777861 0.2798227 0.008054375 0.004086554 0.2876205 0.006874024 0.004416465 0.305432 0.008716225 0.004129469 0.314331 0.009268641 0.004342555 0.341004 0.006550312 0.00512284 0.3832594 0.006644904 0.00507152 0.3877035 0.006986379 0.004888892 0.3966081 0.007128059 0.004775226 0.4010884 0.007448494 0.004330217 0.4144755 0.007634341 0.003920435 0.4234219 0.009480893 0.003328442 0.4278987 -0.01522749 0.004697501 0.4860641 -0.0145533 0.004518687 0.4904862 0.009086012 0.001339554 0.4593147 0.00268805 0.001346349 0.4860625 0.003102838 0.001216113 0.490485 0.003567934 0.00113976 0.4948887 0.01422411 0.001503527 0.5252141 0.01558309 0.003681421 0.5376753 0.01715308 0.006301701 0.549285 0.01760399 0.007235348 0.5528895 0.01984143 0.01065355 0.5654338 -0.01326555 0.008525252 0.03788328 -0.002172827 0.006440043 0.09741604 3.22983e-6 0.006010055 0.1270402 -0.001718819 0.006351888 0.115893 0.002521872 0.005350172 0.202872 -4.67411e-4 0.005867838 0.2201645 5.52237e-5 0.005635499 0.2686787 0.001648485 0.005379676 0.2943018 0.002209067 0.005414664 0.314331 0.003042399 0.005652546 0.347671 0.002882421 0.005603909 0.341004 0.002931773 0.005831897 0.3654326 -8.75301e-5 0.006441593 0.3698824 0.006839096 0.004984259 0.3921559 0.00413829 0.005258619 0.4055554 -4.41169e-4 0.005019307 0.4323902 -0.00188148 0.005019128 0.4368786 0.008717119 0.002570509 0.4425135 0.002693891 0.001798629 0.5080109 0.009420871 2.43944e-4 0.5036547 0.01139211 0.001416087 0.5209528 0.01663947 0.00844717 0.5563293 0.01914697 0.01271051 0.5721901 -0.004961431 0.006851315 0 -0.0235396 0.01047581 0.0428965 -0.01873469 0.009498178 0 -0.02688878 0.01108258 0.03788328 -0.003374934 0.006668031 0.1359587 2.22519e-4 0.005923628 0.1627182 -0.003132522 0.006573617 0.1671787 -0.002887666 0.00647825 0.1850234 8.64035e-5 0.005658209 0.2482354 0.001121461 0.005430817 0.27648 0.001387059 0.005396902 0.2853927 3.71717e-4 0.005686998 0.3040152 0.002554893 0.005500018 0.3276703 -1.63391e-5 0.00630021 0.352115 0.001362562 0.006097257 0.3591259 0.003250718 0.00579077 0.3787873 0.006117284 0.004418194 0.4189433 -9.63886e-4 0.005603134 0.4234127 -0.001002132 0.005809724 0.4189512 -0.02396744 0.006116807 0.4948983 -0.02483832 0.00626707 0.4904867 0.00519067 0.00181812 0.4637927 0.002443611 0.001600265 0.5036547 0.002566993 0.003127038 0.5209535 0.004286825 0.002258539 0.5166606 0.0131849 0.006073594 0.5455393 0.01659792 0.009460389 0.5595945 -0.006770491 0.007328808 0.08412814 -0.008468925 0.007657289 0.1404179 -0.004976928 0.006961405 0.1526825 -0.005049765 0.006882667 0.1915448 -0.003474771 0.006401598 0.2341099 -0.002684175 0.006176948 0.260876 -0.005225896 0.006688654 0.2853927 -0.004935443 0.006665885 0.2943018 -0.006310045 0.007075786 0.3143239 -0.004162251 0.00670588 0.3187785 -0.001909255 0.006541907 0.341004 -0.002229571 0.00683999 0.383249 0.002879977 0.005378007 0.4100013 0.002249121 0.00475037 0.4279016 0.002770364 0.003750324 0.4423465 0.003485321 0.002896487 0.4525845 0.001217961 0.002328991 0.4682653 0.001553893 0.001612842 0.4992803 0.008366048 0.003389656 0.5294357 0.009117186 0.004061698 0.5335956 0.01070886 0.005575537 0.541661 0.01636332 0.01133632 0.5654335 0.01710581 0.01197409 0.5679965 -0.01173567 0.008164703 0 -0.009983062 0.007915735 0.05236876 -0.008714199 0.007719159 0.1011565 -0.00681591 0.007346332 0.1270402 -0.01008778 0.007955491 0.1526825 -0.009953737 0.007904589 0.1660634 -0.006535172 0.007238447 0.1671787 -0.007221817 0.007187306 0.2201645 -0.006592869 0.006962716 0.2482777 -0.005736768 0.006765961 0.2697935 -0.006311714 0.006882727 0.2775942 -0.004648983 0.006661713 0.3032065 -0.003303825 0.006611168 0.3249638 -0.005747675 0.0073421 0.3454346 -0.008702695 0.007971763 0.3509669 -0.002512872 0.006918191 0.374347 -0.005461871 0.007483363 0.378797 -0.003839015 0.007071256 0.3921397 -0.001778364 0.006603062 0.396616 -0.001619756 0.006486594 0.401076 -0.006717443 0.006710112 0.4234247 -0.007018625 0.006968498 0.4189394 -0.001284956 0.006039559 0.4144653 -0.003569126 0.005879282 0.4278998 -0.007609784 0.004875242 0.454828 -0.007919251 0.005819261 0.4421965 0.001071631 0.002907276 0.459311 -0.00430572 0.002633392 0.4904867 -0.003694832 0.002529263 0.49489 -0.005623757 0.002972424 0.4992827 -0.002433061 0.002530813 0.5036544 -1.76213e-4 0.003110051 0.5166601 0.001254975 0.002407371 0.5123472 0.005544781 0.003198027 0.5252153 0.007975697 0.005166292 0.5376768 0.01071566 0.007558345 0.5492858 0.01165813 0.008395731 0.5528889 -0.009762167 0.007831692 0.0267409 -0.03029859 0.01170128 0.03788328 -0.01363247 0.008663117 0.09527283 -0.01173621 0.008304893 0.1196817 -0.01524651 0.008957803 0.1463068 -0.01335883 0.008560419 0.1660634 -0.01161444 0.008188188 0.1810985 -0.009429216 0.007705271 0.1984094 -0.01471883 0.008726894 0.197554 -0.01007211 0.007666289 0.2385717 -0.01300805 0.008188486 0.2519555 -0.009364724 0.00747323 0.260876 -0.01208221 0.007994115 0.2787085 -0.0117641 0.007953703 0.2876205 -0.01101917 0.007958352 0.3121485 -0.006916284 0.007427215 0.3343378 -0.004893422 0.007314741 0.3591126 -0.00789994 0.007923901 0.3634584 -0.008380055 0.008024215 0.383249 -0.003950476 0.007142066 0.3876948 -0.00438559 0.006789088 0.4100005 -0.007245123 0.00718671 0.4144667 -0.01037681 0.007932066 0.4100072 -0.004628837 0.00696361 0.4055339 -0.01156073 0.006452023 0.4429488 -0.002866089 0.004834711 0.4424802 -0.00200212 0.003805041 0.454828 -0.001516461 0.003120779 0.4637914 -0.003383934 0.003283262 0.5123478 0.002450466 0.004521191 0.529435 0.01128995 0.00948584 0.5563348 0.0123856 0.01027876 0.5596038 -0.02544528 0.01074802 0 -0.01705133 0.009316861 0.1270402 -0.01363849 0.008665323 0.1270402 -0.01931548 0.00971359 0.1568597 -0.0187447 0.00955224 0.1797339 -0.01600044 0.008817732 0.2332817 -0.0126025 0.008169531 0.2334606 -0.01239728 0.008048415 0.2697935 -0.01230806 0.008088648 0.2954152 -0.01134318 0.007950365 0.3033441 -0.01050662 0.007978081 0.323225 -0.008883774 0.008137762 0.369899 -0.008718848 0.008113145 0.374347 -0.01120245 0.008477807 0.3921473 -0.008033394 0.007808804 0.3966004 -0.007837772 0.007685184 0.4010615 -0.009458124 0.007003188 0.4278972 -0.006356 0.006158709 0.4323785 -0.004488408 0.003977894 0.459311 -0.004118561 0.00308901 0.5080102 -0.004744172 0.003962993 0.5166614 -6.32465e-4 0.004368543 0.5252166 -0.001647472 0.005286157 0.5294348 0.006433725 0.007371962 0.5455392 0.01676744 0.01268404 0.5702529 0.01829689 0.01317226 0.5737825 -0.04356104 0.01391124 0 -0.04009622 0.01333701 0 -0.02007424 0.009818494 0.03788328 -0.0204916 0.009970605 0.1013432 -0.01707315 0.009324908 0.112549 -0.02040827 0.009941041 0.140418 -0.01670777 0.009189307 0.1705242 -0.01960873 0.009647727 0.1984095 -0.01884216 0.009381353 0.2271372 -0.01971518 0.009455382 0.2519555 -0.01604962 0.008748948 0.260876 -0.01887923 0.009278893 0.278909 -0.01852083 0.009231388 0.2878977 -0.0178098 0.009187638 0.3055287 -0.01749438 0.009201705 0.3142589 -0.01332485 0.008734166 0.3409299 -0.01251828 0.008748352 0.35656 -0.01217651 0.00874567 0.365451 -0.01164209 0.00866276 0.378797 -0.01462888 0.009206116 0.3832514 -0.0113582 0.008557438 0.3877014 -0.01388192 0.008826553 0.4010582 -0.01065474 0.008113563 0.4055206 -0.01281183 0.008062303 0.4189478 -0.0126186 0.007825076 0.4234166 -0.01550108 0.007205843 0.4425723 -0.008902311 0.006361544 0.4368638 -0.0205028 0.005618035 0.4860694 -0.0257042 0.00647825 0.4860721 -0.02387136 0.006305754 0.4816388 -0.007003188 0.004167795 0.4637924 -0.006648182 0.00383377 0.4682682 -0.01382368 0.004392862 0.4948934 -0.008880496 0.003965914 0.50801 -0.008008956 0.004134833 0.5123488 -0.003792345 0.004318058 0.5209534 -0.004881381 0.005150735 0.5252158 0.003429889 0.005149781 0.5335959 0.005477964 0.006576418 0.5416619 0.01740634 0.01304584 0.5721904 0.01284265 0.01199805 0.5654028 0.01428937 0.01251119 0.5679979 -0.0238986 0.01060754 0.1209316 -0.02046501 0.009961962 0.1270402 -0.02374559 0.01055061 0.1521847 -0.02345478 0.01044523 0.1749852 -0.02311408 0.01032513 0.1930704 -0.02191394 0.009918451 0.2353778 -0.02088379 0.009647428 0.2659184 -0.01739507 0.008996009 0.2697935 -0.01816469 0.009200334 0.2967235 -0.02044928 0.009838104 0.3225753 -0.01536631 0.008899509 0.323225 -0.01609486 0.009361565 0.350237 -0.01512116 0.009315907 0.369899 -0.01492947 0.009286224 0.374347 -0.01729607 0.009615302 0.3921517 -0.01405793 0.00894612 0.396614 -0.01631379 0.009040296 0.4100067 -0.01308971 0.00829029 0.4144723 -0.01527076 0.008087813 0.4279016 -0.01212191 0.007247507 0.4323782 -0.03532528 0.007855772 0.503654 -0.03411895 0.007620036 0.49928 -0.03286659 0.0075562 0.503654 -0.01015841 0.005049705 0.4593179 -0.01555746 0.004771173 0.4992857 -0.01057243 0.00388354 0.4992834 -0.0121774 0.00432372 0.5036566 -0.01368141 0.004821121 0.5080125 -0.00728774 0.003437042 0.5036545 -0.008188664 0.005114972 0.5209523 0.002515077 0.006200909 0.5376788 0.006133139 0.008426904 0.5492882 0.005835056 0.009495019 0.5528929 -0.03664201 0.01274752 0 -0.03324997 0.01215457 0 -0.02731609 0.01123601 0.117565 -0.02723836 0.01120907 0.1408557 -0.02703213 0.01113408 0.1627182 -0.02640211 0.01090794 0.1984095 -0.02530658 0.0105437 0.2353911 -0.02474886 0.01038712 0.2519555 -0.02370673 0.01017093 0.2787085 -0.02439117 0.01039952 0.3055303 -0.02128571 0.0101599 0.3365598 -0.01807403 0.009568095 0.3365598 -0.02201229 0.01053154 0.359048 -0.01606327 0.009440898 0.3596113 -0.01844286 0.009915411 0.365451 -0.01798015 0.00984764 0.37878 -0.02082878 0.01034796 0.3832422 -0.01754218 0.009711861 0.3876981 -0.01986044 0.009926974 0.4010695 -0.01660537 0.009223937 0.4055248 -0.01880586 0.009166598 0.4189368 -0.01847618 0.008903384 0.4234236 -0.01839041 0.007731199 0.4425606 -0.01466923 0.007437646 0.4368702 -0.01322162 0.005922853 0.454828 -0.0126276 0.005216658 0.463805 -0.01219379 0.004868209 0.4682751 -0.01167434 0.004533529 0.4727311 -0.01117509 0.004237949 0.4771888 -0.01003015 0.003755152 0.4860645 -0.009426951 0.003589272 0.4904864 -0.008740663 0.003471195 0.4948905 -0.009309291 0.004790782 0.5166635 -0.009203672 0.005921006 0.5252181 -5.39862e-4 0.005890786 0.5335963 0.001881897 0.007247805 0.5416636 0.005994498 0.0104745 0.5563411 0.008122742 0.01107668 0.559611 -0.05026543 0.01496303 0 -0.04690504 0.01444613 0 -0.03072911 0.01185435 0.09878909 -0.02729088 0.01122707 0.09527283 -0.03073018 0.01185375 0.1271845 -0.03055626 0.01179194 0.1543045 -0.03027141 0.01169162 0.1749852 -0.02676749 0.01103907 0.180562 -0.02867025 0.01115328 0.2356171 -0.02791118 0.01094669 0.2569888 -0.02422386 0.01026284 0.2659014 -0.02511501 0.01044535 0.2877692 -0.02473735 0.01041048 0.296671 -0.0240184 0.01040327 0.3142755 -0.02509492 0.0106911 0.323225 -0.02239793 0.01052343 0.3503543 -0.0219894 0.01057833 0.3684128 -0.02128821 0.01045924 0.3743425 -0.02364706 0.01081871 0.387697 -0.02341282 0.01072436 0.3921444 -0.0201137 0.01006144 0.3966051 -0.02233612 0.01013261 0.4099966 -0.01910054 0.009397327 0.414467 -0.02112346 0.009149193 0.4279 -0.01786202 0.00830388 0.4323876 -0.04186958 0.008842527 0.512345 -0.04234004 0.009132504 0.51666 -0.04423111 0.009008526 0.512345 -0.01572728 0.006074965 0.459324 -0.01322579 0.004451394 0.4816303 -0.01263052 0.005890309 0.5209536 -0.01387482 0.005587399 0.5166637 -0.00580132 0.006039559 0.5294357 -0.008498072 0.007306516 0.5335967 -0.009986698 0.006770551 0.5294398 -0.004497826 0.006608366 0.5335959 -0.001230418 0.006889998 0.5376763 0.001528561 0.008278846 0.5455389 0.002985715 0.009006261 0.5492877 0.01461791 0.01308482 0.5702537 -0.03410518 0.01244831 0.0859397 -0.02992635 0.01157099 0.1930451 -0.03334498 0.01218074 0.1929582 -0.03204786 0.01175469 0.2357978 -0.02720522 0.0108003 0.2746641 -0.03053724 0.01139432 0.2747607 -0.02956652 0.01127421 0.2965285 -0.02916204 0.01125276 0.305432 -0.02831512 0.01127487 0.3242173 -0.02449935 0.01074296 0.3365598 -0.02662634 0.01135247 0.3587825 -0.02581071 0.01126766 0.374347 -0.02412599 0.010962 0.3788008 -0.02623343 0.01115143 0.3965951 -0.02592474 0.01100713 0.4010686 -0.02259016 0.0103088 0.405539 -0.02442997 0.009964466 0.423409 -0.02474212 0.01022398 0.418932 -0.02413326 0.008738517 0.442655 -0.02126276 0.008239209 0.4426209 -0.02049785 0.008495211 0.4368584 -0.02558201 0.007887601 0.4580379 -0.02363002 0.007173061 0.4638092 -0.02913749 0.008083343 0.4638194 -0.01902055 0.006773233 0.4577317 -0.01806008 0.006201863 0.4637967 -0.01761871 0.005851268 0.4682768 -0.01706922 0.005511462 0.4727323 -0.01652157 0.005206942 0.477192 -0.01839387 0.006334841 0.516664 -0.01733922 0.005760192 0.5123498 -0.001688778 0.007894933 0.5416628 0.01600831 0.0133028 0.5721906 0.01143056 0.01302957 0.5680018 -0.05372369 0.01547032 0 -0.03752803 0.01304638 0.08614164 -0.03416013 0.01246839 0.1185532 -0.03758847 0.01306724 0.1187322 -0.03403168 0.01242244 0.1477706 -0.03749352 0.01303428 0.140418 -0.03373414 0.01231783 0.1716395 -0.03704166 0.01287686 0.178657 -0.03660476 0.01272529 0.1984095 -0.03560864 0.01240015 0.2307945 -0.03127223 0.01154553 0.2571037 -0.03425741 0.01205021 0.2658042 -0.02996653 0.01131319 0.2876205 -0.03347373 0.01191437 0.2834807 -0.0287531 0.01125121 0.314331 -0.03186589 0.01182168 0.3174797 -0.02717834 0.01135045 0.3475703 -0.03063607 0.01191461 0.3440173 -0.02613812 0.01131737 0.3678867 -0.02903515 0.01183205 0.3723084 -0.02950209 0.01188659 0.363528 -0.02702814 0.01145195 0.3832437 -0.02957338 0.01179939 0.3921329 -0.02984982 0.01190119 0.3876867 -0.02500772 0.01044911 0.4144747 -0.02836704 0.01118487 0.4099968 -0.02955526 0.01034188 0.432375 -0.02371662 0.009347259 0.4323788 -0.02631664 0.009510576 0.4368531 -0.01857036 0.005403101 0.4816352 -0.02546602 0.006406426 0.4992869 -0.02195435 0.005985677 0.503659 -0.02550894 0.006535053 0.503654 -0.02320098 0.006392717 0.5080136 -0.01845782 0.005634784 0.5080133 -0.02196413 0.006499052 0.5123484 -0.01268786 0.004967868 0.5123486 -0.01349401 0.006651759 0.5252195 -0.01409584 0.007450103 0.5294399 -0.0050444 0.007569372 0.5376766 -0.001912176 0.008892357 0.5455422 -1.97663e-4 0.009572923 0.5492871 0.001584112 0.01025497 0.5528886 0.005422174 0.01155513 0.559602 0.009373188 0.01264637 0.5654712 -0.04102307 0.01365351 0.1094627 -0.04096192 0.0136339 0.1340642 -0.03733128 0.01297789 0.1582577 -0.04081463 0.013583 0.1526825 -0.04015684 0.01335662 0.1929664 -0.03900772 0.01298141 0.2305091 -0.03834569 0.01279348 0.2482865 -0.03498393 0.0122199 0.2483227 -0.03760272 0.01262062 0.2659075 -0.03286737 0.01185077 0.2965285 -0.03617042 0.01241415 0.2965285 -0.03244656 0.01182657 0.305432 -0.0348156 0.01239579 0.3241241 -0.0335946 0.01245629 0.3474083 -0.03002184 0.01191008 0.3543375 -0.03188329 0.01231414 0.3767415 -0.02866595 0.01175767 0.378797 -0.03200966 0.01204365 0.4010559 -0.0323258 0.01218879 0.3965958 -0.02868598 0.01137274 0.4055234 -0.03029817 0.01096343 0.4234159 -0.03068602 0.01123666 0.4189172 -0.02704203 0.01018255 0.4278852 -0.028373 0.008348584 0.4580551 -0.03116953 0.00879687 0.4580409 -0.02279216 0.00741446 0.458002 -0.02309834 0.006807208 0.4682778 -0.02254128 0.006465494 0.4727435 -0.02190577 0.006146073 0.4771931 -0.01973086 0.005422055 0.4904868 -0.01896393 0.005289554 0.4948987 -0.01711058 0.005184531 0.5036584 -0.01773881 0.007329881 0.5252193 -0.01703619 0.006619215 0.5209543 -0.008883178 0.008223891 0.5376802 -0.005325853 0.008529901 0.5416637 0.002133786 0.01115006 0.556333 0.01734274 0.01334005 0.5737823 -0.06051355 0.01638698 0 -0.05683946 0.01590538 0 -0.04434627 0.01418709 0.08111989 -0.04444605 0.01422131 0.1120787 -0.04435801 0.01419192 0.1387323 -0.04060298 0.01351058 0.1697134 -0.04350382 0.01390033 0.1953776 -0.04219007 0.01347988 0.2363767 -0.04134505 0.01326143 0.2569545 -0.03679543 0.01248103 0.2835209 -0.03573322 0.01238715 0.305432 -0.0390222 0.01293212 0.305432 -0.03528952 0.01237952 0.314331 -0.03700214 0.01298594 0.3441623 -0.03292536 0.01244354 0.3590364 -0.03581261 0.01294779 0.3635356 -0.03240966 0.01240015 0.3678894 -0.0314899 0.01221573 0.383249 -0.03469645 0.01276195 0.3812122 -0.03301441 0.01209259 0.40554 -0.03099113 0.01146847 0.4144731 -0.02701705 0.009231209 0.4426468 -0.02990567 0.009709417 0.4426561 -0.02052181 0.005616605 0.499287 -0.0124588 0.007962048 0.5335978 -0.01264137 0.008824288 0.5376808 -0.005325376 0.009473979 0.5455439 -0.003393292 0.01011812 0.5492905 0.01247626 0.01345807 0.5702559 -0.001368761 0.01075989 0.5528963 0.003011524 0.01203131 0.5598188 -0.07084286 0.01754957 0 -0.07405227 0.01784867 0 -0.04783725 0.01475679 0.09419226 -0.04415065 0.01412022 0.1610125 -0.04384732 0.01401692 0.1794467 -0.04717659 0.01453375 0.183908 -0.04054504 0.01309859 0.2747481 -0.03991895 0.01300823 0.2876205 -0.03947579 0.0129618 0.2965285 -0.04278409 0.01349127 0.2965285 -0.03839981 0.0129202 0.3174784 -0.04166841 0.01344323 0.3174688 -0.04021757 0.01349914 0.3440599 -0.0363292 0.01297593 0.3547911 -0.03527253 0.01288086 0.3723224 -0.03840351 0.01338201 0.3723141 -0.03410476 0.01258349 0.3900801 -0.03671151 0.01289391 0.396616 -0.03267794 0.01190191 0.410006 -0.03531676 0.01216435 0.414475 -0.03124141 0.01088023 0.427903 -0.0337736 0.01101994 0.432387 -0.03046202 0.01019889 0.436874 -0.03402531 0.009279429 0.4574149 -0.04271477 0.008613348 0.503654 -0.04116654 0.008595407 0.50801 -0.04358255 0.0087924 0.50801 -0.02852618 0.007705271 0.4682755 -0.02791464 0.007354021 0.472745 -0.02723604 0.007027506 0.4771969 -0.0315265 0.00756061 0.50801 -0.03393244 0.007853806 0.50801 -0.02292323 0.007029652 0.5166633 -0.02144366 0.007295608 0.5209549 -0.02088373 0.007793843 0.525215 -0.01643043 0.009378969 0.5376806 -0.0164321 0.008571803 0.5335991 -0.008906662 0.009122788 0.5416657 -5.44551e-4 0.0115959 0.5563427 0.01454907 0.01355069 0.5721912 0.006819486 0.01306664 0.565451 0.009398221 0.01336735 0.5679974 -0.06766909 0.01722675 0 -0.06358772 0.01676476 0 -0.04770404 0.01471161 0.07186961 -0.05124503 0.01527512 0.08613061 -0.04787224 0.0147686 0.1161357 -0.05121421 0.01526492 0.1404075 -0.04776555 0.01473265 0.1432074 -0.04748862 0.01463872 0.1671155 -0.05018526 0.01492172 0.2010429 -0.04685604 0.01442635 0.1975687 -0.04556035 0.01401746 0.2367931 -0.04807317 0.01431614 0.2571644 -0.04471004 0.01379954 0.2570992 -0.04388672 0.01363348 0.2747167 -0.04723066 0.01414734 0.2747339 -0.04324215 0.01354008 0.2876205 -0.04572206 0.01396971 0.3034189 -0.04231375 0.01345849 0.3055781 -0.04358851 0.01398712 0.3412424 -0.04242056 0.01396125 0.3590734 -0.0395264 0.01348686 0.354683 -0.03896927 0.013453 0.3635153 -0.0405966 0.01365309 0.3855889 -0.03781336 0.01326113 0.3811777 -0.03735899 0.01313102 0.387702 -0.03703927 0.01302194 0.392158 -0.03905111 0.01303935 0.40554 -0.03637582 0.01274544 0.401076 -0.03603124 0.01257538 0.40554 -0.03567892 0.01238209 0.410006 -0.03751897 0.01210343 0.423424 -0.03494608 0.01192063 0.418947 -0.03456473 0.01164948 0.423424 -0.03417485 0.01134967 0.427903 -0.03574264 0.01064032 0.442436 -0.0333597 0.01066267 0.436874 -0.03277015 0.01016187 0.4427433 -0.05152648 0.00970906 0.520952 -0.04928416 0.009694874 0.520952 -0.04902541 0.009988784 0.525215 -0.02769768 0.006921648 0.481628 -0.03009343 0.007639288 0.512345 -0.03244364 0.007925689 0.512345 -0.02470713 0.007752716 0.520952 -0.02693092 0.008043348 0.520952 -0.02627551 0.007499217 0.51666 -0.02041107 0.0091241 0.5336002 -0.01821315 0.008081555 0.5294399 -0.008713781 0.01001578 0.5455466 -0.006557762 0.01062417 0.549293 -0.004278063 0.01122504 0.5528978 7.09159e-4 0.01235705 0.559683 0.00332719 0.01283156 0.562731 -0.05471199 0.01578891 0.09392285 -0.05131268 0.01529729 0.1185106 -0.0547446 0.01580053 0.1140107 -0.05103665 0.01520597 0.1583774 -0.05409973 0.01558721 0.1808961 -0.05071747 0.0150994 0.1785462 -0.05220746 0.01499927 0.2401173 -0.04882282 0.01450401 0.2399032 -0.04965245 0.01450961 0.2921985 -0.04643994 0.01403373 0.2900778 -0.04800301 0.01443123 0.3214914 -0.04494041 0.01394581 0.3174471 -0.04636949 0.01445645 0.3475129 -0.04298007 0.01398241 0.3503713 -0.04498583 0.01436859 0.3678812 -0.04183012 0.01390582 0.3679146 -0.04122132 0.01380646 0.3767677 -0.04317444 0.01394319 0.392158 -0.0401048 0.013493 0.392158 -0.03976213 0.0133627 0.396616 -0.03941059 0.0132119 0.401076 -0.04129403 0.01306188 0.414475 -0.03868186 0.01284366 0.410006 -0.03830385 0.01262336 0.414475 -0.03791624 0.01237708 0.418947 -0.03961467 0.01189696 0.432387 -0.03711128 0.01180094 0.427903 -0.03669208 0.01146847 0.432387 -0.03626137 0.01110851 0.436874 -0.03682535 0.009685158 0.4574819 -0.03963214 0.01007235 0.4575216 -0.04191917 0.00908184 0.477183 -0.04003864 0.009100019 0.472727 -0.03921866 0.008752763 0.477183 -0.0331766 0.008710026 0.46379 -0.03254276 0.008327245 0.468262 -0.03186279 0.007965564 0.472727 -0.03113526 0.007631003 0.477183 -0.03035295 0.007329642 0.481628 -0.02951455 0.007067799 0.486062 -0.02861464 0.006851255 0.490483 -0.02764993 0.00668621 0.494889 -0.03085356 0.008077263 0.51666 -0.02856302 0.007798254 0.51666 -0.02774626 0.007332444 0.512345 -0.02125591 0.008507251 0.529435 -0.01253151 0.009679555 0.5416682 -0.003207862 0.01200777 0.5563542 0.005080163 0.01333451 0.5654546 0.007969498 0.01358646 0.5679974 0.01091718 0.01369959 0.5702531 -0.06755143 0.01722437 0.004390895 -0.05458521 0.01574736 0.07354116 -0.05818539 0.01627737 0.1049705 -0.05467832 0.01577877 0.1363541 -0.05446845 0.0157091 0.1584306 -0.05777275 0.01614403 0.1673247 -0.05742597 0.01603025 0.1852888 -0.05351185 0.01539301 0.2040659 -0.05144649 0.01481097 0.2571101 -0.05082666 0.01468515 0.2697935 -0.05393338 0.01510459 0.274706 -0.05024254 0.01458525 0.2812051 -0.0522077 0.01490736 0.3056269 -0.04915845 0.01446461 0.3011476 -0.04865181 0.01443618 0.309925 -0.05078989 0.01488959 0.3287817 -0.0487675 0.0148679 0.3590944 -0.04559057 0.01442617 0.3590915 -0.04746973 0.01469898 0.3767436 -0.04434651 0.01426488 0.3767439 -0.0436728 0.01410382 0.3856304 -0.04281592 0.01381051 0.396616 -0.04510021 0.01390331 0.40554 -0.04244941 0.01365756 0.401076 -0.04207408 0.01348268 0.40554 -0.04168891 0.01328462 0.410006 -0.04343491 0.01294833 0.423424 -0.04089045 0.01281321 0.418947 -0.04047536 0.012537 0.423424 -0.04005074 0.01223194 0.427903 -0.04148763 0.01145333 0.4425318 -0.03916501 0.01153439 0.436874 -0.03861051 0.01105684 0.4424886 -0.0359531 0.009117186 0.46379 -0.03529244 0.00873059 0.468262 -0.03458559 0.008364677 0.472727 -0.03382635 0.008025705 0.477183 -0.03301221 0.007719576 0.481628 -0.03213798 0.007452428 0.486062 -0.03119933 0.007230222 0.490483 -0.03019291 0.007059097 0.494889 -0.02911442 0.006945192 0.49928 -0.02795845 0.00689435 0.503654 -0.02672284 0.006912827 0.50801 -0.02540111 0.007006585 0.512345 -0.02541905 0.009033024 0.529435 -0.02336251 0.009486734 0.533594 -0.02536749 0.009712219 0.533594 -0.02333652 0.008779168 0.529435 -0.0161544 0.01018273 0.5416711 -0.012093 0.01051044 0.545547 -0.0155161 0.01095867 0.5455536 -0.009721457 0.01108789 0.5492953 -0.007207274 0.01165598 0.5529057 9.23548e-4 0.01311647 0.5624992 0.01662254 0.01345044 0.5737823 -0.07639122 0.01804578 0 -0.07786637 0.01817482 0.004417717 -0.05810803 0.01625257 0.08502781 -0.06159639 0.01671737 0.09415876 -0.06163465 0.01672953 0.1138827 -0.05816835 0.01627218 0.1273709 -0.06148064 0.01667988 0.1459925 -0.05800896 0.01622074 0.1494528 -0.06096184 0.01651215 0.1806902 -0.0604133 0.01633435 0.2023335 -0.05692684 0.01586651 0.2042905 -0.05900275 0.01591706 0.239843 -0.05560725 0.01547354 0.2397881 -0.05482214 0.01528036 0.2570633 -0.05820161 0.01572191 0.2570855 -0.05655223 0.0154339 0.2879867 -0.0532251 0.01500099 0.2877539 -0.05272734 0.01494646 0.2966563 -0.05462127 0.01531022 0.319822 -0.05157792 0.01488304 0.3159856 -0.05306953 0.01532799 0.3439231 -0.04958087 0.01490253 0.347488 -0.05094492 0.01516932 0.372312 -0.04813349 0.01480615 0.3678837 -0.0467776 0.01453554 0.3856098 -0.04932254 0.01477217 0.392158 -0.04624634 0.01437014 0.392158 -0.04587286 0.01423537 0.396616 -0.04549145 0.01408034 0.401076 -0.04728496 0.01386958 0.414475 -0.04469913 0.01370292 0.410006 -0.04428833 0.01347792 0.414475 -0.04386693 0.01322686 0.418947 -0.04546737 0.01268613 0.432387 -0.04299336 0.01264095 0.427903 -0.04253941 0.01230353 0.432387 -0.04207187 0.01193845 0.436874 -0.04238551 0.0103892 0.4581084 -0.0451951 0.01072615 0.4581764 -0.04356229 0.009809792 0.468262 -0.04276996 0.009432852 0.472727 -0.04550361 0.009740531 0.472727 -0.03873372 0.009503602 0.46379 -0.03804618 0.009113192 0.468262 -0.03731054 0.008743524 0.472727 -0.03652042 0.008400201 0.477183 -0.03567349 0.008089542 0.481628 -0.03476351 0.007817327 0.486062 -0.03378707 0.007589817 0.490483 -0.03273892 0.00741291 0.494889 -0.03161567 0.007292807 0.49928 -0.03041201 0.007235348 0.503654 -0.02912366 0.007246494 0.50801 -0.02734845 0.008637547 0.525215 -0.02750468 0.009267687 0.529435 -0.023036 0.008092999 0.525215 -0.02116948 0.009984016 0.537675 -0.01883274 0.01051056 0.541661 -0.02065449 0.0107156 0.541661 -0.01806122 0.01124507 0.545537 -0.004933655 0.0123282 0.5566483 0.01313138 0.01375758 0.572192 0.003307163 0.01358038 0.5654541 0.006553828 0.01378309 0.5679985 0.00983864 0.01384913 0.5702532 -0.06482619 0.01706779 0.06320947 -0.06159085 0.01671522 0.1314281 -0.0648505 0.01707494 0.1539178 -0.06128436 0.0166164 0.1628809 -0.06419086 0.01686429 0.1895478 -0.06078541 0.01597702 0.2722389 -0.0574212 0.01556706 0.2722476 -0.05910241 0.01576203 0.3010311 -0.05578541 0.01535797 0.3011007 -0.05524533 0.01532518 0.3099175 -0.05790525 0.01571047 0.3198171 -0.05546718 0.01569235 0.3546677 -0.05226373 0.01530224 0.3547217 -0.05161982 0.0152558 0.3634934 -0.05335682 0.01541185 0.3811593 -0.05023932 0.01503187 0.3811672 -0.04970186 0.01488977 0.387702 -0.05158454 0.01484972 0.401076 -0.04893416 0.01463556 0.396616 -0.04853582 0.01447826 0.401076 -0.04812866 0.01429915 0.40554 -0.04771167 0.01409673 0.410006 -0.0493648 0.01369708 0.423424 -0.04684662 0.01361638 0.418947 -0.04639869 0.0133357 0.423424 -0.04593926 0.01302599 0.427903 -0.04718166 0.01213598 0.4430227 -0.04498296 0.01231878 0.436874 -0.0442965 0.01178741 0.4429826 -0.04151648 0.00986731 0.46379 -0.04080313 0.009473562 0.468262 -0.03833794 0.008437752 0.481628 -0.03739213 0.008160948 0.486062 -0.03637689 0.007928431 0.490483 -0.03528696 0.00774604 0.494889 -0.02959233 0.009482026 0.529435 -0.03168106 0.009674966 0.529435 -0.03167003 0.009102523 0.525215 -0.02950769 0.008880436 0.525215 -0.02519124 0.008374691 0.525215 -0.02247822 0.01090288 0.541661 -0.02308684 0.01019978 0.537675 -0.01925408 0.009750664 0.537675 -0.01290816 0.01150524 0.5493011 -0.01014858 0.01204234 0.5529164 -0.006434142 0.0124858 0.556501 -0.001025736 0.01340645 0.5626378 -0.08505994 0.01862168 0 -0.08105319 0.01838594 0 -0.08476787 0.01861941 0.004423201 -0.06504422 0.01713716 0.09232151 -0.06854146 0.01754003 0.1165745 -0.06508135 0.01714885 0.1182975 -0.06501239 0.01712685 0.1361303 -0.06842923 0.01750457 0.1407179 -0.06793677 0.01734852 0.176213 -0.06458097 0.01698875 0.1717382 -0.06372314 0.01671493 0.2057794 -0.06247496 0.01634883 0.2384094 -0.06496238 0.01651382 0.2571732 -0.06157916 0.01613324 0.2571522 -0.06324678 0.01622051 0.2877996 -0.05989301 0.015841 0.2880253 -0.06198602 0.01610535 0.3079001 -0.05854439 0.0157274 0.3099583 -0.05630105 0.01572072 0.3438261 -0.05953276 0.01608347 0.3437372 -0.05796098 0.01599907 0.3634949 -0.05478894 0.01564216 0.3635047 -0.05409443 0.01555329 0.3722921 -0.05548417 0.01549428 0.392158 -0.05279636 0.01526683 0.387702 -0.05240207 0.01514744 0.392158 -0.05199778 0.01500886 0.396616 -0.05116146 0.01466876 0.40554 -0.05328834 0.01457321 0.414475 -0.05072855 0.01446443 0.410006 -0.05028492 0.01423519 0.414475 -0.04983067 0.01397997 0.418947 -0.05133444 0.01337373 0.432387 -0.0488885 0.01338541 0.427903 -0.04839968 0.01304352 0.432387 -0.04789638 0.01267385 0.436874 -0.04632484 0.01012063 0.468262 -0.04909074 0.01040464 0.468262 -0.04709094 0.01052057 0.46379 -0.04430252 0.01020681 0.46379 -0.05132573 0.009335458 0.512345 -0.05156058 0.009497344 0.51666 -0.05369353 0.009382903 0.512345 -0.04100459 0.008762717 0.481628 -0.04002398 0.008481621 0.486062 -0.03896993 0.008244335 0.490483 -0.03783816 0.008056998 0.494889 -0.03662544 0.00792545 0.49928 -0.04003834 0.008970737 0.51666 -0.0403214 0.009340286 0.520952 -0.03584909 0.009000658 0.520952 -0.03808462 0.009182989 0.520952 -0.03773903 0.008783161 0.51666 -0.0338335 0.009302318 0.525215 -0.03599923 0.009478986 0.525215 -0.03361582 0.008794426 0.520952 -0.0291568 0.008314609 0.520952 -0.02430391 0.01107156 0.541661 -0.02500617 0.01039689 0.537675 -0.008493304 0.01271396 0.5564244 0.001541256 0.01379483 0.565453 0.005134701 0.01395601 0.5679996 0.008758187 0.01398062 0.5702535 -0.09494817 0.01894313 0 -0.09714579 0.01896351 0 -0.06832516 0.01747149 0.06812351 -0.07177692 0.01782548 0.06791061 -0.06848508 0.01752233 0.09190505 -0.07194107 0.0178771 0.09184175 -0.0719645 0.01788443 0.1273261 -0.07168865 0.01779818 0.1585252 -0.06823801 0.01744407 0.1584551 -0.06757378 0.01723384 0.1915385 -0.06707233 0.01707559 0.2083234 -0.07042604 0.01740491 0.2103574 -0.06578308 0.01670861 0.2403228 -0.06924581 0.01707118 0.2393031 -0.06738013 0.0166769 0.2747268 -0.06401199 0.01633083 0.2747664 -0.06603544 0.01650243 0.2966731 -0.06270444 0.01616042 0.2965911 -0.06119239 0.01607996 0.3197507 -0.06447929 0.01641744 0.3197432 -0.06186479 0.0163809 0.3546914 -0.05865681 0.01605153 0.3547153 -0.05722886 0.01590585 0.3723453 -0.05959683 0.01608318 0.3811776 -0.05647104 0.0157622 0.381177 -0.05589437 0.0156154 0.387702 -0.05769151 0.01550692 0.401076 -0.05506592 0.01535403 0.396616 -0.05463677 0.01519322 0.401076 -0.05419772 0.01501041 0.40554 -0.05374789 0.01480406 0.410006 -0.0553075 0.01433658 0.423424 -0.05281716 0.01431602 0.418947 -0.05233442 0.01403123 0.423424 -0.05184018 0.01371759 0.427903 -0.05303955 0.01279711 0.4426111 -0.05081218 0.01300197 0.436874 -0.05006396 0.01245266 0.4431219 -0.04988276 0.01080727 0.46379 -0.0526781 0.01106536 0.46379 -0.05085539 0.01135617 0.4578982 -0.04800629 0.01104062 0.4581986 -0.05517166 0.01026004 0.5341205 -0.05683404 0.009951651 0.529435 -0.05285871 0.01046121 0.534469 -0.04462194 0.009386003 0.477183 -0.04367554 0.009063243 0.481628 -0.04265803 0.008777976 0.486062 -0.04156517 0.008536338 0.490483 -0.04039263 0.008344352 0.494889 -0.03913408 0.008207798 0.49928 -0.03778612 0.008132636 0.503654 -0.0363416 0.008124828 0.50801 -0.03479701 0.008190393 0.512345 -0.0331462 0.008335292 0.51666 -0.03138571 0.008565425 0.520952 -0.03077548 0.0108664 0.537675 -0.02884989 0.01073116 0.537675 -0.02796036 0.01134914 0.541661 -0.02613157 0.01122057 0.541661 -0.02692747 0.01057434 0.537675 -0.01851379 0.01208734 0.549284 -0.01475548 0.01266366 0.5535236 -0.01657855 0.01274281 0.5531944 -0.016106 0.01186692 0.5493118 -0.01308655 0.01237827 0.5529419 -0.0027498 0.01355278 0.5624352 0.01590108 0.01353836 0.5737824 -0.09042543 0.01884084 0 -0.088081 0.01875686 0 -0.09167909 0.01889491 0.004453897 -0.07528114 0.01815938 0.07374799 -0.07545518 0.01821285 0.1093765 -0.07199287 0.01789307 0.1095872 -0.07186126 0.01785272 0.1429564 -0.07487744 0.01803511 0.1741198 -0.07138013 0.01770198 0.176245 -0.07095193 0.01756817 0.1937783 -0.07439839 0.01788663 0.1937585 -0.07263004 0.0173791 0.2399248 -0.06834787 0.01686054 0.2573214 -0.07173985 0.01717394 0.257316 -0.06659698 0.01656454 0.2877294 -0.06877547 0.01676255 0.3055007 -0.06529986 0.01644545 0.3078567 -0.06276327 0.01641464 0.3436998 -0.06601113 0.01671344 0.3435431 -0.061149 0.01632648 0.3634447 -0.06431525 0.0166189 0.363514 -0.06039142 0.01623088 0.3722971 -0.06209826 0.01622039 0.387702 -0.058995 0.01593381 0.387702 -0.0585708 0.01581114 0.392158 -0.05813562 0.01566928 0.396616 -0.05979734 0.01539409 0.410006 -0.05723655 0.01532244 0.40554 -0.05677181 0.01511454 0.410006 -0.05629432 0.01488184 0.414475 -0.05580723 0.01462298 0.418947 -0.05721253 0.01394689 0.432387 -0.05479532 0.01402103 0.427903 -0.05427169 0.01367533 0.432387 -0.05373251 0.01330184 0.436874 -0.05586808 0.009848952 0.486062 -0.05322158 0.009694039 0.486062 -0.05458182 0.009591698 0.490483 -0.04824066 0.0100215 0.472727 -0.04732811 0.009663879 0.477183 -0.04634779 0.009337663 0.481628 -0.04529547 0.009048879 0.486062 -0.04416382 0.008803188 0.490483 -0.04294937 0.00860691 0.494889 -0.041646 0.008465707 0.49928 -0.04024928 0.008385598 0.503654 -0.03875291 0.008372485 0.50801 -0.03715157 0.008432269 0.512345 -0.03544199 0.008570969 0.51666 -0.03139364 0.01026785 0.533594 -0.03340601 0.01040935 0.533594 -0.02737444 0.009918332 0.533594 -0.02322638 0.01172137 0.545537 -0.02081876 0.01246547 0.5503063 -0.02495145 0.0118426 0.545537 -0.01978135 0.01142174 0.545537 -0.0105769 0.01290863 0.556329 -0.003955662 0.01364421 0.562295 0.01168811 0.01391905 0.572192 -2.31441e-4 0.01397651 0.5654534 0.003687918 0.01410412 0.5679985 0.00767225 0.01409184 0.5702535 -0.07540184 0.0181964 0.09149819 -0.07888501 0.01848518 0.09611564 -0.07541584 0.01820141 0.1297013 -0.07523286 0.01814496 0.1518793 -0.07874488 0.01844233 0.1471563 -0.07828134 0.0183016 0.1763583 -0.07386124 0.01772207 0.2103781 -0.07729089 0.01800066 0.2105219 -0.07074862 0.01698774 0.2747912 -0.07478392 0.01738101 0.2635668 -0.06994909 0.01687413 0.2877388 -0.06937086 0.01681053 0.296671 -0.07301133 0.0171138 0.2921579 -0.0679506 0.01672446 0.3173667 -0.07125395 0.0169937 0.3173131 -0.06506764 0.01667684 0.3546953 -0.06353706 0.01652139 0.3723149 -0.06669682 0.01677918 0.372305 -0.0627126 0.01637071 0.3812077 -0.06165909 0.01609647 0.392158 -0.06120997 0.01595324 0.396616 -0.06074994 0.01578938 0.401076 -0.06381106 0.01603901 0.401076 -0.06027901 0.01560348 0.40554 -0.05930387 0.01515984 0.414475 -0.0582832 0.01461136 0.423424 -0.06126159 0.01485425 0.423424 -0.05879986 0.01489937 0.418947 -0.05775409 0.0142942 0.427903 -0.05665534 0.01357185 0.436874 -0.05583363 0.01299947 0.4433227 -0.05871826 0.01322466 0.4434463 -0.0582745 0.01149034 0.46379 -0.05927085 0.01199907 0.4584146 -0.05645453 0.0118072 0.4583451 -0.05364018 0.01158422 0.4582667 -0.058178 0.01048499 0.477183 -0.05546259 0.01032596 0.477183 -0.05706506 0.0101487 0.481628 -0.05185818 0.01066029 0.468262 -0.05098015 0.01027452 0.472727 -0.05003672 0.0099141 0.477183 -0.04902356 0.009584784 0.481628 -0.04793536 0.009292662 0.486062 -0.04676479 0.009043455 0.490483 -0.04550856 0.008843243 0.494889 -0.0441603 0.008697867 0.49928 -0.03950941 0.008650064 0.512345 -0.03542059 0.01052725 0.533594 -0.03462821 0.01106834 0.537675 -0.03743547 0.01062053 0.533594 -0.03270119 0.01097923 0.537675 -0.02938348 0.01010394 0.533594 -0.0227034 0.01252067 0.5500065 -0.02667748 0.01194363 0.545537 -0.02150338 0.01158076 0.545537 -0.008760511 0.01351159 0.5597432 -0.005082249 0.01382344 0.5626565 -0.07876485 0.01844853 0.076285 -0.08236682 0.01873385 0.09884411 -0.07891863 0.01849555 0.1138533 -0.07886701 0.01848006 0.1317383 -0.0822699 0.01870495 0.1406524 -0.07856941 0.01838916 0.1606473 -0.08206486 0.0186429 0.1585049 -0.08140683 0.01844483 0.189485 -0.07783925 0.01816701 0.1938049 -0.08043837 0.01815629 0.2182382 -0.07575577 0.01758581 0.245868 -0.07899999 0.01779031 0.2487813 -0.07384759 0.01722013 0.2792404 -0.07721817 0.01745718 0.2792099 -0.07224845 0.01704305 0.3034158 -0.07557761 0.01727706 0.3033927 -0.07408922 0.01721942 0.3236134 -0.06925153 0.01697713 0.3434647 -0.06827932 0.01693874 0.3546613 -0.07109135 0.017138 0.3590949 -0.06750255 0.01687902 0.3634968 -0.06585502 0.01662772 0.3811578 -0.06852763 0.01674717 0.3856188 -0.06520521 0.01647382 0.387702 -0.06475114 0.0163486 0.392158 -0.06428611 0.01620417 0.396616 -0.06637185 0.01606601 0.40554 -0.06332421 0.01585173 0.40554 -0.06585776 0.01585412 0.410006 -0.06282657 0.01564115 0.410006 -0.06231719 0.01540553 0.414475 -0.06179517 0.01514375 0.418947 -0.06367868 0.0147441 0.427903 -0.06071549 0.01453584 0.427903 -0.06310218 0.01439416 0.432387 -0.06015598 0.01418697 0.432387 -0.05958092 0.01381039 0.436874 -0.06160169 0.01341807 0.4435583 -0.05547499 0.01129353 0.46379 -0.05462914 0.01088625 0.468262 -0.0537222 0.01049822 0.472727 -0.05274885 0.01013523 0.477183 -0.05170178 0.009803235 0.481628 -0.05057668 0.009508073 0.486062 -0.04936826 0.009255766 0.490483 -0.04807013 0.009052157 0.494889 -0.04667699 0.008903145 0.49928 -0.04518258 0.008814573 0.503654 -0.04685217 0.009975016 0.525215 -0.04635149 0.01033782 0.529435 -0.03945171 0.01068794 0.533594 -0.03848606 0.01117157 0.537675 -0.04146832 0.01072841 0.533594 -0.03655648 0.01113283 0.537675 -0.033773 0.009845614 0.529435 -0.02472883 0.0125454 0.5496076 -0.02840471 0.01202356 0.545537 -0.02012413 0.01221871 0.549284 -0.002002358 0.01412057 0.5654534 0.002247989 0.01422113 0.5679981 0.006580591 0.0141806 0.5702536 -0.1005223 0.01895761 0 -0.1020534 0.01895868 0.004396736 -0.08564949 0.01888102 0.07038021 -0.08215826 0.01867079 0.06802284 -0.08582001 0.01893174 0.09597772 -0.08585464 0.01894235 0.1138611 -0.0823695 0.01873487 0.122868 -0.0856232 0.01887369 0.1518487 -0.08173996 0.01854491 0.1763191 -0.08529204 0.01877552 0.1718569 -0.08103585 0.01833271 0.2019143 -0.08406186 0.01840913 0.2138301 -0.08157122 0.01781857 0.2635155 -0.07817709 0.01761984 0.2635239 -0.07971233 0.0175454 0.2921743 -0.07635909 0.01734888 0.292225 -0.07478582 0.01723456 0.3141864 -0.0778653 0.01741939 0.3172605 -0.07214093 0.0171951 0.3473144 -0.07575345 0.01739472 0.3432496 -0.07027453 0.01705777 0.3679029 -0.07301592 0.01718634 0.3723114 -0.06942194 0.01693123 0.3767494 -0.0709424 0.01674747 0.392158 -0.06784552 0.01656615 0.392158 -0.07044696 0.01660102 0.396616 -0.06736546 0.0164206 0.396616 -0.06687432 0.01625436 0.401076 -0.06834894 0.01579409 0.414475 -0.06533175 0.01561748 0.414475 -0.06779378 0.0155301 0.418947 -0.06479322 0.01535445 0.418947 -0.06424272 0.01506382 0.423424 -0.06543856 0.01418775 0.436874 -0.06250816 0.01401621 0.436874 -0.06449306 0.01358008 0.4436435 -0.06419008 0.01191943 0.4623478 -0.06208777 0.01215779 0.4584855 -0.0619623 0.01097911 0.472727 -0.05921322 0.01085186 0.472727 -0.06089514 0.01061064 0.477183 -0.05740272 0.01108121 0.468262 -0.05646687 0.01069116 0.472727 -0.05438262 0.009991705 0.481628 -0.05197423 0.009438991 0.490483 -0.0506342 0.009232401 0.494889 -0.04919517 0.009080171 0.49928 -0.0476529 0.008988261 0.503654 -0.046 0.008962333 0.50801 -0.04348647 0.01074111 0.533594 -0.04425227 0.01032453 0.529435 -0.04215461 0.01028239 0.529435 -0.03816723 0.009631335 0.525215 -0.0358662 0.009992718 0.529435 -0.03159141 0.0121625 0.545903 -0.02946144 0.01217865 0.5463134 -0.01734352 0.01338076 0.556329 -0.01097947 0.01361578 0.5594683 -0.007183134 0.01396989 0.5626521 0.01517295 0.0135979 0.5737824 -0.09307384 0.01890999 0 -0.08918017 0.01906031 0.07849162 -0.08930122 0.01909565 0.09843587 -0.08924156 0.01907873 0.1362731 -0.08580261 0.01892691 0.131688 -0.08905977 0.01902502 0.1540171 -0.08480942 0.01863187 0.191609 -0.08826488 0.01879191 0.1915845 -0.08747321 0.01856011 0.2145622 -0.08239763 0.01798725 0.2490024 -0.08578854 0.01813989 0.2494426 -0.08396387 0.01781034 0.2792608 -0.08059287 0.01765489 0.279192 -0.08224225 0.01762616 0.3034671 -0.07890796 0.0174719 0.303447 -0.07900518 0.01754468 0.3431513 -0.07469785 0.0173524 0.3547027 -0.07706904 0.01743769 0.3634634 -0.07791972 0.01750153 0.3546636 -0.07388073 0.01729011 0.3634607 -0.07524394 0.01717519 0.3812025 -0.07211536 0.01703077 0.3811759 -0.07142668 0.01687455 0.387702 -0.0699402 0.01643389 0.401076 -0.07192724 0.01617223 0.410006 -0.07247382 0.01638579 0.40554 -0.06942182 0.01624459 0.40554 -0.06889152 0.01603174 0.410006 -0.06722587 0.01523852 0.423424 -0.06900018 0.01470321 0.432387 -0.06961262 0.01505506 0.427903 -0.06664472 0.01491773 0.427903 -0.06605011 0.01456665 0.432387 -0.06688761 0.01341909 0.4467377 -0.06107676 0.01165437 0.46379 -0.06017804 0.0112437 0.468262 -0.01450222 0.01145702 0.568287 -0.01824051 0.01113021 0.567238 -0.01505142 0.01186996 0.567996 -0.0589258 0.009782493 0.529435 -0.05988222 0.009588837 0.525215 -0.05319988 0.009382605 0.494889 -0.05171591 0.009227693 0.49928 -0.0501247 0.009132921 0.503654 -0.04841989 0.009104073 0.50801 -0.04659414 0.009146869 0.512345 -0.04464316 0.00926733 0.51666 -0.04256063 0.009471356 0.520952 -0.04033654 0.009758353 0.525215 -0.03796064 0.01011532 0.529435 -0.02618414 0.01301032 0.5525825 -0.03637599 0.01175594 0.5425438 -0.02979129 0.01145631 0.541661 -0.02081435 0.01338905 0.5557644 -0.01913255 0.01339447 0.5560394 -0.01558434 0.01381492 0.559587 -0.0124467 0.01366037 0.5592449 0.01060503 0.01399904 0.5721903 -0.003791034 0.01422464 0.5654523 8.09169e-4 0.01430499 0.5679982 0.005491673 0.01424396 0.5702536 -0.1079027 0.01877635 0 -0.1054064 0.01886308 0 -0.1038655 0.01890319 0 -0.09859532 0.01898598 0.004436552 -0.09238117 0.01909798 0.05234497 -0.08901053 0.01901072 0.06089359 -0.09274083 0.01920223 0.09165787 -0.09279727 0.01921874 0.109432 -0.08932077 0.01910161 0.1183453 -0.09263414 0.01917201 0.1451494 -0.08875566 0.01893597 0.1718237 -0.09201443 0.01899248 0.1807637 -0.09145826 0.01883125 0.1998094 -0.08927857 0.0182693 0.2481772 -0.088355 0.01808738 0.2636889 -0.08495926 0.01797419 0.2636564 -0.0864169 0.01781195 0.2922968 -0.08306479 0.01770019 0.2922312 -0.08448529 0.01768308 0.3172371 -0.08117121 0.01757234 0.3172693 -0.08226478 0.01765334 0.3430332 -0.07934951 0.017439 0.3722919 -0.08026468 0.01754468 0.3634378 -0.07617729 0.01733249 0.3723211 -0.07454049 0.01701861 0.387702 -0.07661557 0.01684677 0.3966161 -0.07714152 0.01699447 0.392158 -0.07404124 0.01689082 0.392158 -0.07353055 0.01674365 0.3966161 -0.07300812 0.01657569 0.401076 -0.07380008 0.01576948 0.4189471 -0.0743888 0.01603484 0.414475 -0.07136815 0.01593381 0.414475 -0.07079619 0.01566904 0.418947 -0.07021111 0.01537662 0.423424 -0.07063221 0.01401889 0.441363 -0.07130408 0.01442152 0.436874 -0.06837058 0.01432335 0.436874 -0.06771743 0.01392143 0.441363 -0.06716972 0.01209002 0.4615283 -0.06471228 0.01107102 0.472727 -0.06573337 0.01146501 0.468262 -0.06295514 0.0113722 0.468262 -0.06347566 0.009655117 0.494889 -0.06502562 0.009868502 0.490483 -0.06241393 0.009852111 0.490483 -0.05974924 0.01027286 0.481628 -0.05851632 0.009971499 0.486062 -0.05719107 0.009712398 0.490483 -0.05576717 0.009501397 0.494889 -0.05423825 0.009344458 0.49928 -0.05259811 0.009247422 0.503654 -0.05084133 0.00921601 0.50801 -0.04895967 0.009256303 0.512345 -0.04694771 0.009373962 0.51666 -0.04480028 0.009575009 0.520952 -0.04250729 0.009858787 0.525215 -0.04005742 0.01021236 0.529435 -0.0385611 0.01169556 0.5421632 -0.0280596 0.01295751 0.5522483 -0.0316233 0.01154112 0.541661 -0.02276825 0.01345121 0.556329 -0.02141183 0.01346188 0.556329 -0.01800578 0.01381301 0.559587 -0.01372319 0.0137788 0.5596273 -0.009300112 0.01406693 0.562648 -0.1191574 0.0180583 0 -0.09599596 0.01921021 0.06531524 -0.0926128 0.01916551 0.07414042 -0.09625375 0.01928305 0.1004779 -0.09276592 0.01920992 0.1273649 -0.09618836 0.01926481 0.1361722 -0.09600013 0.01921093 0.1539526 -0.09238964 0.01910096 0.162934 -0.09535521 0.01902759 0.1851628 -0.09406548 0.01866614 0.2212094 -0.09070044 0.0186187 0.2193148 -0.09212833 0.01822143 0.2578206 -0.09071737 0.017991 0.2792679 -0.08733654 0.01792258 0.2793381 -0.08891707 0.01780474 0.3034422 -0.08558022 0.01773792 0.3034118 -0.0855242 0.01771861 0.3428969 -0.08434963 0.01767361 0.354693 -0.08113145 0.01760894 0.354695 -0.08152168 0.01734352 0.381189 -0.07838559 0.01728069 0.3811827 -0.07765591 0.0171228 0.387702 -0.07607752 0.01667839 0.401076 -0.07800287 0.01633477 0.410006 -0.07858192 0.01654917 0.40554 -0.07552725 0.01648783 0.40554 -0.07496446 0.01627379 0.410006 -0.0731979 0.01547646 0.423424 -0.0749045 0.0148611 0.432387 -0.07555234 0.01521402 0.427903 -0.07258188 0.01515436 0.427903 -0.07195186 0.01480191 0.432387 -0.07269102 0.01356905 0.4468004 -0.06981188 0.01351946 0.4467139 -0.07021391 0.01114356 0.472727 -0.07129287 0.01153838 0.468262 -0.06851285 0.01152086 0.468262 -0.0676378 0.009848058 0.490483 -0.06911832 0.01010918 0.486062 -0.0664674 0.01012998 0.486062 -0.06361413 0.01070159 0.477183 -0.06243419 0.01036268 0.481628 -0.06116634 0.01006013 0.486062 -0.05980205 0.009799659 0.490483 -0.05833619 0.009587347 0.494889 -0.05676233 0.009428858 0.49928 -0.05507314 0.009330153 0.503654 -0.05326342 0.009297013 0.50801 -0.04925388 0.009451091 0.51666 -0.04704141 0.009649872 0.520952 -0.04467946 0.009931445 0.525215 -0.03345566 0.01160228 0.541661 -0.02412468 0.01342099 0.556329 -0.01921683 0.01378595 0.559587 0.009874284 0.01403284 0.5721904 -0.005560815 0.01428347 0.5654523 -6.28119e-4 0.01435267 0.5679979 0.0044052 0.01427996 0.5702536 -0.114573 0.01841616 0 -0.1122899 0.01856052 0 -0.09939348 0.01921081 0.05857336 -0.09615772 0.01925575 0.08280253 -0.09959459 0.01926803 0.07852178 -0.09974771 0.01931071 0.1140063 -0.09626966 0.01928758 0.1183808 -0.0995295 0.01924937 0.1495245 -0.09568548 0.01912164 0.1717748 -0.0992453 0.01916939 0.1673077 -0.09491109 0.01890045 0.1998164 -0.09842187 0.01893854 0.1980472 -0.09536468 0.01821297 0.2604629 -0.0931428 0.01790171 0.2921229 -0.08977836 0.01787984 0.2922221 -0.09111899 0.0177707 0.3170828 -0.08780205 0.01774972 0.3171434 -0.08879011 0.01773917 0.3427512 -0.08345872 0.01760888 0.3634361 -0.08567905 0.01752245 0.3723036 -0.08664697 0.01762878 0.3634639 -0.08251106 0.01750236 0.3723078 -0.08077245 0.01718538 0.387702 -0.08278858 0.01692819 0.3966161 -0.08334517 0.01707625 0.392158 -0.08024317 0.0170567 0.392158 -0.07970172 0.01690876 0.3966161 -0.07914811 0.01674008 0.401076 -0.07981055 0.01584869 0.4189471 -0.08043301 0.01611453 0.414475 -0.07741063 0.01609545 0.414475 -0.07680505 0.0158298 0.4189471 -0.07618564 0.01553648 0.423424 -0.07646453 0.01409578 0.441363 -0.07717376 0.01449888 0.436874 -0.07423865 0.01448035 0.436874 -0.07354819 0.01407748 0.441363 -0.07259917 0.01207321 0.462494 -0.06995862 0.01213276 0.4616727 -0.06746268 0.01112627 0.472727 -0.0663343 0.01075619 0.477183 -0.06512111 0.01041656 0.481628 -0.06381618 0.01011323 0.486062 -0.06090599 0.009638905 0.494889 -0.05928713 0.009479582 0.49928 -0.05754894 0.009379863 0.503654 -0.05568718 0.00934571 0.50801 -0.04567152 0.01112776 0.5383337 -0.04349493 0.01123178 0.5386202 -0.03530371 0.01242113 0.5487571 -0.03334635 0.01252132 0.549087 -0.03528922 0.01163917 0.541661 -0.02873492 0.01300269 0.552887 -0.01140761 0.01410859 0.5626454 0.01435703 0.01362401 0.5737826 -0.1030269 0.01922881 0.07372206 -0.09971028 0.01930022 0.09617638 -0.1031779 0.01927059 0.09397155 -0.1031659 0.01926779 0.1317952 -0.09969419 0.01929515 0.1317101 -0.1030023 0.01922219 0.1494979 -0.09887856 0.01906681 0.1829617 -0.1020241 0.01895147 0.1937468 -0.1023998 0.01905602 0.1806589 -0.101388 0.01877772 0.210946 -0.09760236 0.01870882 0.2194975 -0.09888494 0.01820534 0.2587635 -0.09747141 0.0179854 0.2793136 -0.09409505 0.01801204 0.2792971 -0.09559035 0.01779925 0.3034926 -0.09225463 0.01782584 0.3034291 -0.09205603 0.01771384 0.3425874 -0.0907911 0.01766902 0.3546531 -0.08757489 0.01769423 0.3546459 -0.08780103 0.01733899 0.3811823 -0.08465808 0.01736313 0.3811996 -0.0838896 0.01720499 0.387702 -0.08469223 0.0165444 0.40554 -0.08529025 0.01673525 0.401076 -0.08221918 0.01675939 0.401076 -0.08163708 0.01656836 0.40554 -0.08104181 0.0163539 0.410006 -0.07917404 0.01555526 0.423424 -0.08081096 0.01485657 0.432387 -0.08149421 0.01520931 0.427903 -0.07852333 0.01523268 0.427903 -0.07785779 0.0148797 0.432387 -0.07834786 0.01349526 0.4475288 -0.07550311 0.0135442 0.4472534 -0.07407277 0.01151663 0.468262 -0.07539856 0.01204478 0.4625586 -0.07176876 0.01004999 0.486062 -0.0731815 0.01035255 0.481628 -0.07049506 0.01041245 0.481628 -0.0690546 0.0107733 0.477183 -0.06780809 0.01043349 0.481628 -0.02339208 0.01121503 0.565448 -0.02195054 0.01078629 0.566122 -0.02563148 0.01042515 0.56494 -0.06181174 0.009495377 0.49928 -0.06002551 0.00939542 0.503654 -0.05811071 0.009360969 0.50801 -0.05606096 0.009397804 0.512345 -0.05386799 0.009511947 0.51666 -0.05155098 0.01050251 0.533594 -0.04799431 0.01097881 0.5379154 -0.04266977 0.01175993 0.5451907 -0.04050457 0.01192247 0.545537 -0.0404151 0.01118373 0.537675 -0.0302248 0.01294767 0.552887 -0.02548015 0.01337105 0.556329 -0.01679563 0.01382249 0.559587 0.009142994 0.01404756 0.5721904 -0.007339417 0.0142945 0.5654523 -0.002068102 0.01436156 0.5679978 0.003314435 0.01428657 0.5702535 -0.1105667 0.01865446 0 -0.1063328 0.01910674 0.05871063 -0.1028313 0.01917523 0.05617851 -0.1065403 0.01916331 0.07849156 -0.1066991 0.01920592 0.1138691 -0.1032226 0.01928347 0.1139401 -0.1064714 0.01914453 0.1495817 -0.1027108 0.01914191 0.1673667 -0.1061785 0.0190649 0.1673166 -0.1054763 0.01887392 0.1938059 -0.1039975 0.01848822 0.2291901 -0.1006342 0.01858353 0.2276354 -0.1023226 0.01813858 0.2580723 -0.0998252 0.01779514 0.2926079 -0.09649819 0.01787495 0.2921879 -0.09770536 0.01766884 0.3176144 -0.0944333 0.01774477 0.3170513 -0.09523499 0.01763999 0.3431255 -0.08984595 0.01760411 0.3634326 -0.09200924 0.01742696 0.3723149 -0.09303909 0.01753306 0.3634259 -0.08884286 0.01749742 0.3723198 -0.08700662 0.01718062 0.387702 -0.0889613 0.01683509 0.3966161 -0.08954858 0.01698273 0.392158 -0.08644729 0.01705193 0.392158 -0.08587527 0.01690399 0.3966161 -0.08408063 0.01633012 0.410006 -0.08582085 0.01575821 0.4189471 -0.08647698 0.01602339 0.414475 -0.08345538 0.01609075 0.414475 -0.082816 0.01582515 0.4189471 -0.08216238 0.01553183 0.423424 -0.0822966 0.01400786 0.441363 -0.08304327 0.01441037 0.436874 -0.08010894 0.01447582 0.436874 -0.07938092 0.01407289 0.441363 -0.07826822 0.01200562 0.4623045 -0.07586675 0.01025354 0.481628 -0.0772134 0.0105912 0.477183 -0.07449477 0.01069134 0.477183 -0.07296526 0.01112198 0.472727 -0.07177507 0.01075202 0.477183 -0.07024824 0.0087713 0.512345 -0.07021957 0.008914887 0.50801 -0.06788831 0.008962154 0.512345 -0.06604629 0.009634912 0.494889 -0.06433624 0.009475588 0.49928 -0.06250196 0.009376049 0.503654 -0.06053501 0.009341955 0.50801 -0.05842816 0.009379267 0.512345 -0.05617511 0.009493827 0.51666 -0.05376845 0.009691476 0.520952 -0.05119931 0.009971678 0.525215 -0.04844921 0.01032137 0.529435 -0.04550302 0.01072525 0.533594 -0.04234451 0.01116853 0.537675 -0.03320306 0.01277315 0.552887 -0.03626441 0.01240658 0.549284 -0.03171485 0.01287126 0.552887 -0.02683466 0.01330143 0.556329 -0.01351946 0.01409173 0.5626427 -0.125321 0.01742702 0 -0.122228 0.0177688 0 -0.1099678 0.01902341 0.07369279 -0.1066604 0.01919549 0.09614878 -0.1101083 0.01906144 0.09176063 -0.1101366 0.01906907 0.127291 -0.1066418 0.01919054 0.1316585 -0.1097303 0.01896035 0.1629098 -0.1058643 0.01897901 0.1806319 -0.1093243 0.01885187 0.1807681 -0.1048368 0.01870107 0.2109249 -0.1084565 0.01861977 0.2067046 -0.1054154 0.01795446 0.2630285 -0.10116 0.01795178 0.2750836 -0.1024414 0.01761239 0.301425 -0.09874713 0.01771467 0.3055943 -0.09722614 0.01747882 0.3546468 -0.09401208 0.01759731 0.3546355 -0.0940774 0.01715385 0.3811661 -0.09093624 0.01726895 0.3811878 -0.09012305 0.01711106 0.387702 -0.09079974 0.01636379 0.40554 -0.09142976 0.01655369 0.401076 -0.08836066 0.01666682 0.401076 -0.08774667 0.01647639 0.40554 -0.08711886 0.01626229 0.410006 -0.08743345 0.01503372 0.427903 -0.08813649 0.01535511 0.423424 -0.08515006 0.01546519 0.423424 -0.08446449 0.01514309 0.427903 -0.08376353 0.01479071 0.432387 -0.08404648 0.0132811 0.4479788 -0.08132159 0.01347428 0.4470646 -0.07963031 0.01135224 0.468262 -0.08098173 0.01186126 0.4627371 -0.07685214 0.01145458 0.468262 -0.07571589 0.01106065 0.472727 -0.07375109 0.009351074 0.494889 -0.07190591 0.009196817 0.49928 -0.07442545 0.009030759 0.49928 -0.07024931 0.009789824 0.490483 -0.06861579 0.009577572 0.494889 -0.06686097 0.009419322 0.49928 -0.06497722 0.009320795 0.503654 -0.06295818 0.009287893 0.50801 -0.06079518 0.009326457 0.512345 -0.05848199 0.009442389 0.51666 -0.05601114 0.009641468 0.520952 -0.05337178 0.009923219 0.525215 -0.05054754 0.01027452 0.529435 -0.04752016 0.01068025 0.533594 -0.0378772 0.01230031 0.549284 -0.03468936 0.01265287 0.552887 -0.02284455 0.01359963 0.559587 -0.01774585 0.01387423 0.5626393 -0.0100125 0.01421552 0.5654509 -0.01562893 0.01401382 0.5626407 0.008410692 0.01404196 0.5721903 -0.008683204 0.0142678 0.565448 -0.003148853 0.01434004 0.567996 0.002225399 0.01426213 0.5702532 -0.1172211 0.01822024 0 -0.1132326 0.01879203 0.05615049 -0.1097668 0.01897001 0.05616134 -0.1134372 0.01884561 0.07379829 -0.1101685 0.01907771 0.1095983 -0.1136444 0.01890039 0.1118373 -0.113583 0.01888442 0.1316561 -0.1099961 0.01903134 0.1450823 -0.1131061 0.01875919 0.1673507 -0.1089233 0.01874434 0.1939046 -0.1123764 0.01856696 0.1939076 -0.1118997 0.01844257 0.2067322 -0.1076184 0.0184074 0.2254047 -0.11104 0.01822865 0.2256175 -0.1085614 0.01773822 0.2667101 -0.1038868 0.01774477 0.2837287 -0.1068968 0.01753383 0.2881921 -0.1056019 0.01743102 0.3034309 -0.1043514 0.01737731 0.3173078 -0.1010295 0.01754701 0.3174674 -0.09848499 0.01752042 0.3431009 -0.1017413 0.01735383 0.3430062 -0.09622848 0.0174154 0.363439 -0.09941333 0.01725155 0.363462 -0.09833937 0.01714825 0.3722977 -0.09517663 0.01731067 0.3722972 -0.09323811 0.01699626 0.387702 -0.09264868 0.01686853 0.392158 -0.09512865 0.01656317 0.3966161 -0.09574663 0.01670944 0.392158 -0.09204596 0.01672148 0.3966161 -0.09015578 0.01615041 0.410006 -0.09251576 0.01575708 0.414475 -0.08949732 0.01591211 0.414475 -0.09182602 0.01549327 0.4189471 -0.08882433 0.01564753 0.4189471 -0.0867148 0.01468199 0.432387 -0.08890783 0.01415175 0.436874 -0.08597642 0.01430237 0.436874 -0.08812373 0.01375085 0.441363 -0.08521109 0.01390045 0.441363 -0.08375793 0.01170468 0.4628681 -0.0784654 0.01095932 0.472727 -0.07993024 0.01045167 0.477183 -0.08170574 0.0109629 0.4710094 -0.07706564 0.009816467 0.486062 -0.07546842 0.009559631 0.490483 -0.07807499 0.00938785 0.490483 -0.074418 0.009952425 0.486062 -0.0728597 0.009693622 0.490483 -0.07118427 0.009482979 0.494889 -0.06938415 0.009326338 0.49928 -0.06745201 0.0092296 0.503654 -0.06538015 0.009198665 0.50801 -0.06316101 0.009239256 0.512345 -0.06078755 0.009357392 0.51666 -0.05825155 0.009558796 0.520952 -0.05554294 0.00984323 0.525215 -0.05264449 0.01019722 0.529435 -0.04953682 0.01060599 0.533594 -0.03948718 0.01217013 0.549284 -0.03617388 0.01250976 0.552887 -0.0240513 0.01350206 0.559587 -0.01932007 0.01372689 0.562636 -0.02042686 0.01374143 0.559587 -0.004224896 0.01429772 0.5679973 -0.1319392 0.01653623 0 -0.1135783 0.01888304 0.09162241 -0.1170443 0.01865482 0.09176242 -0.1170744 0.01866221 0.1273232 -0.1134081 0.0188387 0.14957 -0.1162433 0.01844686 0.1806907 -0.1127173 0.01865774 0.1829396 -0.1153143 0.01820892 0.2072823 -0.1138784 0.01787191 0.2364621 -0.1099157 0.01728355 0.2921631 -0.1076739 0.01715964 0.3171243 -0.1036598 0.01710247 0.3545955 -0.1004487 0.01731401 0.3545973 -0.1003434 0.01678663 0.3811657 -0.09721326 0.01699304 0.3811576 -0.09635114 0.01683646 0.387702 -0.09756141 0.01619422 0.401076 -0.09449696 0.01639622 0.401076 -0.09385097 0.01620715 0.40554 -0.09319078 0.0159946 0.410006 -0.09112101 0.01520192 0.423424 -0.09410297 0.0150054 0.423424 -0.09040057 0.01488137 0.427903 -0.08966422 0.01453053 0.432387 -0.09073597 0.01340138 0.4430883 -0.08689194 0.01311308 0.4481863 -0.0857973 0.01122546 0.4660162 -0.08123153 0.009939074 0.481628 -0.0797109 0.009642064 0.486062 -0.08235329 0.009428381 0.486062 -0.07855033 0.0101158 0.481628 -0.06992501 0.009102642 0.503654 -0.06780099 0.00907433 0.50801 -0.06552559 0.009117841 0.512345 -0.06309193 0.009239017 0.51666 -0.06049162 0.009443879 0.520952 -0.05771374 0.009731769 0.525215 -0.05473995 0.01008963 0.529435 -0.03765565 0.01234281 0.552887 -0.04109448 0.0120151 0.549284 -0.02036869 0.01360869 0.562636 -0.02525705 0.01338589 0.559587 -0.02163577 0.01367926 0.559587 0.007676362 0.01401495 0.5721902 0.01353043 0.01359701 0.5737822 0.001142382 0.01420646 0.5702537 -0.1166937 0.01856368 0.05610388 -0.1169021 0.0186178 0.07397294 -0.1203629 0.01833766 0.07390409 -0.1205717 0.01839119 0.1139865 -0.1171066 0.01867103 0.1095471 -0.1205123 0.01837575 0.131726 -0.1169306 0.01862496 0.145035 -0.1166583 0.0185545 0.1628504 -0.1200241 0.01825153 0.1673461 -0.1157523 0.01832073 0.1960548 -0.1147477 0.01806885 0.2199571 -0.114988 0.01719325 0.2712606 -0.1122325 0.01756483 0.2624115 -0.1109557 0.01738846 0.2795035 -0.1089339 0.01721161 0.3034081 -0.1120628 0.01693314 0.305537 -0.1082369 0.01687824 0.3428899 -0.10499 0.0171402 0.3429525 -0.1057898 0.01678442 0.3634184 -0.1026033 0.01704174 0.3634402 -0.1014956 0.01693993 0.3723148 -0.1025685 0.01638007 0.387702 -0.09946155 0.01663142 0.387702 -0.09884208 0.01650542 0.392158 -0.09820878 0.01636022 0.3966161 -0.09689962 0.01600623 0.40554 -0.09854418 0.01531469 0.414475 -0.09622305 0.01579469 0.410006 -0.0955317 0.0155583 0.414475 -0.09482508 0.01529568 0.4189471 -0.09336507 0.01468592 0.427903 -0.0947622 0.01372212 0.436874 -0.09261107 0.01433628 0.432387 -0.09183663 0.01395875 0.436874 -0.09190946 0.01234847 0.4517601 -0.08913284 0.01262336 0.4513122 -0.08670091 0.01041543 0.472727 -0.08395856 0.01063722 0.472727 -0.08264482 0.01027268 0.477183 -0.07504838 0.008486986 0.50801 -0.07745695 0.008215665 0.50801 -0.07732909 0.008502602 0.503654 -0.07631576 0.009182095 0.494889 -0.06725597 0.008766293 0.529435 -0.07228279 0.008055329 0.5259224 -0.07067567 0.00836122 0.525215 -0.07239603 0.008939743 0.503654 -0.06539404 0.009087324 0.51666 -0.06272941 0.009296357 0.520952 -0.04430228 0.01162582 0.549284 -0.03913474 0.01215034 0.552887 -0.04061025 0.01193064 0.552887 -0.04270017 0.01183426 0.549284 -0.02141523 0.01347249 0.562636 -0.01537293 0.0136922 0.5654492 -0.02818918 0.01321232 0.556329 -0.01179641 0.01409786 0.5654506 -0.00567609 0.01420211 0.5679969 -0.1385385 0.01538991 0 -0.1201516 0.0182842 0.05614954 -0.1205248 0.01837843 0.09405535 -0.1239493 0.01803743 0.08942496 -0.1240163 0.01805353 0.1227836 -0.1203337 0.01833057 0.1495506 -0.1236495 0.01796263 0.1584675 -0.1195645 0.01813483 0.1851432 -0.1232592 0.01786559 0.1762974 -0.1190351 0.01800096 0.2003951 -0.1183911 0.01784127 0.2155607 -0.1218156 0.01750993 0.2156469 -0.117435 0.01762384 0.2341073 -0.118129 0.01684308 0.2740222 -0.1132242 0.01700741 0.2926734 -0.1165596 0.01668459 0.2927628 -0.1109924 0.01689261 0.3169624 -0.106862 0.01684296 0.3546317 -0.1106 0.01655066 0.3502244 -0.1046594 0.01668506 0.372276 -0.1037958 0.01657748 0.378797 -0.107206 0.01631379 0.3767467 -0.103189 0.016487 0.383249 -0.1019341 0.01625537 0.392158 -0.1006225 0.01594662 0.401076 -0.1036795 0.015652 0.401076 -0.1012855 0.01611137 0.3966161 -0.09994482 0.01575994 0.40554 -0.09925216 0.01554965 0.410006 -0.09782087 0.01505339 0.4189471 -0.09632647 0.01444649 0.427903 -0.09928375 0.01416146 0.427903 -0.09708166 0.01476442 0.423424 -0.0955547 0.01409822 0.432387 -0.09362673 0.01316332 0.4431262 -0.09596592 0.01263183 0.445853 -0.08831894 0.01091629 0.4669637 -0.09104776 0.01063245 0.4671427 -0.08390986 0.009722411 0.481628 -0.08658462 0.009464621 0.481628 -0.08535641 0.01005339 0.477183 -0.08196473 0.00830239 0.49928 -0.08143597 0.008728384 0.494889 -0.07945549 0.008584976 0.49928 -0.08067864 0.009177267 0.490483 -0.07887756 0.008974969 0.494889 -0.07694214 0.008827269 0.49928 -0.07486414 0.008740127 0.503654 -0.07263559 0.008719563 0.50801 -0.02928429 0.01004678 0.56369 -0.03291428 0.009645998 0.562382 -0.03145849 0.01046371 0.562636 -0.06769388 0.008901298 0.51666 -0.06496495 0.009115576 0.520952 -0.06204837 0.009413659 0.525215 -0.03476357 0.01159995 0.559587 -0.0415427 0.01097196 0.556329 -0.04023748 0.01134425 0.556329 -0.04500275 0.01108002 0.552887 -0.04354512 0.01139879 0.552887 -0.03892147 0.01167231 0.556329 -0.04589992 0.01138782 0.549284 -0.04208034 0.01168102 0.552887 -0.04472047 0.01158142 0.5448799 -0.01666647 0.01347714 0.565448 -0.0224598 0.01331692 0.562636 -0.02954077 0.01310288 0.556329 -0.01359099 0.01392489 0.5654495 0.006945431 0.01396685 0.5721902 5.33453e-5 0.01411849 0.5702536 -0.1236042 0.01795136 0.05612373 -0.1238187 0.01800483 0.07396268 -0.1272954 0.01762247 0.07633751 -0.1240229 0.01805555 0.1050217 -0.1274861 0.01766872 0.1139202 -0.1238986 0.0180239 0.1405884 -0.1274231 0.01765358 0.1317321 -0.1269209 0.01753097 0.1673242 -0.1228627 0.01776689 0.1895158 -0.1224725 0.01766955 0.2004094 -0.1250177 0.01707422 0.2201063 -0.1207279 0.01726442 0.2365351 -0.1153773 0.01661276 0.305606 -0.1186976 0.01624023 0.3055084 -0.1144003 0.0165804 0.3156014 -0.111955 0.01656717 0.3388323 -0.1152269 0.01620209 0.3385519 -0.1095187 0.01651048 0.3590553 -0.1083855 0.01643508 0.367912 -0.1115528 0.01607936 0.3678742 -0.1063064 0.01618659 0.383249 -0.105022 0.01595777 0.392158 -0.1081046 0.01561051 0.392158 -0.1056714 0.01608115 0.387702 -0.1043581 0.01581525 0.3966161 -0.102986 0.01546686 0.40554 -0.1015527 0.01502478 0.414475 -0.1045562 0.01468634 0.414475 -0.1022772 0.01525819 0.410006 -0.1008126 0.01476508 0.4189471 -0.1000562 0.01447778 0.423424 -0.09768378 0.01344054 0.436874 -0.1006006 0.013112 0.436874 -0.09849441 0.01381486 0.432387 -0.09684377 0.01304423 0.441363 -0.09467864 0.01203286 0.45218 -0.08864843 0.009928107 0.4754034 -0.09135013 0.009618461 0.475448 -0.08653879 0.008108973 0.494889 -0.08587449 0.008634269 0.490483 -0.08399003 0.008440673 0.494889 -0.08499211 0.009174108 0.486062 -0.08327871 0.008926689 0.490483 -0.07260495 0.008544206 0.512345 -0.06999051 0.008679986 0.51666 -0.0671969 0.008900403 0.520952 -0.06421124 0.009205162 0.525215 -0.06101417 0.009581208 0.529435 -0.05753141 0.01002269 0.5337574 -0.04993528 0.01098954 0.541661 -0.04567456 0.01150345 0.545537 -0.02453738 0.01294052 0.562636 -0.0235005 0.01314026 0.562636 -0.01754254 0.0133084 0.565448 -0.03089141 0.01297277 0.556329 -0.00712043 0.01406264 0.5679968 -0.008560657 0.0138747 0.5679965 0.006207108 0.01389569 0.5721901 -0.1267049 0.01747786 0.03335988 -0.1270532 0.01756322 0.05620008 -0.1306408 0.01715093 0.06745433 -0.1274443 0.01765835 0.09610497 -0.1308331 0.01719689 0.08727037 -0.1309139 0.01721626 0.122832 -0.1272416 0.01760888 0.1495113 -0.1305382 0.01712656 0.1584656 -0.1264449 0.01741528 0.1851891 -0.1301387 0.01703077 0.176281 -0.1258241 0.01726371 0.2024579 -0.1288607 0.01672685 0.2113151 -0.1239057 0.01683717 0.2402091 -0.1214721 0.01646131 0.2743018 -0.1198948 0.01630872 0.292772 -0.1232246 0.01587581 0.2927522 -0.1177048 0.0162096 0.3154929 -0.1138135 0.01618897 0.3502107 -0.1170135 0.01577216 0.350232 -0.1127132 0.01615166 0.3590085 -0.1103399 0.01596093 0.3767441 -0.1134704 0.01555442 0.3767222 -0.1094186 0.015836 0.383249 -0.1087689 0.01573216 0.387702 -0.1074255 0.01546972 0.3966161 -0.1060221 0.01512485 0.40554 -0.1090517 0.01473057 0.40554 -0.1067314 0.01530826 0.401076 -0.105297 0.01491802 0.410006 -0.1037992 0.01442861 0.4189471 -0.1022361 0.01382887 0.427903 -0.1051822 0.01344555 0.427903 -0.1030259 0.01414322 0.423424 -0.1014291 0.01348429 0.432387 -0.09974193 0.01271772 0.441363 -0.09744614 0.01167523 0.4525621 -0.1013775 0.0117765 0.4475442 -0.09884476 0.01230752 0.445853 -0.09375971 0.01030242 0.467346 -0.09536647 0.009604811 0.4712783 -0.09104847 0.007912278 0.490483 -0.09025549 0.008535265 0.486062 -0.08846479 0.008297204 0.490483 -0.08925479 0.009163856 0.481628 -0.08762657 0.008877396 0.486062 -0.0796473 0.007624745 0.512345 -0.07685333 0.007784008 0.51666 -0.07912802 0.007397949 0.51666 -0.07978987 0.008225381 0.503654 -0.06719046 0.008171975 0.537675 -0.07148271 0.007591962 0.533594 -0.07000821 0.008011698 0.5331518 -0.07495772 0.008279204 0.512345 -0.07228332 0.008421719 0.51666 -0.06942534 0.008649349 0.520952 -0.06637114 0.008961856 0.525215 -0.06246513 0.009422779 0.5302395 -0.05225551 0.01072347 0.5412368 -0.04739302 0.01130998 0.545537 -0.01841473 0.01311767 0.565448 -0.0255686 0.01271486 0.562636 -0.03223919 0.01282089 0.556329 -0.02645981 0.01325035 0.559587 -0.002121925 0.01383376 0.5702537 -0.001034557 0.01399594 0.5702537 0.0127927 0.01352691 0.5737822 -0.1303652 0.01708483 0.04744118 -0.1341477 0.01665627 0.07394015 -0.1309236 0.01721793 0.1049855 -0.1343682 0.01670783 0.1094532 -0.1307906 0.01718693 0.1407067 -0.1338852 0.01659494 0.1628857 -0.129731 0.01693326 0.1895157 -0.1294117 0.01685667 0.1982863 -0.1329979 0.0163868 0.1938824 -0.1279608 0.01652944 0.2288542 -0.1270139 0.01634752 0.2444083 -0.1248426 0.01602184 0.2743376 -0.1280571 0.01551163 0.2757824 -0.1220046 0.01580989 0.3055087 -0.1246994 0.01529675 0.3115193 -0.121001 0.01578205 0.3154007 -0.1184806 0.01578128 0.3383635 -0.1217325 0.01530069 0.338129 -0.1158932 0.01573801 0.3590011 -0.1147103 0.01566898 0.367855 -0.1178538 0.01520043 0.3678677 -0.1125243 0.01543188 0.383249 -0.1111809 0.01521027 0.392158 -0.1142491 0.0147531 0.392158 -0.11186 0.01532995 0.387702 -0.1104866 0.01507133 0.3966161 -0.1097769 0.014912 0.401076 -0.1075533 0.01429635 0.414475 -0.1105427 0.01385098 0.414475 -0.1083105 0.01452583 0.410006 -0.1067796 0.01404076 0.4189471 -0.1059893 0.01375758 0.423424 -0.1043578 0.01310324 0.432387 -0.102634 0.01234149 0.441363 -0.1055186 0.01191163 0.441363 -0.1035112 0.01273322 0.436874 -0.09949296 0.01098179 0.455982 -0.1022691 0.0105552 0.4560808 -0.09346532 0.009136855 0.477183 -0.09524661 0.008538126 0.4798435 -0.09191942 0.008817136 0.481628 -0.08464783 0.0071401 0.50801 -0.08469468 0.007540941 0.503654 -0.0822581 0.007545709 0.50801 -0.0844686 0.007976531 0.49928 -0.08224546 0.00790584 0.503654 -0.07986062 0.00790286 0.50801 -0.07730555 0.007973611 0.512345 -0.07457131 0.008124053 0.51666 -0.07164913 0.008360028 0.520952 -0.06852614 0.008681476 0.525215 -0.06485617 0.009113788 0.5298861 -0.05772852 0.01002317 0.537675 -0.05357539 0.01054763 0.541661 -0.04910808 0.01108682 0.545537 -0.0201382 0.0126571 0.565448 -0.01928019 0.01290196 0.565448 -0.01241773 0.01303672 0.567996 -0.03358423 0.01264584 0.556329 -0.0276606 0.01309406 0.559587 0.005489706 0.01380211 0.5721902 -0.1339247 0.01660406 0.05613631 -0.137466 0.01605093 0.0649957 -0.1342998 0.01669198 0.09160506 -0.1377902 0.01612555 0.118363 -0.1343311 0.01669973 0.1272808 -0.1341755 0.01666349 0.1450733 -0.1374712 0.01605236 0.1540149 -0.1335639 0.01651984 0.1761549 -0.1369783 0.01594007 0.1761764 -0.1333017 0.01645827 0.1850335 -0.1326463 0.0163052 0.2027522 -0.1356685 0.0156418 0.2113338 -0.1320555 0.01617115 0.2157542 -0.131097 0.01597172 0.2333227 -0.1300142 0.015778 0.2501258 -0.1265303 0.01537966 0.2929303 -0.1294184 0.01479357 0.2972962 -0.1234022 0.01475548 0.3501871 -0.1202114 0.0152961 0.3502209 -0.1190662 0.01526552 0.3589954 -0.1165891 0.0150898 0.3767213 -0.1196942 0.01456212 0.3767417 -0.115622 0.01497036 0.383249 -0.1149431 0.01487058 0.387702 -0.1135396 0.01461648 0.3966161 -0.1150857 0.01376914 0.40554 -0.1128146 0.01445943 0.401076 -0.1120736 0.01428037 0.40554 -0.1113164 0.01407802 0.410006 -0.1097525 0.0135979 0.4189471 -0.1081208 0.0130077 0.427903 -0.11105 0.01251059 0.427903 -0.1089451 0.01331728 0.423424 -0.1072788 0.01266801 0.432387 -0.1064143 0.01230072 0.436874 -0.104216 0.01134413 0.4476189 -0.1070562 0.0108568 0.4476587 -0.09822696 0.00922352 0.470924 -0.1007791 0.008718073 0.4714594 -0.09287762 0.008144617 0.486062 -0.09549129 0.007700979 0.486062 -0.08945542 0.007181942 0.49928 -0.08956778 0.006658077 0.503654 -0.09193497 0.00670427 0.49928 -0.08908087 0.007730245 0.494889 -0.08696597 0.007604479 0.49928 -0.07386726 0.00802958 0.520952 -0.05991494 0.009700715 0.5374714 -0.05538904 0.01027745 0.541661 -0.05081772 0.01083189 0.545537 0.008166134 0.01272529 0.573311 0.01093864 0.01298689 0.573782 0.01199436 0.01284027 0.573935 -0.03492653 0.01244592 0.556329 -0.0288586 0.01291561 0.559587 -0.003200471 0.01362544 0.5702535 0.004048287 0.01352208 0.5721905 -0.1372133 0.01599329 0.04736936 -0.1409811 0.01541823 0.07394629 -0.1376588 0.01609492 0.08274036 -0.1377727 0.01612114 0.1005864 -0.1412063 0.01546895 0.1094939 -0.1376959 0.01610374 0.1362012 -0.1411699 0.01546078 0.1272971 -0.1406092 0.01533561 0.1672583 -0.1407959 0.01537758 0.1583657 -0.1372068 0.01599168 0.1671973 -0.1367141 0.01587927 0.1850236 -0.1397147 0.01513588 0.1961258 -0.1363226 0.01578986 0.1960999 -0.1385985 0.01489406 0.2202774 -0.1347332 0.01544678 0.229031 -0.13343 0.01520913 0.2496876 -0.1362985 0.01449489 0.2561607 -0.1309646 0.01490521 0.2806611 -0.1342186 0.01426112 0.2813473 -0.1310272 0.01410859 0.3135323 -0.1277331 0.01473671 0.3138399 -0.1248706 0.01475709 0.3386471 -0.1280924 0.01413965 0.3385044 -0.1222261 0.0147292 0.3590011 -0.1241168 0.01406651 0.3678473 -0.1253742 0.0141226 0.3590033 -0.1209844 0.01466846 0.3678888 -0.1187096 0.01444631 0.383249 -0.1180164 0.01434898 0.387702 -0.1203538 0.01364713 0.392158 -0.1210774 0.01375925 0.387702 -0.1173076 0.01423406 0.392158 -0.1165829 0.01410001 0.3966161 -0.1158424 0.01394546 0.401076 -0.1143125 0.01356959 0.410006 -0.1156672 0.01252633 0.4189471 -0.1164906 0.01277351 0.414475 -0.1135225 0.01334524 0.414475 -0.1127157 0.01309496 0.4189471 -0.1118916 0.0128172 0.423424 -0.1101905 0.01217389 0.432387 -0.1112579 0.01087182 0.441363 -0.1121904 0.01125431 0.436874 -0.1093081 0.01180958 0.436874 -0.108394 0.01142364 0.441363 -0.1050215 0.01005882 0.4562972 -0.1066503 0.009118497 0.4607284 -0.09886324 0.007297813 0.484227 -0.1022381 0.007899403 0.4752316 -0.09788835 0.008082449 0.4798986 -0.09413886 0.006813883 0.494889 -0.09618902 0.006981015 0.490483 -0.09362387 0.007475197 0.490483 -0.09161496 0.007300198 0.494889 -0.08713603 0.007126629 0.503654 -0.0823329 0.006232678 0.5214133 -0.08047139 0.006750702 0.520952 -0.08198153 0.007228553 0.512345 -0.06904584 0.007642328 0.537675 -0.06607353 0.007710397 0.541661 -0.07087922 0.00703758 0.537675 -0.07607823 0.007654309 0.520952 -0.0400846 0.008795559 0.559561 -0.03918004 0.009642779 0.559587 -0.03651612 0.009226679 0.561009 -0.06220304 0.009329259 0.5370695 -0.05719655 0.009970664 0.541661 -0.05252319 0.01054269 0.545537 -0.04749226 0.01111745 0.549284 5.48378e-4 0.01241314 0.571882 0.0021829 0.01278269 0.57219 0.004351437 0.01258295 0.572627 -0.03626424 0.01221889 0.556329 -0.03005182 0.01271301 0.559587 0.003340065 0.01331967 0.5721904 0.01152896 0.01325976 0.573782 -0.00998491 0.01363211 0.5679964 0.00477308 0.01368057 0.5721904 -0.1436452 0.014517 0.02654844 -0.1407519 0.01536709 0.0561214 -0.1442658 0.01465284 0.06511545 -0.1411378 0.01545351 0.09172272 -0.1445791 0.01472127 0.100634 -0.1445979 0.01472514 0.1183967 -0.1410108 0.0154252 0.1450759 -0.1443384 0.01466864 0.1494495 -0.140383 0.01528459 0.1761359 -0.143489 0.01448404 0.1851461 -0.1437644 0.01454377 0.176217 -0.1401122 0.01522421 0.1850476 -0.1421933 0.01420569 0.2158693 -0.1428125 0.01433628 0.2027646 -0.1392384 0.01503008 0.2072842 -0.1375635 0.01469695 0.2378808 -0.1411837 0.01401197 0.2335997 -0.1387234 0.0136556 0.2674956 -0.1326946 0.01415932 0.297425 -0.1364898 0.01346778 0.2922306 -0.1317678 0.01343339 0.3346408 -0.1291213 0.01344913 0.3546249 -0.1303245 0.0134527 0.3457684 -0.1265752 0.01414436 0.3501806 -0.1255511 0.01325958 0.378797 -0.1265611 0.01334577 0.3722597 -0.1227919 0.01396578 0.376734 -0.1217852 0.01385372 0.383249 -0.1196143 0.01351594 0.3966161 -0.1210708 0.01253807 0.40554 -0.1218587 0.012708 0.401076 -0.1188583 0.01336443 0.401076 -0.118086 0.01319116 0.40554 -0.1172968 0.01299458 0.410006 -0.1148262 0.01225179 0.423424 -0.1159758 0.01098388 0.432387 -0.11687 0.01131343 0.427903 -0.1139675 0.0119484 0.427903 -0.1130906 0.01161509 0.432387 -0.1102836 0.01047402 0.445853 -0.1105181 0.00888431 0.456601 -0.1120683 0.009451925 0.450341 -0.1088358 0.009898006 0.452175 -0.1079924 0.008072376 0.4657409 -0.09961098 0.006500542 0.4885894 -0.09198701 0.006128787 0.503654 -0.09174799 0.005577385 0.50801 -0.09438973 0.005530059 0.503654 -0.08661961 0.006274521 0.512345 -0.08939611 0.006163418 0.50801 -0.08702814 0.006681501 0.50801 -0.08430653 0.006780624 0.512345 -0.08139377 0.006961405 0.51666 -0.0782805 0.007230043 0.520952 -0.0747919 0.007598936 0.5254925 -0.06755435 0.008510947 0.533594 -0.06343322 0.009050846 0.537675 -0.05899721 0.009623706 0.541661 -0.05422168 0.01021552 0.545537 -0.04907941 0.01081192 0.549284 -0.03759646 0.01196229 0.556329 -0.03124147 0.01248395 0.559587 0.01117885 0.01312422 0.5737821 0.01205843 0.01340305 0.5737822 -0.1440054 0.0145961 0.04734933 -0.1473697 0.0137577 0.04734355 -0.1444621 0.01469552 0.08274161 -0.147832 0.01385575 0.08274596 -0.1479694 0.01388502 0.1184381 -0.1445012 0.01470404 0.1361829 -0.1478712 0.01386415 0.1362017 -0.1441894 0.01463568 0.1582925 -0.1439994 0.01459443 0.1672025 -0.147359 0.01375585 0.1673283 -0.143177 0.01441532 0.1938986 -0.146528 0.01357918 0.1939583 -0.1445094 0.0131818 0.2336547 -0.1452715 0.01332181 0.2206724 -0.139999 0.01382011 0.2511112 -0.1433002 0.01299285 0.2512726 -0.1393538 0.01263487 0.2962146 -0.1345227 0.0134021 0.3111695 -0.1375783 0.01259934 0.3126417 -0.1334688 0.01266884 0.3457798 -0.1278684 0.013417 0.363448 -0.1296316 0.01258015 0.3722709 -0.130971 0.0126447 0.3634293 -0.1248449 0.01318436 0.383249 -0.1241227 0.01309293 0.387702 -0.1233845 0.01298403 0.392158 -0.1256249 0.01210981 0.3966161 -0.1263943 0.01223403 0.392158 -0.12263 0.01285618 0.3966161 -0.1202657 0.01234507 0.410006 -0.1194433 0.01212739 0.414475 -0.1215196 0.01115715 0.4189471 -0.1223759 0.0113967 0.414475 -0.1186034 0.01188391 0.4189471 -0.1177457 0.01161301 0.423424 -0.1150579 0.01062685 0.436874 -0.1141071 0.01024848 0.441363 -0.1159245 0.009154379 0.445853 -0.1169369 0.009543359 0.441363 -0.1131138 0.009854793 0.445853 -0.1107485 0.007423996 0.4654961 -0.1132426 0.00818485 0.4567327 -0.1030753 0.006977379 0.4801627 -0.103973 0.006073355 0.4844173 -0.1078803 0.006732761 0.4742433 -0.09664988 0.006264507 0.494889 -0.09685164 0.00555402 0.49928 -0.1001011 0.005693256 0.4929922 -0.09440171 0.00616455 0.49928 -0.07948338 0.00582844 0.529435 -0.08333891 0.005318701 0.525215 -0.07792007 0.00642091 0.5290273 -0.0836479 0.006468236 0.51666 -0.0770756 0.00712192 0.525215 -0.0653184 0.008638441 0.537675 -0.06078916 0.009231805 0.541661 -0.05591034 0.009845852 0.545537 -0.05065762 0.01046651 0.549284 -0.003240108 0.01221561 0.571078 -0.007012069 0.0119906 0.57021 -0.00650388 0.01240146 0.570253 -0.03242462 0.01222509 0.559587 -0.01102334 0.01340949 0.567996 -0.1504655 0.01275622 0.03348213 -0.1476334 0.01381343 0.06506597 -0.1510813 0.0128836 0.07396632 -0.1479507 0.01388108 0.1005989 -0.1512446 0.0129171 0.09174305 -0.151278 0.01292407 0.1272701 -0.1477079 0.01382935 0.1493993 -0.150891 0.01284438 0.1583395 -0.1510477 0.01287633 0.1493574 -0.1475529 0.01379674 0.1583878 -0.1471248 0.01370596 0.1762515 -0.1468484 0.01364707 0.1851333 -0.1501769 0.01269716 0.1851236 -0.1461632 0.01350152 0.2027582 -0.1457418 0.01341462 0.2117167 -0.1490534 0.01246803 0.2117664 -0.1472143 0.01214569 0.2425485 -0.1419566 0.0128284 0.2682136 -0.1444339 0.01182633 0.2770811 -0.1414425 0.01168447 0.3068413 -0.1349735 0.01264184 0.334387 -0.1389372 0.01172131 0.3279204 -0.1322541 0.01267057 0.3545683 -0.1353533 0.01178693 0.3545454 -0.1286038 0.01249891 0.378797 -0.1308952 0.01156747 0.383249 -0.1316292 0.01163524 0.378797 -0.1278836 0.01242715 0.383249 -0.1271472 0.01233923 0.387702 -0.1248386 0.01196545 0.401076 -0.1240352 0.01179939 0.40554 -0.1261366 0.01077604 0.410006 -0.1269731 0.01096075 0.40554 -0.1232143 0.01161026 0.410006 -0.1206453 0.01089042 0.423424 -0.1197527 0.01059514 0.427903 -0.1188413 0.01026976 0.432387 -0.1207283 0.009111523 0.436874 -0.1216812 0.009459137 0.432387 -0.1179059 0.009917199 0.436874 -0.1148591 0.008756458 0.450341 -0.115253 0.007181286 0.459311 -0.116476 0.007572233 0.454828 -0.1103758 0.005951762 0.4746392 -0.1025626 0.004981577 0.4930454 -0.09626322 0.004135787 0.5082866 -0.0926032 0.004966437 0.5103022 -0.08891683 0.005702078 0.512345 -0.08810526 0.005277097 0.51666 -0.08588653 0.005910396 0.51666 -0.07533967 0.00640583 0.533594 -0.07267707 0.006339311 0.537675 -0.07547163 0.007062196 0.529435 -0.0436176 0.008352637 0.558038 -0.04711723 0.007897853 0.55644 -0.04649025 0.008779227 0.556329 -0.06256777 0.008788526 0.541661 -0.05758851 0.009427726 0.545537 -0.05222421 0.01007598 0.549284 -0.04644966 0.01071947 0.552887 -0.03359955 0.01193237 0.559587 -0.02659237 0.01245969 0.562636 -0.01172345 0.01323485 0.567996 -0.004252672 0.0133621 0.5702543 -0.150845 0.01283478 0.05622875 -0.1540001 0.01171892 0.04737657 -0.1544736 0.01181358 0.08281224 -0.1513158 0.01293188 0.1095044 -0.1546162 0.01184213 0.1137202 -0.1511639 0.01290053 0.1405076 -0.1544643 0.01181185 0.1405039 -0.1506937 0.01280385 0.1673356 -0.1537516 0.01166927 0.1761724 -0.1539906 0.01171708 0.1672786 -0.1504571 0.01275503 0.1762353 -0.1498527 0.01263004 0.1939641 -0.1529547 0.01150989 0.1983988 -0.1494815 0.01255369 0.2027822 -0.1485784 0.0123769 0.2207104 -0.1480563 0.01228314 0.2296035 -0.1507622 0.01111698 0.2382669 -0.1515942 0.01125341 0.2250884 -0.1458955 0.01196956 0.2601031 -0.1494564 0.01094019 0.2560419 -0.1454414 0.0106514 0.299292 -0.1377604 0.01175427 0.337058 -0.1365887 0.01177859 0.3457719 -0.1390516 0.01077258 0.3501377 -0.140282 0.01074749 0.3413534 -0.1340444 0.01176834 0.363413 -0.1326736 0.01171094 0.3722884 -0.13535 0.01069796 0.374347 -0.1363895 0.0107482 0.3678475 -0.1301447 0.01148366 0.387702 -0.1293774 0.01138246 0.392158 -0.1285932 0.01126253 0.3966161 -0.13071 0.01015973 0.401076 -0.1315262 0.01029497 0.3966161 -0.1277918 0.0111224 0.401076 -0.1252822 0.010567 0.414475 -0.1244097 0.01033216 0.4189471 -0.1263586 0.009133398 0.423424 -0.1272656 0.009390056 0.4189471 -0.1235191 0.01007014 0.423424 -0.1226096 0.009779512 0.427903 -0.1197413 0.008742809 0.441363 -0.1187103 0.008359193 0.445853 -0.1203582 0.007065296 0.450341 -0.1214629 0.007451117 0.445853 -0.1176251 0.007966935 0.450341 -0.1133601 0.0066365 0.465742 -0.1144734 0.005397498 0.4704203 -0.116613 0.005920648 0.46379 -0.106767 0.005372583 0.4838625 -0.1073234 0.004331767 0.4882941 -0.111195 0.004790961 0.4792998 -0.09797555 0.004838764 0.5016312 -0.1028374 0.00408411 0.4972183 -0.08536404 0.004532217 0.525215 -0.08936446 0.004629492 0.5179328 -0.0848037 0.005592882 0.520952 -0.07342267 0.007038176 0.533594 -0.06433153 0.008285224 0.541661 -0.0592516 0.008953094 0.545537 -0.05377757 0.009632468 0.549284 -0.04788404 0.01031005 0.552887 -0.02262395 0.01167505 0.565448 -0.01443004 0.01224225 0.567996 -0.02760791 0.01216995 0.562636 0.002646327 0.01304852 0.5721905 -0.1569977 0.01041871 0.03426039 -0.154269 0.01177281 0.06506717 -0.1575624 0.01052796 0.06952911 -0.1545947 0.01183772 0.1005685 -0.1578481 0.01058316 0.1050556 -0.1545975 0.01183837 0.1226775 -0.1578144 0.01057672 0.1271444 -0.1545475 0.01182848 0.1315857 -0.1543456 0.01178812 0.1493967 -0.1541887 0.01175677 0.1583124 -0.1575056 0.01051706 0.1539049 -0.153389 0.01159691 0.1873758 -0.15653 0.01032859 0.1895651 -0.1525498 0.01142996 0.2073171 -0.1520951 0.01134353 0.2162295 -0.1553035 0.01009684 0.2162509 -0.1536163 0.009830057 0.2430128 -0.1479663 0.01079148 0.2735958 -0.1484497 0.00944674 0.3000983 -0.1417815 0.01069939 0.3301405 -0.137754 0.01077657 0.3589752 -0.1414105 0.009613037 0.3545534 -0.1346189 0.01064908 0.378797 -0.1338711 0.01058572 0.383249 -0.1367896 0.009452283 0.383249 -0.1331065 0.01050657 0.387702 -0.132325 0.01041007 0.392158 -0.1298761 0.01000303 0.40554 -0.1290242 0.009823501 0.410006 -0.131856 0.008723676 0.410006 -0.128154 0.009619593 0.414475 -0.1254326 0.008848249 0.427903 -0.1244874 0.008533418 0.432387 -0.1235173 0.008191466 0.436874 -0.1262525 0.007129251 0.436874 -0.1225126 0.007828652 0.441363 -0.1191884 0.006677448 0.454828 -0.1179434 0.006293773 0.459311 -0.120582 0.00526905 0.459311 -0.114543 0.003942787 0.477183 -0.1051613 0.003161966 0.4973064 -0.09987998 0.003215849 0.5061495 -0.09384357 0.003586053 0.5148518 -0.07442206 0.005518794 0.537675 -0.07721954 0.005675673 0.533594 -0.05203962 0.008668363 0.552887 -0.05332463 0.007899403 0.552887 -0.05827975 0.007854521 0.549284 -0.06089425 0.00841099 0.545537 -0.05531316 0.009126126 0.549284 -0.04930144 0.009842514 0.552887 -0.04283171 0.01054668 0.556329 -0.035914 0.01122039 0.559587 -0.02861058 0.01183897 0.562636 -0.02098596 0.01237738 0.565448 -0.01310449 0.01281046 0.567996 -0.005030632 0.01311308 0.570253 -0.1572011 0.009899199 0 -0.1601315 0.008945286 0.03427612 -0.157305 0.01047813 0.05181562 -0.1577497 0.0105642 0.08727669 -0.1608916 0.009086847 0.08728832 -0.1578488 0.01058334 0.1182357 -0.1609916 0.009105503 0.1182424 -0.1577473 0.01056379 0.1360558 -0.1576453 0.01054406 0.1449686 -0.160786 0.009067237 0.1449687 -0.1573271 0.01048254 0.1628078 -0.1571064 0.01043993 0.1717205 -0.1602407 0.008965849 0.1717377 -0.1568409 0.01038867 0.1806581 -0.1561739 0.01025956 0.1984032 -0.1557634 0.0101813 0.2073377 -0.1590982 0.008753299 0.2028515 -0.1547933 0.01000869 0.2251576 -0.1542306 0.009918808 0.234086 -0.1576204 0.00850284 0.2296801 -0.1529499 0.009744644 0.2519438 -0.1518874 0.009630143 0.2650023 -0.1545466 0.00815171 0.2696557 -0.1502566 0.009509801 0.2827103 -0.1528294 0.008055031 0.2874429 -0.1454786 0.009483158 0.3252725 -0.1484519 0.0080868 0.3252248 -0.1439172 0.009548664 0.3369768 -0.1426944 0.009588479 0.3457577 -0.1456297 0.008209288 0.3457431 -0.1400594 0.009611368 0.3633882 -0.138295 0.009554207 0.374347 -0.1411532 0.008210241 0.374347 -0.1390226 0.009585082 0.369899 -0.1375507 0.009510457 0.378797 -0.1360114 0.009378433 0.387702 -0.1352158 0.009287416 0.392158 -0.1335719 0.009048283 0.401076 -0.1363494 0.007742166 0.401076 -0.1344028 0.009177803 0.3966161 -0.1327232 0.008897364 0.40554 -0.1309706 0.008525788 0.414475 -0.1300664 0.00830233 0.4189471 -0.1282012 0.007773041 0.427903 -0.1308882 0.006509602 0.427903 -0.1291434 0.008051872 0.423424 -0.1272394 0.007464587 0.432387 -0.1252302 0.006773114 0.441363 -0.1230386 0.006024301 0.450341 -0.12564 0.004801094 0.450341 -0.1241624 0.00640273 0.445853 -0.1218486 0.005644321 0.454828 -0.1192284 0.004904925 0.46379 -0.1162193 0.004235446 0.472727 -0.1187075 0.003065347 0.472727 -0.1177776 0.004558265 0.468262 -0.1127385 0.003686785 0.481628 -0.1097148 0.003374934 0.4884226 -0.111066 0.002198994 0.490483 -0.1036709 0.002124845 0.503654 -0.09453421 0.002737641 0.51666 -0.0873295 0.003607988 0.525215 -0.08902442 0.004078328 0.520952 -0.07608348 0.004523813 0.537675 -0.07904416 0.004817724 0.533594 -0.08143889 0.005069017 0.529435 -0.05967026 0.007021486 0.549284 -0.05746209 0.00645107 0.551232 -0.06079363 0.005955159 0.549313 -0.06778216 0.007046818 0.541661 -0.06250518 0.007785141 0.545537 -0.05681884 0.008541524 0.549284 -0.05069059 0.009302675 0.552887 -0.04409515 0.01005566 0.556329 -0.03704249 0.01078218 0.559587 -0.02959394 0.0114569 0.562636 -0.02181702 0.01205456 0.565448 -0.01377713 0.01254922 0.567996 -0.005539655 0.01291543 0.570253 -0.1604421 0.009003162 0.05183327 -0.1634588 0.007219374 0.05367618 -0.1607024 0.00905162 0.06953758 -0.1609715 0.009101688 0.1004233 -0.1609957 0.009106278 0.1093277 -0.1639875 0.007313132 0.107124 -0.1609569 0.009099006 0.1271561 -0.1608892 0.00908637 0.1360563 -0.1638801 0.007294118 0.1362232 -0.1606447 0.009041011 0.1539068 -0.1604642 0.009007394 0.1628095 -0.163456 0.007219493 0.1625989 -0.1599727 0.00891596 0.1806629 -0.159658 0.008857429 0.1895802 -0.1593923 0.008807718 0.196178 -0.1623683 0.007025599 0.196178 -0.1586578 0.008673846 0.2117851 -0.1581653 0.008589506 0.2207299 -0.160579 0.006731986 0.2296634 -0.1570258 0.008416652 0.2385923 -0.1563787 0.008333086 0.2475046 -0.1556796 0.008254706 0.2564057 -0.1584366 0.006480336 0.2585723 -0.1556986 0.006320357 0.2876645 -0.1508978 0.008023083 0.3051905 -0.1526118 0.006332933 0.3147662 -0.1468785 0.008159577 0.3369205 -0.1490875 0.006505846 0.3411743 -0.1443222 0.008244097 0.3545511 -0.1429495 0.008253216 0.3633781 -0.1418932 0.008235275 0.369899 -0.1446263 0.006598532 0.369899 -0.1403961 0.008172452 0.378797 -0.1396219 0.008120417 0.383249 -0.1388304 0.008052766 0.387702 -0.1380213 0.007968127 0.392158 -0.1371944 0.007865071 0.3966161 -0.1398525 0.006273329 0.3966161 -0.1354862 0.007598042 0.40554 -0.1346045 0.007431268 0.410006 -0.133704 0.007240414 0.414475 -0.1327846 0.007024168 0.4189471 -0.1353728 0.005474269 0.4189471 -0.1318461 0.006780982 0.423424 -0.1299103 0.006208658 0.432387 -0.128907 0.005881011 0.436874 -0.1278678 0.00553286 0.441363 -0.1267823 0.005170762 0.445853 -0.1292769 0.003676891 0.445853 -0.1244303 0.004430294 0.454828 -0.1231427 0.004064917 0.459311 -0.1217667 0.003711283 0.46379 -0.1202918 0.003375947 0.468262 -0.1226857 0.001942396 0.468262 -0.1170033 0.002785861 0.477183 -0.1151686 0.002544045 0.481628 -0.1131931 0.002346277 0.486062 -0.115476 9.79243e-4 0.486062 -0.108777 0.002108693 0.494889 -0.1063154 0.002081871 0.49928 -0.1084897 7.79835e-4 0.49928 -0.1008329 0.002244174 0.50801 -0.09779083 0.002446293 0.512345 -0.09982961 0.001225411 0.512345 -0.09105253 0.003124594 0.520952 -0.08920085 0.002487361 0.525215 -0.08242797 0.00236088 0.53334 -0.0807814 0.003777444 0.533594 -0.07953459 0.002852082 0.535879 -0.08333671 0.004176616 0.529435 -0.06729859 0.004902958 0.545184 -0.06555855 0.006158113 0.545537 -0.06407433 0.005434691 0.547295 -0.06944054 0.006267011 0.541661 -0.0640698 0.007049858 0.545537 -0.045322 0.009478747 0.556329 -0.03813791 0.01026719 0.559587 -0.03054875 0.01100808 0.562636 -0.00603348 0.01268315 0.570253 -0.163189 0.00717163 0.03819346 -0.1636887 0.007260859 0.0692954 -0.1661921 0.004960954 0.06396478 -0.1638612 0.007291018 0.08487641 -0.1665167 0.00501573 0.09498977 -0.1639404 0.0073058 0.09580689 -0.1639843 0.007313549 0.1181777 -0.1665604 0.005023121 0.120198 -0.1639497 0.007307469 0.1270185 -0.1637763 0.007276833 0.1449456 -0.1636362 0.007251501 0.1537721 -0.1662591 0.004972279 0.151218 -0.1632261 0.007178068 0.1717408 -0.162957 0.00713092 0.1805842 -0.1654735 0.004839718 0.18223 -0.1653363 0.004816532 0.186105 -0.1626446 0.007074952 0.1893755 -0.1620702 0.006973206 0.2028642 -0.1616315 0.00689727 0.2116819 -0.1643146 0.004646599 0.209349 -0.161139 0.006816565 0.2205533 -0.1599768 0.006649851 0.2385843 -0.1623984 0.004380106 0.24031 -0.1621139 0.004347085 0.244177 -0.1593353 0.006572127 0.2473285 -0.1574458 0.006402909 0.2698207 -0.1601909 0.004184246 0.267364 -0.1566179 0.006355583 0.2785533 -0.1547468 0.006303906 0.2965252 -0.1570451 0.004098832 0.298226 -0.1566042 0.004104137 0.302078 -0.153752 0.006305932 0.3052847 -0.1514981 0.006380736 0.3235429 -0.153733 0.004218757 0.325166 -0.1503143 0.00644201 0.3324251 -0.1481357 0.006547987 0.347671 -0.147112 0.006584167 0.3544304 -0.1498762 0.004442214 0.352034 -0.1457396 0.006605744 0.3631349 -0.1438745 0.006580591 0.374347 -0.1431054 0.006550014 0.378797 -0.1447584 0.004445075 0.382631 -0.1423189 0.006505429 0.383249 -0.144063 0.004401981 0.386445 -0.1415147 0.006445407 0.387702 -0.1406926 0.006368517 0.392158 -0.138994 0.00615853 0.401076 -0.1381171 0.006022572 0.40554 -0.1403995 0.004004538 0.40548 -0.1372213 0.005864202 0.410006 -0.1363067 0.005681872 0.414475 -0.1344195 0.005239963 0.423424 -0.1334465 0.004977524 0.427903 -0.1324535 0.004685759 0.432387 -0.1347284 0.002766191 0.431995 -0.1314345 0.00436747 0.436874 -0.1303792 0.004028975 0.441363 -0.1281169 0.003317832 0.450341 -0.1268884 0.002958297 0.454828 -0.1290547 0.001134097 0.454496 -0.1255809 0.002604842 0.459311 -0.1241835 0.002264022 0.46379 -0.1210768 0.001646578 0.472727 -0.1216015 -3.36983e-4 0.476468 -0.1193459 0.001383066 0.477183 -0.120117 -5.13215e-4 0.480048 -0.1174826 0.001158416 0.481628 -0.1133154 8.52032e-4 0.490483 -0.1109902 7.83381e-4 0.494889 -0.1114513 -8.8048e-4 0.497378 -0.1133514 -8.76726e-4 0.493989 -0.1058033 8.47954e-4 0.503654 -0.1052453 -6.17879e-4 0.507204 -0.1029202 9.94309e-4 0.50801 -0.1030093 -4.44364e-4 0.510373 -0.09652101 0.001547873 0.51666 -0.09830474 2.89974e-5 0.516529 -0.09298366 0.001968204 0.520952 -0.08525025 0.001899898 0.530726 -0.08800137 0.001469314 0.528039 -0.08514368 0.003094494 0.529435 -0.07101947 0.005321502 0.541661 -0.07045578 0.004382193 0.542988 -0.07354629 0.003872394 0.540709 -0.05062389 0.007422268 0.554795 -0.01076543 0.0117377 0.56928 0.0158382 0.01292741 0.574498 -0.1655483 0.004852354 0.02711474 -0.1657008 0.004877984 0.03489261 -0.1658087 0.004896283 0.04068982 -0.1659585 0.004921495 0.04912108 -0.1660689 0.004940092 0.05578374 -0.1662724 0.004974484 0.0697878 -0.1663435 0.004986524 0.07560503 -0.1664295 0.005000889 0.08377301 -0.1664763 0.005008876 0.08917558 -0.1665462 0.005020678 0.100809 -0.1665607 0.005023121 0.104686 -0.1665685 0.005024433 0.108564 -0.1665711 0.005024909 0.112442 -0.1665683 0.005024433 0.11632 -0.1665462 0.005020678 0.124075 -0.1665249 0.005017101 0.127953 -0.1664975 0.005012452 0.131831 -0.166464 0.00500679 0.135708 -0.1664244 0.005000114 0.139586 -0.1663763 0.004992008 0.143463 -0.1663212 0.004982709 0.147341 -0.16619 0.004960596 0.155095 -0.1661129 0.004947543 0.158972 -0.166027 0.004933059 0.162849 -0.1659331 0.004917204 0.166726 -0.1658314 0.004900097 0.170602 -0.1657218 0.00488156 0.174478 -0.165602 0.004861354 0.178354 -0.1651904 0.004791975 0.18998 -0.1650348 0.004765868 0.193855 -0.164869 0.004738271 0.197729 -0.1646937 0.004709184 0.201603 -0.1645089 0.004678666 0.205476 -0.1641098 0.00461471 0.213221 -0.1638953 0.004581928 0.217093 -0.1636707 0.004548311 0.220964 -0.1634364 0.00451374 0.224834 -0.163192 0.004479527 0.228704 -0.1629375 0.004446327 0.232574 -0.1626729 0.004413187 0.236442 -0.1618189 0.004316747 0.248044 -0.1615138 0.004287421 0.251909 -0.1611985 0.004259049 0.255774 -0.1608731 0.004231691 0.259638 -0.1605373 0.004206538 0.263502 -0.1598343 0.004163861 0.271225 -0.1594674 0.004145443 0.275085 -0.1590902 0.004128992 0.278945 -0.1587021 0.004116952 0.282803 -0.1583037 0.004107832 0.28666 -0.1578947 0.004101574 0.290516 -0.1574752 0.004098176 0.294372 -0.1561526 0.004113316 0.305929 -0.1556904 0.00412625 0.30978 -0.1552176 0.00414294 0.313629 -0.1547336 0.004164159 0.317476 -0.1542387 0.004189431 0.321322 -0.1532164 0.004252135 0.32901 -0.1526885 0.004285693 0.332851 -0.1521487 0.004317283 0.336691 -0.1515978 0.004349768 0.340529 -0.1510357 0.004383325 0.344366 -0.1504622 0.004417836 0.348201 -0.1492785 0.004463434 0.355866 -0.1486691 0.004481673 0.359695 -0.1480479 0.004496812 0.363523 -0.1474145 0.004503846 0.367349 -0.1467686 0.004499793 0.371172 -0.1461106 0.004488646 0.374994 -0.1454405 0.004470407 0.378813 -0.1429998 0.004318416 0.3921568 -0.1419028 0.004206597 0.397875 -0.1411576 0.004114806 0.401679 -0.1392979 0.003823816 0.4108985 -0.1380492 0.003585278 0.416866 -0.1372389 0.003407359 0.420654 -0.1364153 0.003211498 0.424438 -0.1355785 0.002997815 0.428219 -0.1338546 0.002520799 0.435765 -0.1329504 0.002264261 0.439527 -0.1320247 0.001993119 0.443283 -0.1310772 0.001707375 0.447032 -0.130108 0.001407146 0.4507761 -0.1279569 8.61674e-4 0.458204 -0.1268148 5.89879e-4 0.4618991 -0.1256282 3.18714e-4 0.465582 -0.1243686 7.01819e-5 0.46924 -0.1230188 -1.42512e-4 0.472865 -0.1185652 -6.71217e-4 0.483605 -0.1169083 -7.72094e-4 0.487103 -0.1151704 -8.40596e-4 0.490564 -0.1094675 -8.40489e-4 0.500713 -0.1073981 -7.49918e-4 0.503984 -0.10069 -2.29375e-4 0.513493 -0.09584254 3.2953e-4 0.519504 -0.09330332 6.7224e-4 0.522416 -0.09068721 0.001057088 0.525266 -0.07657003 0.003373622 0.538345 -0.05407285 0.006940126 0.55306 -0.00433886 0.01150494 0.570799 -0.006392359 0.01204502 0.570357 -0.002700448 0.01225304 0.571194 -0.1395749 -1.03827e-4 0.402169 -0.1399914 0.003957331 0.4075011 -0.1392325 0.003826141 0.411211 -0.1407389 0.004070401 0.403788 -0.1414751 0.004165291 0.400072 -0.1419023 9.14887e-5 0.389975 -0.1421983 0.004252135 0.396353 -0.1371079 -4.54728e-4 0.414384 -0.1440947 1.60148e-4 0.377798 -0.1436086 0.004384577 0.3889091 -0.1442958 0.004429519 0.385182 -0.1449711 0.004463136 0.381454 -0.1429095 0.004325449 0.392632 -0.1456347 0.00449115 0.377723 -0.1461565 1.31105e-4 0.365633 -0.1462864 0.004508614 0.373991 -0.1469262 0.004515588 0.370256 -0.1475542 0.004512012 0.366519 -0.1480923 3.33011e-5 0.353475 -0.1481708 0.004504978 0.36278 -0.148776 0.004493474 0.35904 -0.1493695 0.004475176 0.355297 -0.1499517 0.004450082 0.351553 -0.1499066 -1.04335e-4 0.341322 -0.1510564 0.004392206 0.3442515 -0.1560357 -5.11075e-4 0.292666 -0.1573009 -5.12517e-4 0.280482 -0.1577955 0.004097521 0.291442 -0.1516311 0.004361093 0.340311 -0.1521688 0.004327595 0.33656 -0.1516039 -2.52858e-4 0.329168 -0.1551685 0.004145622 0.314024 -0.154456 0.004185318 0.3196634 -0.1531888 -3.83319e-4 0.317009 -0.1537165 0.004227519 0.325299 -0.152931 0.004274666 0.3311114 -0.1546654 -4.70248e-4 0.304842 -0.1558261 0.004120647 0.3086749 -0.1565282 0.004104137 0.302739 -0.1571733 0.004096508 0.2971012 -0.1583988 0.004105746 0.2857678 -0.1591689 0.004129707 0.2781698 -0.1584621 -4.81347e-4 0.268292 -0.1598801 0.004162073 0.2707574 -0.1606531 0.004212498 0.262196 -0.1595205 -4.24315e-4 0.256097 -0.1612367 0.004257798 0.2553462 -0.1604772 -3.48188e-4 0.243898 -0.1618574 0.004317045 0.2475722 -0.1622473 0.004359722 0.242388 -0.1613332 -2.5973e-4 0.231696 -0.1626545 0.004406452 0.2367361 -0.1630397 0.004455924 0.231048 -0.1620898 -1.65679e-4 0.219493 -0.1637456 0.004555344 0.219703 -0.1635197 0.00452274 0.223485 -0.163962 0.004588067 0.21592 -0.162748 -7.28162e-5 0.207289 -0.1632844 0.004489898 0.227267 -0.164366 0.004653215 0.208353 -0.1641687 0.004620909 0.212137 -0.1641505 1.41256e-4 0.170684 -0.1654889 0.004841744 0.181854 -0.1637749 8.35999e-5 0.182884 -0.1645542 0.004683434 0.204569 -0.1633091 1.21191e-5 0.195085 -0.1647329 0.00471282 0.200784 -0.1649023 0.00474143 0.196999 -0.1650622 0.004769206 0.193213 -0.1653556 0.004819154 0.18564 -0.1652134 0.004795134 0.189427 -0.1568772 -0.001959681 0.2036185 -0.1578612 -0.00181216 0.1780772 -0.1659361 0.0049178 0.166704 -0.1644421 1.86004e-4 0.158485 -0.1656131 0.004862904 0.178067 -0.1661106 0.004947245 0.159128 -0.1661863 0.00495994 0.155339 -0.1658363 0.004900932 0.170492 -0.1657283 0.004882633 0.174279 -0.1459576 -0.003668606 0.1401905 -0.139576 -0.004298686 0.1401905 -0.1660276 0.004933238 0.162916 -0.1570234 -0.001956522 0 -0.1574941 -0.001867115 0.01218801 -0.1646556 2.18759e-4 0.146288 -0.164797 2.40467e-4 0.134093 -0.1664184 0.004999101 0.140184 -0.1663716 0.004991233 0.143973 -0.1663173 0.004982054 0.147762 -0.1664595 0.005006074 0.136395 -0.1664943 0.005011916 0.132606 -0.1648722 2.52023e-4 0.121899 -0.1665224 0.005016684 0.128817 -0.1665438 0.00502026 0.125028 -0.1665743 0.005025446 0.113661 -0.1665655 0.005024373 0.1190528 -0.1648875 2.54363e-4 0.109705 -0.1257912 -0.005366921 0.01402801 -0.119469 -0.005735754 0 -0.1648487 2.48402e-4 0.09751331 -0.1665614 0.005023419 0.1042242 -0.1665732 0.005025267 0.109872 -0.1665063 0.005014121 0.09283834 -0.1647618 2.35066e-4 0.08532208 -0.166539 0.005019485 0.0985043 -0.1663904 0.004994392 0.07955908 -0.1664403 0.005002677 0.08460903 -0.1646329 2.15281e-4 0.07313168 -0.1274504 -0.005170881 0.08700001 -0.1264759 -0.005263566 0.05484753 -0.1663304 0.00498408 0.07416945 -0.1520552 -0.002882778 0.05896925 -0.1456741 -0.003711044 0.05700188 -0.1586261 -0.001697361 0.08091247 -0.1644679 1.89953e-4 0.06094211 -0.1662216 0.004965901 0.06582391 -0.1661178 0.004948377 0.05869865 -0.1353877 -0.004737079 0 -0.1385189 -0.00445801 0.01239383 -0.132151 -0.004959881 0.01254826 -0.1581899 -0.001762747 0.04832077 -0.1642729 1.60026e-4 0.04875302 -0.1393097 -0.00433886 0.05775439 -0.1512092 -0.00300914 0.01220899 -0.1509228 -0.003051996 0 -0.1639873 1.16026e-4 0.03299826 -0.1658003 0.004894793 0.04005837 -0.1659513 0.004920184 0.048509 -0.144876 -0.003830611 0.01226621 -0.1452303 -0.003799676 0 -0.1655907 0.004859507 0.02911615 -0.1395183 -0.004383087 0 -0.142376 -0.004107117 0 -0.1635678 5.17936e-5 0.01218801 -0.1585943 -0.001586675 0 -0.1537559 -0.002587556 0 -0.1654467 0.004835128 0.02193319 -0.14808 -0.003451764 0 -0.1634877 8.6559e-5 0 -0.1619737 -5.2808e-4 0 -0.1652281 0.004798233 0.01136481 -0.1595944 -0.001318395 0 -0.1605848 -0.001016438 0 -0.1644297 5.16171e-4 0 -0.1662556 0.004971683 0.151551 -0.1647815 7.16557e-4 0 -0.1651487 0.004784822 0.007576525 -0.1654129 0.001220762 0 -0.1651126 9.49176e-4 0 -0.1656692 0.001533687 0 -0.1658736 0.001883089 0 -0.1660172 0.002261281 0 -0.1650686 0.004771292 0.003788232 -0.1660531 0.003063082 0 -0.1659278 0.003447115 0 -0.1654403 0.00422579 0 -0.1660844 0.002660334 0 -0.1657369 0.003803789 0 -0.1649876 0.004757642 0 -0.093656 -0.00671488 0.0119028 -0.08676761 -0.006886601 0 -0.09312617 -0.006722986 0 -0.1384624 0.003676831 0.414918 -0.137691 0.003504693 0.4186241 -0.1369116 0.003312826 0.422328 -0.1344968 -9.9015e-4 0.426623 -0.136111 0.003107488 0.426026 -0.1352889 0.002888739 0.429718 -0.1336162 0.002386987 0.437095 -0.1344453 0.002656579 0.4334051 -0.1327505 0.002114176 0.440776 -0.1318412 0.001842677 0.444444 -0.1317234 -0.001728117 0.438889 -0.1286401 -0.002583682 0.451166 -0.1308884 0.001572608 0.448101 -0.1278247 7.28321e-4 0.459026 -0.1288966 0.001002848 0.455399 -0.1299042 0.001294791 0.451752 -0.113118 -0.005807638 0.451166 -0.1149914 -0.005900204 0.463424 -0.1098505 -0.00656706 0.463424 -0.1266885 4.71157e-4 0.462631 -0.125488 2.31386e-4 0.466214 -0.1250283 -0.00341463 0.463424 -0.1242401 -8.4294e-6 0.469793 -0.1229258 -2.28787e-4 0.473348 -0.1215342 -4.18325e-4 0.476869 -0.1206678 -0.004078328 0.475638 -0.1185194 -7.06025e-4 0.4838081 -0.1153393 -0.004432201 0.487778 -0.1200654 -5.77035e-4 0.480355 -0.1168988 -8.19103e-4 0.487249 -0.1096196 -8.74534e-4 0.500543 -0.1088231 -0.004333496 0.499817 -0.1115634 -9.18526e-4 0.497284 -0.1151993 -8.92212e-4 0.490641 -0.1134208 -9.25354e-4 0.493986 -0.1075934 -7.91853e-4 0.503758 -0.1054963 -6.66188e-4 0.506916 -0.1008992 -0.003639578 0.511727 -0.1033283 -4.97543e-4 0.510017 -0.09640002 3.07111e-4 0.51902 -0.09878033 -5.88805e-6 0.516074 -0.1010894 -2.85913e-4 0.513061 -0.09394842 6.47055e-4 0.521893 -0.09134626 -0.002209365 0.52348 -0.09142565 0.001013934 0.524693 -0.09371453 -0.005696713 0.365633 -0.09507453 -0.00585848 0.353475 -0.09942883 -0.005493998 0.365711 -0.08882957 0.001417815 0.527427 -0.1521639 -0.002866566 0.1544184 -0.08341956 0.002327859 0.532692 -0.07980072 -2.68226e-5 0.534935 -0.08615833 0.001869142 0.530103 -0.09275197 -0.006892263 0.219493 -0.09948784 -0.006618976 0.211616 -0.09948933 -0.006648182 0.2261099 -0.08061319 0.002794027 0.535194 -0.07773929 0.003267705 0.53761 -0.07174885 0.004262089 0.542169 -0.07477718 0.003761589 0.539933 -0.06866955 0.004759848 0.544325 -0.06565707 0.002711117 0.54577 -0.0623576 0.005747556 0.548394 -0.0590977 0.006252765 0.550298 -0.06553977 0.005254805 0.5464 -0.05247157 0.007228195 0.55388 -0.0558024 0.006746292 0.552127 -0.09949266 -0.006712198 0.260539 -0.0971443 -0.006883144 0.256097 -0.09949159 -0.006691277 0.248308 -0.09635758 -0.006912052 0.268292 -0.04828429 0.005786538 0.555641 -0.04910635 0.007698655 0.555559 -0.09550702 -0.006911039 0.280482 -0.09949368 -0.00673151 0.272769 -0.09949463 -0.006749272 0.285 -0.0456953 0.00816518 0.557152 -0.04224449 0.008624732 0.558663 -0.03174144 0.009879529 0.562824 -0.02746772 0.008902549 0.56416 -0.03526711 0.009481906 0.561499 -0.02818244 0.01026451 0.564082 -0.02460157 0.01062589 0.565279 -0.01374202 0.01155579 0.568509 -0.01738291 0.01127183 0.567493 -0.02100211 0.01096171 0.566416 -0.01007258 0.01181262 0.569462 -0.03876775 0.009063601 0.560113 0.001003205 0.01243656 0.571973 -0.09943741 -0.00565809 0.353282 -0.09139806 -0.008251905 0.487778 -0.09058117 -0.00761795 0.499817 -0.08594524 -0.007983505 0.499817 -0.09475898 -0.00548321 0.402169 -0.09646916 -0.005361974 0.389975 -0.09941744 -0.00527656 0.4030001 -0.09635519 -0.006055414 0.341322 -0.09442836 -0.006614387 0.1645845 -0.09947836 -0.00643903 0.1401778 -0.09152323 -0.006480455 0.3288587 -0.08528143 -0.006910026 0.3160001 -0.09373015 -0.006633162 0.3160001 -0.0721997 -0.007178425 0.1523865 -0.07232171 -0.007155656 0.1401905 -0.08180987 -0.006941378 0.1523865 -0.09942263 -0.005375742 0.37814 0.011155 -0.008956372 0.05484753 0.01745814 -0.009061992 0.07313168 0.05287623 -0.009882807 0.1767839 0.05914103 -0.009972572 0.1763772 0.01744949 -0.00905919 0.1462879 0.03665333 -0.009464979 0.1401904 -0.09247773 -0.006609201 0.1057428 -0.08846044 -0.006725907 0.115802 -0.09947609 -0.006395041 0.126 -0.09480965 -0.006549119 0.134093 -0.09247791 -0.00661385 0.126 -0.07649397 -0.007339537 0.3010001 -0.07129621 -0.007472276 0.3010001 -0.07649749 -0.007405638 0.292996 -0.06746757 -0.007692337 0.280482 -0.07649999 -0.00745517 0.285 -0.09155261 -0.007034659 0.243898 -0.09403115 -0.006682336 0.182884 -0.09948462 -0.006558895 0.1850093 -0.09367644 -0.006743073 0.195085 -0.094702 -0.006567537 0.146288 -0.08793032 -0.00681889 0.04265862 -0.0944848 -0.006604731 0.05484753 -0.0882166 -0.006768643 0.06703686 -0.08840513 -0.006735622 0.09141767 -0.08191645 -0.006922185 0.07922691 -0.09247833 -0.006620168 0.08700001 -0.09947842 -0.006439328 0.05900269 -0.09947651 -0.006403148 0.08700001 -0.08743548 -0.006897389 0.01211631 0.07209324 -0.01001143 0.0142892 0.07852447 -0.0100969 0.008343338 0.07220762 -0.01003688 0 -0.09948456 -0.00655657 0 -0.09948301 -0.006526648 0.01231825 -0.05957162 -0.007433176 0.127996 -0.04677361 -0.007701158 0.115802 -0.08203905 -0.006900131 0.1036092 -0.08821547 -0.006768822 0.1523865 -0.05938851 -0.007469594 0.1523865 -0.0323382 -0.007999062 0.121899 -0.02513116 -0.008144378 0.109705 -0.04668128 -0.007720589 0.1401905 -0.008287012 -0.008491814 0.121899 0.03670829 -0.009486138 0.06703686 0.0174089 -0.009046256 0.08532208 0.05282437 -0.009858846 0.04265862 0.05915755 -0.009919762 0.05827426 0.03364121 -0.009467065 0.04113501 0.07849001 -0.01007217 0.01562505 0.07856774 -0.01012539 0 0.06578665 -0.009945154 0 0.05938518 -0.01002389 0.01215636 0.06577539 -0.01005285 0.01213175 0.0463199 -0.009688794 0.06703686 0.04642856 -0.009735107 0.04265862 0.02395993 -0.009231507 0.05484753 -0.00179547 -0.008646309 0.07922691 -0.001871228 -0.008625268 0.1036092 0.01737612 -0.009035646 0.09751325 -0.001839876 -0.008633971 0.1340929 0.01739585 -0.009041965 0.1340929 0.01736706 -0.009032785 0.121899 0.0367881 -0.009516716 0.1645845 0.04627043 -0.009667694 0.1401904 0.04639089 -0.009719192 0.1645845 0.05267822 -0.009791672 0.1401904 0.04653781 -0.009781658 0.1828839 0.05275207 -0.009825587 0.1584849 0.06556761 -0.01001977 0.1813548 0.07846808 -0.01005655 0.1750116 0.07214093 -0.009991407 0.1828839 0.07850879 -0.01008462 0.184018 0.06102448 -0.01005345 0.193 0.07201373 -0.009927153 0.1646192 0.06686103 -0.01010018 0.193 0.07855325 -0.01011532 0.193 0.07270395 -0.01012086 0.193 -0.07827597 -0.007439017 0.256097 -0.06945472 -0.007623016 0.243898 -0.07892566 -0.007389426 0.243898 -0.06817722 -0.007697224 0.268292 -0.07757139 -0.007465481 0.268292 -0.06981337 -0.007576346 0.292666 -0.07001596 -0.007558107 0.231696 -0.07825928 -0.006068348 0.3778203 -0.07690161 -0.006058275 0.3899918 -0.0712952 -0.00745356 0.303 -0.07953661 -0.006171226 0.3656672 -0.07129526 -0.006597399 0.353475 -0.08073735 -0.006337583 0.3535439 -0.06884056 -0.007671773 0.256097 0.05912703 -0.009905755 0.1527221 -0.02508342 -0.008155703 0.134093 -0.0739243 -0.00737071 0.213391 -0.0675649 -0.007521629 0.213391 -0.06509566 -0.007424056 0.317009 -0.05824244 -0.007742464 0.3048286 -0.0733233 -0.007011651 0.329168 -0.07233643 -0.006801784 0.341322 -0.06423193 -0.007235944 0.329168 -0.06317579 -0.006810188 0.3528745 -0.06779831 -0.006489813 0.3656535 -0.08499693 -0.005800843 0.389975 -0.08344262 -0.005916118 0.402169 -0.07778322 -0.00609833 0.402169 -0.0835607 -0.007080435 0.438889 -0.08552509 -0.006432294 0.426623 -0.08895933 -0.006861269 0.438889 -0.0817905 -0.00618261 0.414384 -0.08736705 -0.005982339 0.414384 -0.09726232 -0.007086992 0.451166 -0.09196734 -0.007374644 0.451166 -0.09435659 -0.006609797 0.438889 -0.09101444 -0.006209433 0.426623 -0.09434658 -0.007818043 0.463424 -0.09586286 -0.008035898 0.475638 -0.09083086 -0.008360564 0.475638 -0.08916914 -0.008099317 0.463424 0.008445739 0.01273012 0.573358 0.004718601 0.01259553 0.572695 -0.08654129 -0.008565306 0.487778 0.06115376 -0.01161867 0.463424 0.05596792 -0.01159512 0.463424 0.05534511 -0.01203358 0.475638 0.0564633 -0.01094979 0.451166 0.06176733 -0.01097393 0.451166 0.07207238 -0.01126235 0.455733 0.06637251 -0.01158863 0.463424 0.07191175 -0.01138514 0.45807 0.06772363 -0.01024574 0.438889 0.07306945 -0.01033127 0.439261 0.07286095 -0.01053434 0.4429272 0.06710326 -0.01094311 0.451166 0.07334774 -0.01006937 0.4342309 0.0735746 -0.009863674 0.43 0.05115914 -0.01087158 0.451166 0.05078178 -0.01151865 0.463424 0.07252067 -0.01086723 0.448716 0.07266181 -0.01073396 0.446376 0.04373764 -0.01183146 0.4756435 0.04404509 -0.01138782 0.4634345 0.0722264 -0.01113158 0.453395 0.07080447 -0.01199209 0.472061 0.07100796 -0.01191091 0.469734 0.0654633 -0.01202732 0.475638 0.05030208 -0.01195925 0.475638 0.04967802 -0.0120387 0.487778 0.0603888 -0.01205652 0.475638 0.05454498 -0.01211047 0.487778 0.06963068 -0.01218658 0.483656 0.06431066 -0.01210433 0.487778 0.06936168 -0.01217937 0.485966 0.04886382 -0.0116021 0.499817 0.07013219 -0.01215142 0.479027 0.02044385 -0.01142215 0.487778 0.02139276 -0.01102286 0.499816 0.04280865 -0.01148396 0.4998198 0.04145717 -0.01037025 0.5117274 0.05351459 -0.01167064 0.499817 0.05220395 -0.01055938 0.5117269 0.05816686 -0.0116918 0.499817 0.01136493 -0.009723305 0.5117287 0.04781728 -0.0104947 0.5117269 0.04649358 -0.00856316 0.5234799 0.01267486 -0.007847428 0.5234813 0.05462563 -0.0086416 0.5234799 0.05055904 -0.008623063 0.5234799 0.04840266 -0.005821228 0.5349349 0.04472947 -0.005767047 0.5349349 0.01714456 -0.001729309 0.5457696 0.03941702 -0.005663096 0.5349354 0.04062235 -0.008448302 0.5234804 0.04082816 -0.002236187 0.5457713 0.04534345 -0.002305746 0.5457699 0.05207687 -0.005837917 0.5349349 0.01417112 -0.005120217 0.5349363 0.04096782 0.001752555 0.5556409 0.04852408 -0.00232017 0.5457699 -0.003227531 0.002657413 0.555642 0.003887951 0.006715595 0.5641604 0.03734284 0.001808404 0.5556419 0.0191313 0.00219798 0.5556403 0.03592807 0.006069242 0.5641601 0.04352575 0.001740932 0.5556409 0.01914721 0.006401777 0.5641586 -0.01360696 -0.004551887 0.5349351 -0.0180605 -0.00721848 0.52348 0.008845627 0.01044446 0.5708002 -0.02014762 -9.45103e-4 0.5457696 -0.02360165 -0.004334151 0.5349345 -0.004008591 0.006896078 0.5641604 0.01960974 0.01021981 0.5707992 -0.03281462 -5.9841e-4 0.545769 -0.03820264 -0.003962039 0.5349341 -0.009916841 -0.001174211 0.5457709 -0.008973181 0.007038891 0.5641594 0.004134833 0.01058125 0.5708005 0.001528084 0.01069855 0.5707996 -0.01615124 0.007338583 0.5641595 -3.08494e-4 0.01081866 0.5708002 -0.01256483 0.007169127 0.5641592 -0.02222746 0.00781399 0.56416 -0.002556502 0.01106345 0.570799 -0.001643419 0.01094502 0.570799 -0.01866018 0.00749731 0.56416 -0.003463089 0.01122826 0.570799 -0.02576553 0.008364617 0.56416 -0.02400189 0.008044302 0.56416 0.01969665 0.01298707 0.5750001 -0.1587833 -0.001673758 0.1051344 -0.15874 -0.001680314 0.1294095 -0.1584482 -0.001724064 0.1537362 -0.1560472 -0.002074778 0.219493 -0.1553072 -0.002163589 0.231696 -0.1544706 -0.002245903 0.243898 -0.1535365 -0.002314925 0.256097 -0.1525043 -0.002363681 0.268292 -0.1513729 -0.002385437 0.280482 -0.1501414 -0.002373337 0.292666 -0.1452348 -0.00350064 0.280482 -0.1463354 -0.003484487 0.268292 -0.1488093 -0.002320468 0.304842 -0.1473755 -0.002219974 0.317009 -0.1458383 -0.00207448 0.329168 -0.1438177 -0.00187081 0.34402 -0.1405615 -0.001636564 0.365633 -0.1385655 -0.001586735 0.377798 -0.1364432 -0.001633286 0.389975 -0.1341899 -0.001805186 0.402169 -0.1318011 -0.002131402 0.414384 -0.129272 -0.002640843 0.426623 -0.1235972 -0.004176974 0.451166 -0.126585 -0.003351628 0.438889 -0.1200972 -0.004972577 0.463424 -0.1158726 -0.005593419 0.475638 -0.110711 -0.005894482 0.487778 -0.1044002 -0.005730867 0.499817 -0.09672802 -0.004957437 0.511727 -0.04585218 0.005018234 0.555641 -0.06263291 0.001755654 0.54577 -0.08748018 -0.003430843 0.52348 0.01218461 0.01284021 0.573963 0.01593428 0.01292586 0.574511 -0.07630789 -0.001130342 0.534935 -0.02044528 0.007638096 0.56416 -0.1461258 -0.003643393 0.1041651 -0.1524943 -0.002817213 0.1062167 -0.1506903 -0.003086447 0.2024993 -0.1453495 -0.00375992 0.1751707 -0.1497907 -0.003211498 0.219493 -0.1490678 -0.003297209 0.231696 -0.1482513 -0.003375887 0.243898 -0.1473407 -0.003440618 0.256097 -0.1440385 -0.003482162 0.292666 -0.1427458 -0.003422081 0.304842 -0.1413564 -0.003313541 0.317009 -0.1398684 -0.003159105 0.329168 -0.1366543 -0.002827048 0.3529299 -0.1347685 -0.002689123 0.365633 -0.1328406 -0.002626895 0.377798 -0.1307907 -0.002660274 0.389975 -0.1286143 -0.002818167 0.402169 -0.1263064 -0.003129661 0.414384 -0.1238623 -0.003623723 0.426623 -0.1183756 -0.005125701 0.451166 -0.1212646 -0.004318237 0.438889 -0.1109074 -0.006495535 0.475638 -0.1059187 -0.006765186 0.487778 -0.09982091 -0.006562829 0.499817 -0.07269144 -0.001787424 0.534935 -0.08347713 -0.004158139 0.52348 -0.09240907 -0.005742132 0.511727 -0.0595014 0.001186728 0.54577 -0.1297071 -0.005148947 0 -0.1436079 -0.004014194 0.2174697 -0.1427853 -0.004112124 0.231696 -0.1419891 -0.004188179 0.243898 -0.141102 -0.004249811 0.256097 -0.1401238 -0.004290223 0.268292 -0.1390544 -0.004302322 0.280482 -0.1378934 -0.004279196 0.292666 -0.1366406 -0.004213988 0.304842 -0.1352956 -0.004099726 0.317009 -0.1338573 -0.003938794 0.329168 -0.1306489 -0.003578543 0.3537802 -0.1289354 -0.003445744 0.365633 -0.127076 -0.003374636 0.377798 -0.1230799 -0.004023849 0.365633 -0.1250993 -0.003398478 0.389975 -0.1230001 -0.003546416 0.402169 -0.1207737 -0.003847301 0.414384 -0.1184152 -0.004330277 0.426623 -0.1159074 -0.005013108 0.438889 -0.1059079 -0.007143974 0.475638 -0.08806037 -0.006306171 0.511727 -0.07944649 -0.004680991 0.52348 -0.1010934 -0.007391095 0.487778 -0.09520989 -0.007160961 0.499817 -0.04333466 0.004560768 0.555641 -0.06904995 -0.002259731 0.534935 -0.05634844 7.778e-4 0.54577 -0.1239101 -0.00550276 0 -0.1397422 -0.004273474 0.1049104 -0.1331343 -0.004810273 0.1468206 -0.1391998 -0.00435537 0.1645908 -0.1385537 -0.004452943 0.1877397 -0.1368319 -0.004698216 0.2263454 -0.1357028 -0.004808783 0.243898 -0.1348394 -0.004868149 0.256097 -0.1338886 -0.004905819 0.268292 -0.1328502 -0.00491482 0.280482 -0.1317247 -0.004888236 0.292666 -0.1305118 -0.004819095 0.304842 -0.1292117 -0.004700362 0.317009 -0.1278232 -0.004534542 0.329168 -0.1231183 -0.005180895 0.317009 -0.1263418 -0.004347145 0.341322 -0.1247623 -0.004167258 0.353475 -0.1193999 -0.004417359 0.378586 -0.1193873 -0.004176974 0.390793 -0.1193738 -0.003920376 0.4030001 -0.1143906 -0.004343867 0.4030001 -0.1152199 -0.004395663 0.414384 -0.1129472 -0.004870116 0.426623 -0.1078402 -0.006328701 0.451166 -0.1105298 -0.005544066 0.438889 -0.1046897 -0.007076561 0.463424 -0.08369499 -0.006737172 0.511727 -0.1008893 -0.007639467 0.475638 -0.09624946 -0.007869303 0.487778 -0.04079937 0.004231929 0.555641 -0.07540035 -0.005080461 0.52348 -0.06539469 -0.002620637 0.534935 -0.05318349 4.65336e-4 0.54577 -0.1329281 -0.004841804 0.05800586 -0.1333041 -0.004781007 0.1060708 -0.1323629 -0.004931569 0.1843667 -0.1303339 -0.005214571 0.2286014 -0.1294068 -0.00530529 0.243898 -0.1285671 -0.005362749 0.256097 -0.1276435 -0.005398273 0.268292 -0.1222878 -0.005767941 0.256097 -0.1266365 -0.005404829 0.280482 -0.1255463 -0.005375444 0.292666 -0.1243734 -0.005303144 0.304842 -0.1194424 -0.005227148 0.3292579 -0.1194325 -0.005040943 0.341964 -0.1194225 -0.004849374 0.354171 -0.1194116 -0.004641473 0.366379 -0.1094036 -0.004711091 0.4030001 -0.1096573 -0.004834294 0.414384 -0.1074707 -0.005302011 0.426623 -0.1051438 -0.005968809 0.438889 -0.1025542 -0.006745576 0.451166 -0.08130413 -0.008282959 0.499817 -0.09952104 -0.007484197 0.463424 -0.03825509 0.003980755 0.555641 -0.07932275 -0.007081985 0.511727 -0.07134795 -0.005400002 0.52348 -0.06173378 -0.002909362 0.534935 -0.05001324 2.15339e-4 0.54577 -0.1274499 -0.005162239 0.11 -0.1194615 -0.005594193 0.11 -0.1269128 -0.005195856 0.121899 -0.1268473 -0.005206048 0.134093 -0.1267242 -0.005225121 0.146288 -0.1265382 -0.005253911 0.158485 -0.1262844 -0.00529325 0.170684 -0.1259574 -0.005343914 0.182884 -0.1251189 -0.005473136 0.2062751 -0.1244924 -0.005561649 0.219493 -0.1238388 -0.005640864 0.231696 -0.1231038 -0.005711972 0.243898 -0.1194749 -0.005849421 0.268716 -0.1194681 -0.0057199 0.2855004 -0.1194576 -0.005518317 0.305341 -0.1044126 -0.005021929 0.4030001 -0.1040886 -0.005193591 0.414384 -0.1019881 -0.005655765 0.426623 -0.09975171 -0.006316721 0.438889 -0.08579587 -0.00863409 0.475638 -0.0357061 0.003779709 0.555641 -0.07494574 -0.007364392 0.511727 -0.06729096 -0.005661785 0.52348 -0.05806815 -0.003145873 0.534935 -0.0468406 1.06217e-5 0.54577 -0.1194677 -0.005711317 0.12221 -0.119473 -0.005812227 0.134419 -0.1194774 -0.005896806 0.146629 -0.119481 -0.005965232 0.158838 -0.1194837 -0.006017327 0.171047 -0.1194862 -0.006065487 0.1893008 -0.1194868 -0.006076276 0.207674 -0.1194862 -0.006063401 0.219883 -0.1194846 -0.006034255 0.232091 -0.1194821 -0.005984544 0.2461344 -0.09851664 -0.005496323 0.414384 -0.0965023 -0.005953788 0.426623 -0.08168166 -0.008829295 0.487778 -0.07666039 -0.008535265 0.499817 -0.03315418 0.003615081 0.555641 -0.07056611 -0.007602334 0.511727 -0.06323146 -0.005882322 0.52348 -0.05440056 -0.003345072 0.534935 -0.04366523 -1.61873e-4 0.54577 -0.1194639 -0.005639374 0.05617457 -0.1194621 -0.005604445 0.08700001 -0.08667039 -0.007621467 0.451166 -0.09941881 -0.005303204 0.39057 -0.08398962 -0.008340597 0.463424 -0.09294253 -0.00575602 0.414384 -0.08075904 -0.008868753 0.475638 -0.07682013 -0.009055793 0.487778 -0.0720148 -0.00875169 0.499817 -0.03060096 0.003476381 0.555641 -0.06618517 -0.00780642 0.511727 -0.05917078 -0.006071507 0.52348 -0.05073249 -0.003515958 0.534935 -0.03918242 -3.67597e-4 0.5457686 -0.09226942 -0.005599141 0.377798 -0.09073352 -0.005594849 0.389975 -0.08137196 -0.00783652 0.451166 -0.08910125 -0.005712866 0.402169 -0.07880884 -0.008550941 0.463424 -0.07572072 -0.009073257 0.475638 -0.0719574 -0.009253203 0.487778 -0.06736814 -0.008940339 0.499817 -0.02699381 0.003310859 0.5556402 -0.0618025 -0.00798434 0.511727 -0.05342733 -0.006301343 0.5234782 -0.04554277 -0.00372374 0.5349336 -0.09946185 -0.006123721 0.328427 -0.09947764 -0.006425261 0.3160001 -0.09944844 -0.005868017 0.340854 -0.08913069 -0.006071984 0.353475 -0.08783513 -0.005907833 0.365633 -0.07392084 -0.006433129 0.4143948 -0.08645921 -0.005807757 0.377798 -0.08003479 -0.006629467 0.426623 -0.07816118 -0.007274329 0.438889 -0.07607269 -0.008026897 0.451166 -0.07362711 -0.008737027 0.463424 -0.07068169 -0.009254276 0.475638 -0.06709378 -0.009427845 0.487778 -0.06272053 -0.009107232 0.499817 -0.05741971 -0.008141756 0.511727 -0.09948641 -0.006591737 0.199385 -0.09218555 -0.006967842 0.231696 -0.09324973 -0.006814956 0.207289 -0.08664232 -0.007039606 0.213391 -0.0908553 -0.007085621 0.256097 -0.09009605 -0.007113635 0.268292 -0.0892769 -0.007111608 0.280482 -0.09035867 -0.007059514 0.285 -0.08544379 -0.00667119 0.329168 -0.08434695 -0.006464362 0.341322 -0.07229 -0.00687617 0.4266328 -0.07054358 -0.007517635 0.4389088 -0.07077264 -0.008197546 0.451166 -0.06631493 -0.008969247 0.4634166 -0.06357002 -0.009480297 0.4756337 -0.06022536 -0.009646296 0.4877753 -0.021878 0.003125429 0.5556403 -0.05616456 -0.009315848 0.499815 -0.05123561 -0.00833863 0.5117254 -0.04530781 -0.006565034 0.5234787 -0.02649241 -7.84716e-4 0.5457694 -0.0308606 -0.004161059 0.5349344 -0.08086258 -0.007073342 0.01195281 -0.07722979 -0.007128715 0 0.06556546 -0.009949028 0.05820518 -0.08792084 -0.006820499 0.170684 -0.08747065 -0.006899476 0.1889845 -0.08456581 -0.00726962 0.256097 -0.0820232 -0.007307946 0.285 -0.08383393 -0.00729686 0.268292 -0.0858519 -0.007153153 0.231696 -0.08523929 -0.007219374 0.243898 -0.07938379 -0.006848454 0.329168 -0.07648432 -0.007155239 0.3160001 -0.0783419 -0.006640076 0.341322 -0.06984931 -0.006328105 0.4021801 -0.06333953 -0.008411467 0.4511434 -0.07281017 -0.007274508 0.01199787 -0.08168178 -0.006964385 0.05484753 -0.08201509 -0.006904423 0.127996 -0.08028346 -0.00721085 0.213391 -0.08138906 -0.007017016 0.176784 -0.0809198 -0.007101416 0.195085 -0.07951772 -0.007323741 0.231696 -0.06666338 -0.006382942 0.3778122 -0.06544137 -0.006369113 0.389985 -0.06278228 -0.006735146 0.4143908 -0.06131482 -0.007173657 0.4266287 -0.05975466 -0.007809817 0.4389005 -0.05596798 -0.009249985 0.463419 -0.05349469 -0.009753584 0.4756354 -0.05051279 -0.009909689 0.4877762 -0.04687869 -0.009567677 0.4998157 -0.01479429 0.002921283 0.5556413 -0.04248225 -0.008575975 0.511726 -0.03718453 -0.006785213 0.5234792 -0.07193201 -0.007229149 0.0426588 -0.07230263 -0.007159352 0.07922691 -0.0724197 -0.007137417 0.1036092 -0.07401275 -0.007101237 0.1249475 -0.07202631 -0.00721085 0.1645845 -0.07179725 -0.007253646 0.176784 -0.07150846 -0.007307648 0.1889845 -0.07649296 -0.007319629 0.303 -0.05854487 -0.006614029 0.4021759 -0.05221986 -0.008691489 0.451166 -0.05934298 -0.00758183 0.01190328 -0.05258136 -0.007716834 0 -0.06567627 -0.007349789 0.05484753 -0.06352686 -0.007490634 0.1889845 -0.05898004 -0.007830739 0.2926501 -0.05403554 -0.006816506 0.3656454 -0.05305147 -0.006705999 0.3778054 -0.05407506 -0.006640315 0.3899818 -0.05172693 -0.006998836 0.4143885 -0.05042994 -0.007433235 0.4266269 -0.04711645 -0.00810945 0.438896 -0.04570943 -0.009494781 0.4634205 -0.04353362 -0.009991228 0.4756361 -0.04091173 -0.0101388 0.4877765 -0.03770583 -0.009786546 0.499816 -0.03380769 -0.008782923 0.5117263 -0.02912861 -0.006977319 0.5234794 -0.06106549 -0.007419764 0.07617926 -0.05957311 -0.007432937 0.09751343 -0.05913257 -0.007520318 0.170684 -0.0573467 -0.007846057 0.231696 -0.05859345 -0.007627427 0.195085 -0.05682629 -0.007910013 0.243898 -0.05802583 -0.007735252 0.213391 -0.05625951 -0.007957696 0.256097 -0.05565094 -0.007981896 0.268292 -0.05124664 -0.008059501 0.2804757 -0.05287349 -0.007701814 0.317009 -0.05210995 -0.007511436 0.329168 -0.05131566 -0.007297039 0.341322 -0.04689282 -0.007167756 0.3534845 -0.04741495 -0.006867349 0.4021732 -0.04161691 -0.008932471 0.451166 -0.04598927 -0.007867038 0.01218795 -0.05045592 -0.007684051 0.05332392 -0.05157673 -0.007600843 0.1036092 -0.03682076 -0.007015645 0.3899585 -0.03540772 -0.007353901 0.4143797 -0.03437268 -0.007782459 0.4266189 -0.03162252 -0.009802162 0.4634241 -0.02982032 -0.01029032 0.4756383 -0.02764874 -0.01042801 0.4877783 -0.02507275 -0.01006197 0.4998171 -0.02187013 -0.009043097 0.5117271 0.02652919 0.01007157 0.5707992 -0.03875887 -0.008028388 0 -0.04620885 -0.007820546 0.03047013 -0.04025441 -0.007856369 0.07922691 -0.04651165 -0.007756531 0.1584849 -0.03913974 -0.007941484 0.170684 -0.04611253 -0.007840871 0.182884 -0.04467648 -0.008116483 0.231696 -0.04583418 -0.007899701 0.195085 -0.04419708 -0.008179545 0.243898 -0.04530608 -0.008006691 0.213391 -0.0436778 -0.008226215 0.256097 -0.04312378 -0.008249282 0.268292 -0.04192984 -0.008195996 0.292666 -0.04129874 -0.008105397 0.304842 -0.03769314 -0.00802499 0.3170391 -0.03316855 -0.00791043 0.329168 -0.03930312 -0.007553398 0.341322 -0.03494125 -0.007225453 0.3656105 -0.03454113 -0.007102251 0.3777948 -0.03256988 -0.007183134 0.4021599 -0.02991694 -0.008477032 0.4388861 -0.02844125 -0.009214699 0.4511911 0.03268688 0.006113648 0.5641606 -0.02635931 -0.008296608 0 -0.0352652 -0.007996439 0.05484753 0.02831894 0.01004785 0.5707999 -0.02511054 -0.008149266 0.09751325 -0.02500891 -0.008173406 0.146288 -0.02489721 -0.008200049 0.1584849 -0.02454787 -0.008283376 0.182884 -0.03258639 -0.008268833 0.213391 -0.02329576 -0.008555173 0.231696 -0.02430343 -0.00834155 0.195085 -0.02130633 -0.008649051 0.243898 -0.02087342 -0.008693933 0.256097 -0.004620671 -0.009037554 0.2684258 -0.004165947 -0.009026885 0.2805892 -0.02101689 -0.008625149 0.292666 -0.006654262 -0.008813858 0.304915 -0.01903188 -0.007969379 0.341322 -0.02521163 -0.007616817 0.353475 -0.02696728 -0.008229315 0.02437603 -4.59997e-4 -0.01043963 0.4634292 -0.003838002 -0.0108217 0.47564 0.001584827 -0.01102572 0.4877801 0.002947568 -0.01063489 0.4998185 -0.008232951 -0.008669137 0 -0.01587122 -0.008435249 0.03351718 -0.01525598 -0.00840485 0.05484753 -0.01621747 -0.008347928 0.07922691 -0.01509672 -0.008625507 0.213391 0.002535164 -0.007859945 0.3777907 0.00355798 -0.008150696 0.41438 0.004015624 -0.008567512 0.4266194 0.004562914 -0.009181499 0.4388833 0.02965575 0.01005315 0.570799 -0.007677853 -0.008652627 0.01218795 -0.007949948 -0.008581101 0.170684 -0.003982245 -0.008715093 0.317009 -0.003619134 -0.00851643 0.329168 -0.002912223 -0.008073627 0.353475 -0.002552986 -0.00788778 0.365633 -0.001717209 -0.007732927 0.3899744 -0.001300394 -0.007821798 0.4021686 0.01119673 -0.0100243 0.4511387 0.005092144 -0.008919477 0.01218795 0.006079912 -0.008946239 0 -0.001456677 -0.008740186 0.03047013 -0.001650333 -0.008686542 0.05484753 0.01736134 -0.009030938 0.109705 -0.001776695 -0.008651435 0.1462879 -0.001681923 -0.008677721 0.1584849 0.004776597 -0.009038627 0.213391 -0.001385331 -0.008759975 0.1828839 0.006003737 -0.009161174 0.231696 0.005201339 -0.008951783 0.1950849 0.004741132 -0.00918734 0.243898 0.00507611 -0.009230256 0.256097 0.007642269 -0.009217917 0.292666 0.002741217 -0.008417367 0.341322 0.01675277 -0.01125013 0.4756346 0.05659091 -0.01057928 0.5117269 0.02183437 0.01252496 0.574403 0.02394068 0.01201736 0.573711 0.01466965 -0.00912249 0.01218795 0.01497364 -0.009110689 0 0.01132947 -0.009009599 0.03047013 0.01753056 -0.009085237 0.1584849 0.01778364 -0.009166538 0.1828839 0.01764106 -0.009120762 0.1706839 0.0234096 -0.009449005 0.3047887 0.02345025 -0.009293854 0.3169448 0.02362453 -0.009090602 0.3291454 0.02374237 -0.00886166 0.3413236 0.02383089 -0.008636534 0.3534963 0.02390217 -0.008444488 0.3656693 0.02403146 -0.008276522 0.3900024 0.02410393 -0.008358299 0.4021857 0.02018821 -0.01087337 0.4634196 0.06284666 -0.0116648 0.499817 0.06782644 -0.01185697 0.49746 0.06816041 -0.01196223 0.495169 0.0210542 -0.0092597 0.01218795 0.02133339 -0.009225189 0 0.03662854 -0.009455442 0.09141767 0.02778178 -0.009497046 0.2074431 0.02843987 -0.009692609 0.2438099 0.02868199 -0.009733557 0.2559762 0.02891778 -0.009750247 0.2681707 0.02914136 -0.009735345 0.2803865 0.05172443 -0.002301752 0.5457699 0.05587279 -0.003072202 0.543734 0.05678945 -0.003771066 0.541696 0.02742582 -0.009397327 0.01209694 0.02769225 -0.009336709 0 0.03660523 -0.009446442 0.1158019 0.0275653 -0.009430468 0.1952089 0.02795255 -0.009567201 0.2195023 0.02818477 -0.009635329 0.2316829 0.02933573 -0.009681522 0.292675 0.02397763 -0.008316636 0.377798 0.02420359 -0.008590519 0.414384 0.02446979 -0.009605824 0.438889 0.0243203 -0.009000122 0.426623 0.07139319 -0.01172578 0.465074 0.04262995 -0.01190084 0.4877788 0.06100529 -0.01055389 0.5117269 0.06710958 -0.0115686 0.502026 0.04609906 0.001755714 0.5556409 0.05384612 -0.001617848 0.5476989 0.04759091 0.002325654 0.556927 0.03862112 0.00608015 0.5641599 0.03384548 -0.009536445 0.01215112 0.03405129 -0.009445428 0 0.04624837 -0.009658277 0.09141767 0.04622733 -0.009649336 0.1158019 0.03152078 -0.009523093 0.2048519 0.03152006 -0.0095371 0.216704 0.03151947 -0.009548187 0.2285559 0.03151905 -0.009556531 0.2404069 0.03151875 -0.009561955 0.252258 0.03151857 -0.009565114 0.2645238 0.03151881 -0.009561359 0.287811 0.03151911 -0.009555518 0.299661 0.03151953 -0.009546816 0.311511 0.03152018 -0.009535253 0.323361 0.0315209 -0.009520888 0.335211 0.03152179 -0.009503722 0.34706 0.03152287 -0.009483635 0.358909 0.03152406 -0.009460806 0.370758 0.03152543 -0.009435057 0.382607 0.03152692 -0.009406566 0.394456 0.03152859 -0.009375154 0.406304 0.03153038 -0.009340941 0.418152 0.03887993 -0.009925901 0.4390324 0.03153228 -0.009303927 0.43 0.06503421 -0.01039332 0.5133559 0.05871647 -0.008617997 0.5234799 0.05577301 -0.005816638 0.5349349 0.06190013 -0.007962882 0.526741 0.04022914 -0.009672701 0.01215708 0.04041045 -0.009551227 0 0.0527237 -0.009812653 0.06703686 0.05265766 -0.009782254 0.09141767 0.03695178 -0.009579539 0.1828839 0.03152167 -0.009506285 0.193 0.04016524 -0.009497821 0.43 0.04427242 -0.01073974 0.4512082 0.0687884 -0.01211202 0.490575 0.0584805 -0.005094528 0.537544 0.03400158 0.0087893 0.568821 0.03206843 0.009506046 0.569973 0.04663562 -0.009806871 0.01216393 0.04676979 -0.009654104 0 0.05263859 -0.009773373 0.1158019 0.05905008 -0.009866893 0.1228363 0.03970509 -0.00969237 0.193 0.06633168 -0.01118296 0.5065739 0.06591546 -0.01094669 0.5088399 0.05157124 -8.42456e-5 0.5515249 0.05031675 7.03014e-4 0.5533679 0.03775274 0.007242798 0.566253 0.0530132 -0.009930133 0.01216286 0.05312925 -0.009754121 0 0.05907201 -0.009876787 0.09141767 0.05028915 -0.009689033 0.43 0.0460782 -0.01006841 0.438889 0.07174527 -0.01150405 0.460406 0.06356722 -0.009322822 0.5200849 0.06407463 -0.00971049 0.517848 0.04296433 0.004804611 0.561868 0.04457813 0.003975868 0.5602779 0.06548678 -0.009905993 0.09141767 0.0654667 -0.009896099 0.1228321 0.06553637 -0.009934961 0.1527504 0.0531733 -0.009951531 0.193 0.05147814 -0.0101729 0.438889 0.06988745 -0.01217842 0.481343 0.06848144 -0.01204675 0.492874 0.06672942 -0.01138979 0.5043029 0.0612964 -0.007444083 0.5289419 0.06064909 -0.006898939 0.53112 0.05765938 -0.004445195 0.539632 0.05273818 -8.61296e-4 0.5496289 0.03590416 0.00802493 0.567573 0.07846045 -0.01005154 0.02243006 0.07206571 -0.009945213 0.04265862 0.07196336 -0.009881079 0.07807928 0.07837307 -0.009991288 0.04754501 0.07832008 -0.009954392 0.07406198 0.07832998 -0.009961247 0.06729954 0.07191377 -0.009859204 0.1060188 0.07830488 -0.009943962 0.09423887 0.07831799 -0.009953022 0.1201967 0.0719285 -0.009860813 0.121899 0.07194018 -0.00987786 0.1413287 0.07834625 -0.009972453 0.1369051 0.07841604 -0.01002061 0.1615775 0.07838702 -0.01000046 0.1525781 0.05798041 -0.009803235 0.43 0.05688238 -0.01025253 0.438889 0.07120388 -0.01182216 0.467404 0.06456363 -0.01006728 0.5156049 0.04612118 0.003152668 0.5586339 0.07842057 -0.01002365 0.03274202 0.07834744 -0.009973227 0.05830723 0.07830542 -0.009944736 0.1058744 0.07836186 -0.00998336 0.143606 0.06300592 -0.009848952 0.43 0.06228649 -0.01027715 0.438889 0.07036566 -0.01210981 0.476707 0.05941349 -0.01213258 0.487778 0.06248044 -0.008449196 0.524532 0.05924159 -0.005723953 0.535421 0.03954273 0.00644946 0.5648649 0.02601557 0.01146399 0.572924 0.07830917 -0.009947121 0.08432555 0.0783329 -0.009963393 0.1301379 0.0784409 -0.01003777 0.1682943 0.06824207 -0.009867966 0.43 0.07237553 -0.01099938 0.451056 0.07157301 -0.01161921 0.462741 0.07058978 -0.0120567 0.474385 0.06908249 -0.01215678 0.488273 0.06747591 -0.01172435 0.499745 0.06548261 -0.01068347 0.511101 0.06303745 -0.008903026 0.522314 0.05996209 -0.0063259 0.533279 0.05489403 -0.002353966 0.545736 0.04898995 0.001506268 0.5551689 0.04127764 0.005639135 0.5634049 0.02806746 0.01085418 0.572033 0.03009074 0.0101943 0.571043 0.03874742 -0.005381643 0.188 0.03739523 -0.004393756 0.188 0.03755384 -0.004348397 0.188 0.03819715 -0.004435777 0.188 0.03846335 -0.004630029 0.188 0.03856885 -0.004757225 0.188 0.03833884 -0.004521906 0.188 0.03865146 -0.004900038 0.188 0.03804415 -0.004374086 0.188 0.03870952 -0.005054533 0.188 0.0378828 -0.004338383 0.188 0.03771805 -0.004329741 0.188 0.03874206 -0.005216538 0.188 0.03860163 -0.005850732 0.188 0.0371102 -0.004559159 0.188 0.03867548 -0.005703091 0.188 0.03872483 -0.005545318 0.188 0.03724634 -0.004464685 0.188 0.03699302 -0.004674673 0.188 0.03850454 -0.005984127 0.188 0.03689491 -0.004808008 0.188 0.03810131 -0.006264925 0.188 0.03675013 -0.005276978 0.188 0.03677171 -0.005113303 0.188 0.03838634 -0.006099641 0.188 0.0382502 -0.006194055 0.188 0.03682106 -0.004955589 0.188 0.03678709 -0.005603909 0.188 0.03761374 -0.006320178 0.188 0.03684508 -0.005758345 0.188 0.03675448 -0.005442082 0.188 0.0379427 -0.006310284 0.188 0.03777849 -0.006328821 0.188 0.0370332 -0.006028354 0.188 0.03729945 -0.006222665 0.188 0.03715771 -0.006136476 0.188 0.03692775 -0.005901157 0.188 0.03745239 -0.006284415 0.188 0.05346709 -0.004896402 0.193 0.03874206 -0.005216538 0.193 0.03870952 -0.005054533 0.193 0.07368355 -0.00909394 0.193 0.07270395 -0.01012086 0.193 0.03874742 -0.005381643 0.193 0.03675013 -0.005276978 0.193 0.03675448 -0.005442082 0.193 0.03152167 -0.009506285 0.193 0.03865146 -0.004900038 0.193 0.04689365 -0.003548145 0.193 0.03678709 -0.005604147 0.193 0.03684508 -0.005758702 0.193 0.03804415 -0.004374086 0.193 0.0378828 -0.004338383 0.193 0.03856885 -0.004757225 0.193 0.03860169 -0.005850434 0.193 0.03867554 -0.005702853 0.193 0.03761374 -0.006320238 0.193 0.03753364 -0.009645342 0.193 0.03777951 -0.006328821 0.193 0.0434913 -0.009769082 0.193 0.03810232 -0.006264746 0.193 0.03825122 -0.006193757 0.193 0.04937344 -0.009881913 0.193 0.05519628 -0.009980738 0.193 0.05861741 -0.005959272 0.193 0.06362044 -0.006996393 0.193 0.0379427 -0.006310105 0.193 0.06102448 -0.01005345 0.193 0.06859368 -0.00803107 0.193 0.06686103 -0.01010018 0.193 0.07855325 -0.01011556 0.193 0.03771805 -0.004329741 0.193 0.04197627 -0.002545475 0.193 0.03199237 -5.24417e-4 0.193 0.03699302 -0.004674673 0.193 0.03689491 -0.004808008 0.193 0.03833884 -0.004521906 0.193 0.03846335 -0.004630029 0.193 0.03819715 -0.004435777 0.193 0.03707605 -0.001550734 0.193 0.03755384 -0.004348397 0.193 0.03739523 -0.004393756 0.193 0.03724634 -0.004464685 0.193 0.0371102 -0.004559159 0.193 0.03682106 -0.004955589 0.193 0.03677171 -0.005113303 0.193 0.03692871 -0.005901575 0.193 0.03703421 -0.006028771 0.193 0.03715872 -0.006136834 0.193 0.03729939 -0.006222903 0.193 0.03745239 -0.006284594 0.193 0.03838634 -0.006099224 0.193 0.0385046 -0.005983769 0.193 0.03872483 -0.005545318 0.193 0.03874206 -0.005216538 0.188 0.03874742 -0.005381643 0.193 0.03874742 -0.005381643 0.188 0.03856885 -0.004757225 0.188 0.03865146 -0.004900038 0.193 0.03865146 -0.004900038 0.188 0.03870952 -0.005054533 0.188 0.03870952 -0.005054533 0.193 0.03874206 -0.005216538 0.193 0.03833884 -0.004521906 0.193 0.03833884 -0.004521906 0.188 0.03819715 -0.004435777 0.188 0.03856885 -0.004757225 0.193 0.03846335 -0.004630029 0.188 0.03846335 -0.004630029 0.193 0.0378828 -0.004338383 0.188 0.03771805 -0.004329741 0.188 0.0378828 -0.004338383 0.193 0.03804415 -0.004374086 0.188 0.03804415 -0.004374086 0.193 0.03819715 -0.004435777 0.193 0.03724634 -0.004464685 0.188 0.03739523 -0.004393756 0.193 0.03739523 -0.004393756 0.188 0.03755384 -0.004348397 0.193 0.03771805 -0.004329741 0.193 0.03755384 -0.004348397 0.188 0.03699302 -0.004674673 0.193 0.03699302 -0.004674673 0.188 0.03689491 -0.004808008 0.188 0.03724634 -0.004464685 0.193 0.0371102 -0.004559159 0.188 0.0371102 -0.004559159 0.193 0.03677171 -0.005113303 0.188 0.03675013 -0.005276978 0.188 0.03677171 -0.005113303 0.193 0.03682106 -0.004955589 0.188 0.03682106 -0.004955589 0.193 0.03689491 -0.004808008 0.193 0.03684508 -0.005758345 0.188 0.03678709 -0.005604147 0.193 0.03678709 -0.005603909 0.188 0.03675448 -0.005442082 0.193 0.03675013 -0.005276978 0.193 0.03675448 -0.005442082 0.188 0.03703421 -0.006028771 0.193 0.0370332 -0.006028354 0.188 0.03715771 -0.006136476 0.188 0.03684508 -0.005758702 0.193 0.03692775 -0.005901157 0.188 0.03692871 -0.005901575 0.193 0.03745239 -0.006284415 0.188 0.03761374 -0.006320178 0.188 0.03745239 -0.006284594 0.193 0.03729945 -0.006222665 0.188 0.03729939 -0.006222903 0.193 0.03715872 -0.006136834 0.193 0.03777849 -0.006328821 0.188 0.0379427 -0.006310284 0.188 0.03777951 -0.006328821 0.193 0.03761374 -0.006320238 0.193 0.0379427 -0.006310105 0.193 0.03810131 -0.006264925 0.188 0.0382502 -0.006194055 0.188 0.03810232 -0.006264746 0.193 0.03838634 -0.006099641 0.188 0.03825122 -0.006193757 0.193 0.03838634 -0.006099224 0.193 0.03850454 -0.005984127 0.188 0.03860163 -0.005850732 0.188 0.0385046 -0.005983769 0.193 0.03867548 -0.005703091 0.188 0.03860169 -0.005850434 0.193 0.03867554 -0.005702853 0.193 0.03872483 -0.005545318 0.188 0.03872483 -0.005545318 0.193 -0.1175653 0.005660057 0.09454816 -0.1174083 0.008655965 0.09454816 -0.1202825 0.008806586 0.09432649 -0.1204395 0.005810678 0.09432649 -0.1204395 0.005810678 0.09432649 -0.1202825 0.008806586 0.09432649 -0.1219114 0.00889194 0.09670823 -0.1220684 0.005896031 0.09670823 -0.1220684 0.005896031 0.09670823 -0.1219114 0.00889194 0.09670823 -0.120666 0.008826673 0.0993117 -0.120823 0.005830764 0.0993117 -0.120823 0.005830764 0.0993117 -0.120666 0.008826673 0.0993117 -0.1177917 0.008676052 0.09953337 -0.1179487 0.005680143 0.09953337 -0.1179487 0.005680143 0.09953337 -0.1177917 0.008676052 0.09953337 -0.1161628 0.008590698 0.09715157 -0.1163198 0.005594789 0.09715157 -0.1163198 0.005594789 0.09715157 -0.1161628 0.008590698 0.09715157 -0.1174083 0.008655965 0.09454816 -0.1175653 0.005660057 0.09454816 -0.1174083 0.008655965 0.09454816 -0.1143335 0.008494794 0.0950399 -0.1146785 0.008512914 0.09428995 -0.1230203 0.008950054 0.09375011 -0.1234589 0.008973002 0.09444946 -0.1202825 0.008806586 0.09432649 -0.115142 0.008537173 0.09360712 -0.1161628 0.008590698 0.09715157 -0.1157114 0.008567035 0.09301 -0.1140333 0.008479058 0.09665811 -0.1141164 0.008483469 0.09583652 -0.1140863 0.00848186 0.0974822 -0.114274 0.008491694 0.09828639 -0.117103 0.008639931 0.09213525 -0.1163711 0.008601605 0.09251487 -0.1145915 0.008508324 0.09904867 -0.1178867 0.008680999 0.09188145 -0.1195272 0.008767008 0.091775 -0.1203381 0.008809447 0.09192556 -0.1150299 0.008531332 0.09974825 -0.1224728 0.008921325 0.09313261 -0.1177124 0.008671879 0.1015737 -0.1169372 0.008631229 0.1012914 -0.1177917 0.008676052 0.09953337 -0.1237764 0.008989632 0.0952115 -0.1219114 0.00889194 0.09670823 -0.120666 0.008826673 0.0993117 -0.1193482 0.008757591 0.1017392 -0.1240178 0.009002327 0.09683966 -0.1239349 0.008997976 0.09766125 -0.1223406 0.008914411 0.1004886 -0.1216808 0.00887984 0.100984 -0.1237182 0.008986592 0.09845799 -0.1233733 0.008968532 0.09920817 -0.12291 0.008944272 0.09989124 -0.1239645 0.008999526 0.09601557 -0.1209486 0.008841454 0.101364 -0.1185234 0.008714377 0.1017244 -0.1218312 0.008887708 0.09261375 -0.1211131 0.008850097 0.09220772 -0.116219 0.008593618 0.1008852 -0.1155774 0.008560001 0.1003661 -0.1187027 0.008723795 0.09176015 -0.1201639 0.008800327 0.101618 -0.1175653 0.005660057 0.09454816 -0.114834 0.005516946 0.0942924 -0.1144894 0.005498886 0.09504276 -0.1231773 0.005954146 0.09375011 -0.1226298 0.005925416 0.09313261 -0.1204395 0.005810678 0.09432649 -0.1152973 0.005541205 0.09360903 -0.1158667 0.005571067 0.09301137 -0.1142728 0.005487501 0.09583967 -0.1141902 0.00548321 0.09666138 -0.1163198 0.005594789 0.09715157 -0.1142438 0.005486011 0.09748548 -0.1144321 0.005495846 0.09828943 -0.1165266 0.005605638 0.0925157 -0.11475 0.005512535 0.09905135 -0.1172589 0.005644023 0.0921356 -0.1188597 0.005727887 0.09176015 -0.1196842 0.0057711 0.091775 -0.1151887 0.005535483 0.09975045 -0.1219882 0.005891799 0.09261375 -0.1157363 0.005564212 0.1003677 -0.1163778 0.005597829 0.1008863 -0.1179487 0.005680143 0.09953337 -0.1220684 0.005896031 0.09670823 -0.1239334 0.005993783 0.0952115 -0.1236158 0.005977094 0.09444946 -0.1186804 0.005718469 0.1017244 -0.1195052 0.005761682 0.1017392 -0.1240919 0.006002068 0.09766125 -0.1241748 0.006006419 0.09683966 -0.1218378 0.005883932 0.100984 -0.120823 0.005830764 0.0993117 -0.1211056 0.005845546 0.101364 -0.1238752 0.005990684 0.09845799 -0.1235303 0.005972623 0.09920817 -0.1224976 0.005918502 0.1004886 -0.123067 0.005948364 0.09989124 -0.1241215 0.006003618 0.09601557 -0.1203209 0.005804479 0.101618 -0.1178706 0.005676031 0.101574 -0.1212701 0.005854189 0.09220772 -0.1204951 0.005813598 0.09192556 -0.1180437 0.00568515 0.09188145 -0.1170958 0.00563544 0.101292 -0.1239645 0.008999526 0.09601557 -0.1241215 0.006003618 0.09601557 -0.1241748 0.006006419 0.09683966 -0.1186804 0.005718469 0.1017244 -0.1193482 0.008757591 0.1017392 -0.1195052 0.005761682 0.1017392 -0.1237764 0.008989632 0.0952115 -0.1239334 0.005993783 0.0952115 -0.1236158 0.005977094 0.09444946 -0.1234589 0.008973002 0.09444946 -0.1230203 0.008950054 0.09375011 -0.1231773 0.005954146 0.09375011 -0.1224728 0.008921325 0.09313261 -0.1226298 0.005925416 0.09313261 -0.1219882 0.005891799 0.09261375 -0.1218312 0.008887708 0.09261375 -0.1211131 0.008850097 0.09220772 -0.1212701 0.005854189 0.09220772 -0.1203381 0.008809447 0.09192556 -0.1204951 0.005813598 0.09192556 -0.1196842 0.0057711 0.091775 -0.1195272 0.008767008 0.091775 -0.1187027 0.008723795 0.09176015 -0.1188597 0.005727887 0.09176015 -0.1240178 0.009002327 0.09683966 -0.1240919 0.006002068 0.09766125 -0.1239349 0.008997976 0.09766125 -0.1238752 0.005990684 0.09845799 -0.1237182 0.008986592 0.09845799 -0.1233733 0.008968532 0.09920817 -0.1235303 0.005972623 0.09920817 -0.123067 0.005948364 0.09989124 -0.12291 0.008944272 0.09989124 -0.1224976 0.005918502 0.1004886 -0.1223406 0.008914411 0.1004886 -0.1216808 0.00887984 0.100984 -0.1218378 0.005883932 0.100984 -0.1211056 0.005845546 0.101364 -0.1209486 0.008841454 0.101364 -0.1203209 0.005804479 0.101618 -0.1201639 0.008800327 0.101618 -0.1163778 0.005597829 0.1008863 -0.1169372 0.008631229 0.1012914 -0.1170958 0.00563544 0.101292 -0.1178706 0.005676031 0.101574 -0.1177124 0.008671879 0.1015737 -0.1185234 0.008714377 0.1017244 -0.1150299 0.008531332 0.09974825 -0.1151887 0.005535483 0.09975045 -0.11475 0.005512535 0.09905135 -0.116219 0.008593618 0.1008852 -0.1157363 0.005564212 0.1003677 -0.1155774 0.008560001 0.1003661 -0.1142438 0.005486011 0.09748548 -0.1141902 0.00548321 0.09666138 -0.1140863 0.00848186 0.0974822 -0.1144321 0.005495846 0.09828943 -0.114274 0.008491694 0.09828639 -0.1145915 0.008508324 0.09904867 -0.114834 0.005516946 0.0942924 -0.1143335 0.008494794 0.0950399 -0.1144894 0.005498886 0.09504276 -0.1141164 0.008483469 0.09583652 -0.1140333 0.008479058 0.09665811 -0.1142728 0.005487501 0.09583967 -0.1157114 0.008567035 0.09301 -0.115142 0.008537173 0.09360712 -0.1158667 0.005571067 0.09301137 -0.1146785 0.008512914 0.09428995 -0.1152973 0.005541205 0.09360903 -0.1165266 0.005605638 0.0925157 -0.1163711 0.008601605 0.09251487 -0.1172589 0.005644023 0.0921356 -0.117103 0.008639931 0.09213525 -0.1178867 0.008680999 0.09188145 -0.1180437 0.00568515 0.09188145 -0.1192466 9.9169e-4 0.0950275 -0.1178494 9.18473e-4 0.09604859 -0.1210126 0.001084208 0.09745085 -0.1196154 0.001011013 0.09847187 -0.1208282 0.001074552 0.09572863 -0.1180338 9.28139e-4 0.09777075 -0.121065 8.56067e-5 0.09745085 -0.1208282 0.001074552 0.09572863 -0.1210126 0.001084208 0.09745085 -0.1208806 7.59414e-5 0.09572863 -0.1196678 1.23903e-5 0.09847187 -0.1210126 0.001084208 0.09745085 -0.1196154 0.001011013 0.09847187 -0.121065 8.56067e-5 0.09745085 -0.1180862 -7.04913e-5 0.09777075 -0.1196154 0.001011013 0.09847187 -0.1180338 9.28139e-4 0.09777075 -0.1196678 1.23903e-5 0.09847187 -0.1179018 -8.01566e-5 0.09604859 -0.1180338 9.28139e-4 0.09777075 -0.1178494 9.18473e-4 0.09604859 -0.1180862 -7.04913e-5 0.09777075 -0.1192989 -6.94022e-6 0.0950275 -0.1178494 9.18473e-4 0.09604859 -0.1192466 9.9169e-4 0.0950275 -0.1179018 -8.01566e-5 0.09604859 -0.1208806 7.59414e-5 0.09572863 -0.1192466 9.9169e-4 0.0950275 -0.1208282 0.001074552 0.09572863 -0.1192989 -6.94022e-6 0.0950275 -0.1180207 -7.39195e-5 0.0947237 -0.1192989 -6.94022e-6 0.0950275 -0.1183738 -5.54204e-5 0.09451019 -0.1219772 1.33408e-4 0.09663242 -0.1208806 7.59414e-5 0.09572863 -0.121065 8.56067e-5 0.09745085 -0.1187571 -3.53334e-5 0.09435784 -0.1179018 -8.01566e-5 0.09604859 -0.1191602 -1.42076e-5 0.09427076 -0.1177076 -9.03273e-5 0.09499245 -0.117443 -1.04195e-4 0.09530913 -0.1172341 -1.15145e-4 0.09566509 -0.1195722 7.38143e-6 0.09425127 -0.1170864 -1.2288e-4 0.09605062 -0.1199818 2.88433e-5 0.09430003 -0.1203777 4.95927e-5 0.0944156 -0.1213794 1.02082e-4 0.09512329 -0.1210862 8.6718e-5 0.09483295 -0.1207493 6.90629e-5 0.09459495 -0.1219239 1.30615e-4 0.09622299 -0.1180862 -7.04913e-5 0.09777075 -0.117163 -1.18868e-4 0.0976721 -0.1173462 -1.09269e-4 0.09804183 -0.1218801 1.28321e-4 0.0974496 -0.1219624 1.32636e-4 0.097045 -0.1185889 -4.41482e-5 0.09908372 -0.1182174 -6.36128e-5 0.09890449 -0.1212586 9.57507e-5 0.09850752 -0.1215233 1.09623e-4 0.09819096 -0.1196678 1.23903e-5 0.09847187 -0.1193941 -1.94903e-6 0.09924811 -0.1198061 1.96346e-5 0.09922873 -0.1209454 7.9341e-5 0.09877616 -0.1205924 6.08417e-5 0.09898948 -0.1202091 4.07568e-5 0.09914171 -0.1217324 1.20579e-4 0.09783512 -0.1178804 -8.12726e-5 0.09866636 -0.121804 1.24334e-4 0.09582787 -0.1216208 1.14736e-4 0.09545797 -0.1175876 -9.6617e-5 0.09837639 -0.1169896 -1.27953e-4 0.09686779 -0.117043 -1.25153e-4 0.09727716 -0.1170042 -1.27188e-4 0.09645521 -0.1189847 -2.34048e-5 0.09919935 -0.1171294 0.001882076 0.09566509 -0.117443 -1.04195e-4 0.09530913 -0.1173383 0.001893043 0.09530913 -0.1182174 -6.36128e-5 0.09890449 -0.1181128 0.001933634 0.09890449 -0.1184842 0.001953065 0.09908372 -0.117603 0.001906931 0.09499245 -0.1177076 -9.03273e-5 0.09499245 -0.1180207 -7.39195e-5 0.0947237 -0.1179161 0.001923322 0.0947237 -0.1183738 -5.54204e-5 0.09451019 -0.1182691 0.0019418 0.09451019 -0.1186524 0.001961886 0.09435784 -0.1187571 -3.53334e-5 0.09435784 -0.1191602 -1.42076e-5 0.09427076 -0.1190556 0.001983046 0.09427076 -0.1195722 7.38143e-6 0.09425127 -0.1194676 0.002004623 0.09425127 -0.1198771 0.002026081 0.09430003 -0.1199818 2.88433e-5 0.09430003 -0.1203777 4.95927e-5 0.0944156 -0.1202731 0.002046823 0.0944156 -0.1207493 6.90629e-5 0.09459495 -0.1206446 0.002066314 0.09459495 -0.1172341 -1.15145e-4 0.09566509 -0.1169818 0.001874327 0.09605062 -0.1170864 -1.2288e-4 0.09605062 -0.1168996 0.001870036 0.09645521 -0.1170042 -1.27188e-4 0.09645521 -0.1169896 -1.27953e-4 0.09686779 -0.116885 0.001869261 0.09686779 -0.1169384 0.001872062 0.09727716 -0.117043 -1.25153e-4 0.09727716 -0.1170583 0.00187838 0.0976721 -0.117163 -1.18868e-4 0.0976721 -0.1173462 -1.09269e-4 0.09804183 -0.1172415 0.001887977 0.09804183 -0.117483 0.001900613 0.09837639 -0.1175876 -9.6617e-5 0.09837639 -0.1177757 0.001915931 0.09866636 -0.1178804 -8.12726e-5 0.09866636 -0.1189847 -2.34048e-5 0.09919935 -0.1185889 -4.41482e-5 0.09908372 -0.11888 0.001973807 0.09919935 -0.1202091 4.07568e-5 0.09914171 -0.1198061 1.96346e-5 0.09922873 -0.1201044 0.002038002 0.09914171 -0.1193941 -1.94903e-6 0.09924811 -0.1192895 0.001995265 0.09924811 -0.1197014 0.002016842 0.09922873 -0.1209454 7.9341e-5 0.09877616 -0.1211539 0.002092957 0.09850752 -0.1212586 9.57507e-5 0.09850752 -0.1204877 0.002058088 0.09898948 -0.1208407 0.002076566 0.09877616 -0.1205924 6.08417e-5 0.09898948 -0.1217754 0.002125561 0.0974496 -0.1218801 1.28321e-4 0.0974496 -0.1217324 1.20579e-4 0.09783512 -0.1216277 0.002117812 0.09783512 -0.1215233 1.09623e-4 0.09819096 -0.1214186 0.002106845 0.09819096 -0.1219239 1.30615e-4 0.09622299 -0.1219772 1.33408e-4 0.09663242 -0.1218192 0.002127826 0.09622299 -0.1219624 1.32636e-4 0.097045 -0.1218578 0.002129852 0.097045 -0.1218725 0.002130627 0.09663242 -0.1215162 0.002111971 0.09545797 -0.121804 1.24334e-4 0.09582787 -0.1216993 0.002121567 0.09582787 -0.1212747 0.002099335 0.09512329 -0.1216208 1.14736e-4 0.09545797 -0.1213794 1.02082e-4 0.09512329 -0.1209815 0.002083957 0.09483295 -0.1210862 8.6718e-5 0.09483295 -0.1202659 0.002046465 0.09854155 -0.1201044 0.002038002 0.09914171 -0.1199593 0.002030372 0.09866333 -0.1211779 0.002094268 0.09761804 -0.1212961 0.002100408 0.09730964 -0.1216277 0.002117812 0.09783512 -0.121362 0.002103865 0.09698599 -0.1217754 0.002125561 0.0974496 -0.1214186 0.002106845 0.09819096 -0.1210106 0.002085447 0.09790271 -0.1218578 0.002129852 0.097045 -0.1213737 0.00210452 0.09665584 -0.1211539 0.002092957 0.09850752 -0.1207988 0.00207436 0.09815597 -0.1218725 0.002130627 0.09663242 -0.1213311 0.002102255 0.09632831 -0.1205483 0.002061247 0.09837085 -0.1208407 0.002076566 0.09877616 -0.1216993 0.002121567 0.09582787 -0.1218192 0.002127826 0.09622299 -0.1204877 0.002058088 0.09898948 -0.1215162 0.002111971 0.09545797 -0.1212352 0.002097249 0.09601229 -0.11888 0.001973807 0.09919935 -0.1189798 0.001979053 0.0987094 -0.1192895 0.001995265 0.09924811 -0.120661 0.002067148 0.09521633 -0.1206446 0.002066314 0.09459495 -0.1209815 0.002083957 0.09483295 -0.1182691 0.0019418 0.09451019 -0.118491 0.001953423 0.09495812 -0.1182086 0.001938641 0.09512889 -0.118366 0.001946866 0.09847354 -0.1186631 0.001962482 0.09861689 -0.1184842 0.001953065 0.09908372 -0.1177464 0.001914441 0.09559726 -0.1175792 0.001905679 0.09588199 -0.1173383 0.001893043 0.09530913 -0.1175224 0.001902699 0.09748762 -0.1172415 0.001887977 0.09804183 -0.1170583 0.00187838 0.0976721 -0.1174612 0.00189948 0.09619045 -0.1171294 0.001882076 0.09566509 -0.1169818 0.001874327 0.09605062 -0.1173954 0.001896023 0.0965141 -0.1174265 0.001897633 0.09717166 -0.1169384 0.001872062 0.09727716 -0.116885 0.001869261 0.09686779 -0.1173837 0.001895427 0.09684419 -0.1168996 0.001870036 0.09645521 -0.1179581 0.001925528 0.09534388 -0.117603 0.001906931 0.09499245 -0.117483 0.001900613 0.09837639 -0.1176689 0.001910388 0.09778344 -0.1178621 0.001920461 0.09805107 -0.1179161 0.001923322 0.0947237 -0.1181128 0.001933634 0.09890449 -0.1180964 0.00193274 0.09828305 -0.1177757 0.001915931 0.09866636 -0.1190556 0.001983046 0.09427076 -0.1194676 0.002004623 0.09425127 -0.1194497 0.002003669 0.094751 -0.1198771 0.002026081 0.09430003 -0.1200942 0.002037465 0.09488242 -0.1197774 0.002020835 0.09478998 -0.1193073 0.001996219 0.09874844 -0.1197014 0.002016842 0.09922873 -0.1203914 0.002053022 0.09502589 -0.1202731 0.002046823 0.0944156 -0.1208955 0.002079427 0.09544855 -0.1212747 0.002099335 0.09512329 -0.1196368 0.002013504 0.09873294 -0.1210887 0.00208956 0.09571629 -0.1186524 0.001961886 0.09435784 -0.1187977 0.001969516 0.09483623 -0.1191202 0.001986384 0.09476655 -0.1211256 0.003092885 0.09761804 -0.1211779 0.002094268 0.09761804 -0.1210106 0.002085447 0.09790271 -0.1180964 0.00193274 0.09828305 -0.1183136 0.002945542 0.09847354 -0.118366 0.001946866 0.09847354 -0.1212437 0.003099083 0.09730964 -0.1212961 0.002100408 0.09730964 -0.121362 0.002103865 0.09698599 -0.1213096 0.00310254 0.09698599 -0.1213214 0.003103137 0.09665584 -0.1213737 0.00210452 0.09665584 -0.1212788 0.003100872 0.09632831 -0.1213311 0.002102255 0.09632831 -0.1212352 0.002097249 0.09601229 -0.1211829 0.003095865 0.09601229 -0.1210364 0.003088176 0.09571629 -0.1210887 0.00208956 0.09571629 -0.1208432 0.003078043 0.09544855 -0.1208955 0.002079427 0.09544855 -0.120661 0.002067148 0.09521633 -0.1206086 0.003065764 0.09521633 -0.1203391 0.003051638 0.09502589 -0.1203914 0.002053022 0.09502589 -0.1209583 0.003084123 0.09790271 -0.1207988 0.00207436 0.09815597 -0.1207465 0.003072977 0.09815597 -0.1205483 0.002061247 0.09837085 -0.120496 0.003059864 0.09837085 -0.1202136 0.003045082 0.09854155 -0.1202659 0.002046465 0.09854155 -0.1199593 0.002030372 0.09866333 -0.119907 0.003028988 0.09866333 -0.1196368 0.002013504 0.09873294 -0.1195845 0.00301212 0.09873294 -0.119255 0.002994835 0.09874844 -0.1193073 0.001996219 0.09874844 -0.1189798 0.001979053 0.0987094 -0.1189274 0.002977669 0.0987094 -0.1186631 0.001962482 0.09861689 -0.1186107 0.002961099 0.09861689 -0.1175224 0.001902699 0.09748762 -0.1176164 0.002909004 0.09778308 -0.1176689 0.001910388 0.09778344 -0.1178621 0.001920461 0.09805107 -0.1178095 0.002919077 0.09805083 -0.1180441 0.002931416 0.09828311 -0.1173313 0.002894043 0.09684354 -0.1173837 0.001895427 0.09684419 -0.1173954 0.001896023 0.0965141 -0.1174698 0.002901315 0.09748715 -0.1174265 0.001897633 0.09717166 -0.117374 0.002896249 0.09717106 -0.1175792 0.001905679 0.09588199 -0.1177464 0.001914441 0.09559726 -0.1175271 0.002904295 0.0958814 -0.1174612 0.00189948 0.09619045 -0.1174089 0.002898097 0.09618979 -0.1173431 0.002894639 0.09651345 -0.118491 0.001953423 0.09495812 -0.1181567 0.002937316 0.09512853 -0.1182086 0.001938641 0.09512889 -0.1179062 0.002924144 0.09534341 -0.1176944 0.002913057 0.09559667 -0.1179581 0.001925528 0.09534388 -0.1190682 0.00298506 0.09476649 -0.1187458 0.002968132 0.09483605 -0.1191202 0.001986384 0.09476655 -0.1184391 0.002952098 0.09495788 -0.1187977 0.001969516 0.09483623 -0.1194497 0.002003669 0.094751 -0.1193977 0.003002345 0.094751 -0.1197774 0.002020835 0.09478998 -0.1197253 0.003019511 0.09478998 -0.1200419 0.003036081 0.09488248 -0.1200942 0.002037465 0.09488242 -0.1202546 0.003047227 0.096381 -0.1211829 0.003095865 0.09601229 -0.1203026 0.003049731 0.09653902 -0.1209583 0.003084123 0.09790271 -0.1207465 0.003072977 0.09815597 -0.1200364 0.003035783 0.09745281 -0.1211256 0.003092885 0.09761804 -0.1201424 0.003041326 0.09732621 -0.120496 0.003059864 0.09837085 -0.11977 0.003021836 0.09764564 -0.1199112 0.003029227 0.09756028 -0.120226 0.003045737 0.09718388 -0.120285 0.003048837 0.09702968 -0.1212437 0.003099083 0.09730964 -0.119907 0.003028988 0.09866333 -0.1196166 0.003013789 0.09770649 -0.120318 0.003050565 0.09686785 -0.1213096 0.00310254 0.09698599 -0.119255 0.002994835 0.09874844 -0.1194554 0.003005325 0.0977413 -0.1195845 0.00301212 0.09873294 -0.1203239 0.003050863 0.09670275 -0.1213214 0.003103137 0.09665584 -0.1192907 0.002996742 0.09774905 -0.1189274 0.002977669 0.0987094 -0.1191269 0.002988159 0.09772956 -0.1212788 0.003100872 0.09632831 -0.1186852 0.002964973 0.09751635 -0.1180441 0.002931416 0.09828311 -0.1178095 0.002919077 0.09805083 -0.1201813 0.003043413 0.09623301 -0.1210364 0.003088176 0.09571629 -0.1203391 0.003051638 0.09502589 -0.1196841 0.003017306 0.09581607 -0.1200419 0.003036081 0.09488248 -0.1193977 0.003002345 0.094751 -0.1191971 0.002991795 0.09575814 -0.1190682 0.00298506 0.09476649 -0.1185681 0.002958834 0.09740036 -0.1176164 0.002909004 0.09778308 -0.1184715 0.002953767 0.09726655 -0.1187413 0.002967953 0.09593927 -0.1181567 0.002937316 0.09512853 -0.1188825 0.002975344 0.09585392 -0.1183502 0.002947449 0.09696066 -0.117374 0.002896249 0.09717106 -0.1183289 0.002946317 0.09679692 -0.1185102 0.002955794 0.09617346 -0.1184266 0.002951443 0.09631586 -0.1175271 0.002904295 0.0958814 -0.1183676 0.002948343 0.09647005 -0.1174089 0.002898097 0.09618979 -0.1179062 0.002924144 0.09534341 -0.1186161 0.002961337 0.0960468 -0.1176944 0.002913057 0.09559667 -0.1183347 0.002946615 0.09663188 -0.1173431 0.002894639 0.09651345 -0.1184391 0.002952098 0.09495788 -0.1187458 0.002968132 0.09483605 -0.1173313 0.002894043 0.09684354 -0.1183982 0.002949953 0.09711867 -0.1174698 0.002901315 0.09748715 -0.1190358 0.002983391 0.09579294 -0.1197253 0.003019511 0.09478998 -0.1193619 0.003000438 0.09575033 -0.1195257 0.003009021 0.09576982 -0.1206086 0.003065764 0.09521633 -0.1198327 0.003025114 0.09588778 -0.1183136 0.002945542 0.09847354 -0.11882 0.002972066 0.0976116 -0.1199675 0.003032207 0.09598302 -0.1208432 0.003078043 0.09544855 -0.1189686 0.002979815 0.09768331 -0.1186107 0.002961099 0.09861689 -0.1200848 0.003038346 0.09609913 -0.1202136 0.003045082 0.09854155 -0.1179838 0.009937822 0.09696018 -0.1179625 0.009936749 0.09679639 -0.1179684 0.009937047 0.09663128 -0.1195449 0.01001965 0.09756028 -0.1194037 0.01001226 0.09764564 -0.1193178 0.01000773 0.09581607 -0.1180015 0.009938776 0.09646946 -0.1180317 0.009940326 0.09711825 -0.1180606 0.009941875 0.09631526 -0.1181049 0.0099442 0.09726625 -0.1182016 0.009949266 0.09740018 -0.1181443 0.009946227 0.09617292 -0.1183189 0.009955406 0.09751635 -0.1182502 0.00995177 0.09604632 -0.1184537 0.009962439 0.0976116 -0.1183755 0.009958386 0.09593892 -0.1185168 0.009965777 0.09585368 -0.1186022 0.009970247 0.09768331 -0.1189959 0.00999087 0.09575039 -0.1190891 0.009995758 0.0977413 -0.1188312 0.009982228 0.09575808 -0.1189244 0.009987115 0.09774905 -0.1187606 0.009978532 0.09772956 -0.1186701 0.009973824 0.09579282 -0.1194664 0.01001554 0.09588778 -0.1192504 0.01000422 0.09770649 -0.1191596 0.009999454 0.09576988 -0.1197184 0.01002871 0.09609913 -0.1198151 0.01003378 0.09623301 -0.1198596 0.01003617 0.09718388 -0.1196012 0.01002258 0.09598302 -0.119776 0.01003175 0.09732621 -0.1196701 0.01002621 0.09745281 -0.1199517 0.01004093 0.09686785 -0.1199362 0.01004016 0.09653902 -0.1199576 0.01004129 0.09670275 -0.1198883 0.01003766 0.096381 -0.1199187 0.01003921 0.09702968 -0.1201424 0.003041326 0.09732621 -0.119776 0.01003175 0.09732621 -0.1198596 0.01003617 0.09718388 -0.1193178 0.01000773 0.09581607 -0.1198327 0.003025114 0.09588778 -0.1194664 0.01001554 0.09588778 -0.1200364 0.003035783 0.09745281 -0.1196701 0.01002621 0.09745281 -0.1195449 0.01001965 0.09756028 -0.1199112 0.003029227 0.09756028 -0.11977 0.003021836 0.09764564 -0.1194037 0.01001226 0.09764564 -0.1196166 0.003013789 0.09770649 -0.1192504 0.01000422 0.09770649 -0.1190891 0.009995758 0.0977413 -0.1194554 0.003005325 0.0977413 -0.1192907 0.002996742 0.09774905 -0.1189244 0.009987115 0.09774905 -0.1191269 0.002988159 0.09772956 -0.1187606 0.009978532 0.09772956 -0.1186022 0.009970247 0.09768331 -0.1189686 0.002979815 0.09768331 -0.11882 0.002972066 0.0976116 -0.1184537 0.009962439 0.0976116 -0.120226 0.003045737 0.09718388 -0.1199187 0.01003921 0.09702968 -0.120285 0.003048837 0.09702968 -0.1199517 0.01004093 0.09686785 -0.120318 0.003050565 0.09686785 -0.1203239 0.003050863 0.09670275 -0.1199576 0.01004129 0.09670275 -0.1199362 0.01004016 0.09653902 -0.1203026 0.003049731 0.09653902 -0.1198883 0.01003766 0.096381 -0.1202546 0.003047227 0.096381 -0.1201813 0.003043413 0.09623301 -0.1198151 0.01003378 0.09623301 -0.1197184 0.01002871 0.09609913 -0.1200848 0.003038346 0.09609913 -0.1196012 0.01002258 0.09598302 -0.1199675 0.003032207 0.09598302 -0.1188312 0.009982228 0.09575808 -0.1193619 0.003000438 0.09575033 -0.1189959 0.00999087 0.09575039 -0.1191596 0.009999454 0.09576988 -0.1195257 0.003009021 0.09576982 -0.1196841 0.003017306 0.09581607 -0.1188825 0.002975344 0.09585392 -0.1185168 0.009965777 0.09585368 -0.1183755 0.009958386 0.09593892 -0.1191971 0.002991795 0.09575814 -0.1186701 0.009973824 0.09579282 -0.1190358 0.002983391 0.09579294 -0.1181443 0.009946227 0.09617292 -0.1180606 0.009941875 0.09631526 -0.1185102 0.002955794 0.09617346 -0.1182502 0.00995177 0.09604632 -0.1186161 0.002961337 0.0960468 -0.1187413 0.002967953 0.09593927 -0.1179625 0.009936749 0.09679639 -0.1183347 0.002946615 0.09663188 -0.1179684 0.009937047 0.09663128 -0.1183676 0.002948343 0.09647005 -0.1184266 0.002951443 0.09631586 -0.1180015 0.009938776 0.09646946 -0.1183982 0.002949953 0.09711867 -0.1183502 0.002947449 0.09696066 -0.1180317 0.009940326 0.09711825 -0.1183289 0.002946317 0.09679692 -0.1179838 0.009937822 0.09696018 -0.1181049 0.0099442 0.09726625 -0.1184715 0.002953767 0.09726655 -0.1182016 0.009949266 0.09740018 -0.1185681 0.002958834 0.09740036 -0.1186852 0.002964973 0.09751635 -0.1183189 0.009955406 0.09751635 + + + + + + + + + + 0.08255296 -0.9965868 0 -0.08291918 -0.9965563 0 -0.08255296 -0.9965868 0 1 0 0 0.9863626 0.164587 0 -0.2454643 -0.9694057 0 -0.2458016 -0.9693202 0 -0.4020001 -0.9156397 0 -0.401688 -0.9157767 0 -0.5472124 -0.8369939 0 -0.5469574 -0.8371605 0 -0.6772807 -0.7357248 0 -0.6774875 -0.7355343 0 -0.7892915 -0.6140188 0 -0.7891451 -0.6142068 0 -0.8795709 -0.4757679 0 -0.8794736 -0.4759479 0 -0.9458194 -0.3246934 0 -0.9458414 -0.3246294 0 -0.9863569 -0.1646217 0 -0.9863626 -0.164587 0 -1 0 0 0.08221703 -0.9966145 0 0.2454643 -0.9694057 0 0.245163 -0.969482 0 0.401688 -0.9157767 0 0.4014127 -0.9158973 0 0.5467164 -0.8373178 0 0.546936 -0.8371744 0 0.6772807 -0.7357248 0 0.677122 -0.7358708 0 0.7891304 -0.6142258 0 0.7890251 -0.6143611 0 0.8794087 -0.4760679 0 0.8794736 -0.4759479 0 0.9458194 -0.3246934 0 0.945788 -0.3247846 0 0.9863626 -0.164587 0 0.9863569 -0.1646217 0 0.9458194 0.3246934 0 0.6772807 0.7357248 0 0.7891304 0.6142258 0 0.8794736 0.4759479 0 0.7891451 0.6142068 0 0.401688 0.9157767 0 0.2454643 0.9694057 0 0.5469574 0.8371605 0 0.546936 0.8371744 0 -0.2454643 0.9694057 0 -0.08255296 0.9965868 0 0.08255296 0.9965868 0 -0.6772807 0.7357248 0 -0.5469574 0.8371605 0 -0.401688 0.9157767 0 -0.546936 0.8371744 0 -0.8794736 0.4759479 0 -0.7891451 0.6142068 0 -0.7891304 0.6142258 0 -0.9458194 0.3246934 0 -0.9863626 0.164587 0 0 0 1 -8.84119e-5 0 1 5.89326e-5 0 1 -4.41934e-5 0 1 5.89405e-5 0 1 5.89405e-5 0 1 4.41934e-5 0 1 2.94703e-5 0 1 -8.85205e-5 0 1 -1.93369e-5 0 1 -4.41932e-5 0 1 -1.76776e-4 0 1 2.94764e-5 0 1 -8.84132e-5 0 1 -1.76818e-4 0 1 -2.94703e-5 0 1 -1.76826e-4 0 1 -1.47351e-5 0 1 -1.8419e-6 0 1 0 0 -1 0.5469574 -0.8371605 0 -0.546936 -0.8371744 0 -0.7891304 -0.6142258 0 -0.8795709 0.4757679 0 -0.945832 0.3246567 0 -0.945788 0.3247846 0 -0.9863519 0.1646513 0 -0.9863569 0.1646217 0 -0.6771055 0.735886 0 -0.5472124 0.8369939 0 -0.6774875 0.7355343 0 -0.8794087 0.4760679 0 -0.7890251 0.6143611 0 -0.7892915 0.6140188 0 -0.2458016 0.9693202 0 -0.2451558 0.9694838 0 -0.08291918 0.9965563 0 -0.4020001 0.9156397 0 -0.5467164 0.8373178 0 -0.4014127 0.9158973 0 0.08221703 0.9966145 0 0.08291918 0.9965563 0 0.2451558 0.9694838 0 -0.08221703 0.9966145 0 0.2458016 0.9693202 0 0.4014127 0.9158973 0 0.5467164 0.8373178 0 0.4020001 0.9156397 0 0.5472124 0.8369939 0 0.6771055 0.735886 0 0.6774875 0.7355343 0 0.7890251 0.6143611 0 0.8794087 0.4760679 0 0.7892915 0.6140188 0 0.8795709 0.4757679 0 0.945788 0.3247846 0 0.945832 0.3246567 0 0.9863519 0.1646513 0 0.9863569 0.1646217 0 -0.9614952 -0.2748219 0 -0.9936178 -0.1127994 0 -0.998631 0.05230891 0 -0.9986326 0.05227851 0 -0.8201113 -0.572204 0 -0.7146954 -0.6994359 0 -0.7146805 -0.6994512 0 -0.820087 -0.5722389 0 -0.9031143 -0.4294005 0 -0.9031261 -0.4293755 0 -0.2955438 -0.9553292 0 -0.4487877 -0.8936384 0 -0.5897802 -0.8075639 0 0.1947426 -0.9808543 0 0.03064113 -0.9995306 0 -0.1342524 -0.9909472 0 0.5026523 -0.8644888 0 0.6380717 -0.7699771 0 0.3535371 -0.9354205 0 0.9275605 -0.3736732 0 0.8534681 -0.5211451 0 0.9275456 -0.37371 0 0.7560787 -0.6544808 0 0.9936251 0.1127358 0 0.9986294 -0.05233937 0 0.9763907 -0.2160126 0 0.998631 -0.05230891 0 0.9031728 0.4292772 0 0.8202129 0.5720584 0 0.8201987 0.572079 0 0.9615193 0.2747372 0 0.9615113 0.2747654 0 0.449056 0.8935037 0 0.5899921 0.8074091 0 0.7148463 0.6992816 0 0.7148616 0.699266 0 -0.03030574 0.9995407 0 0.1346201 0.9908973 0 0.2958847 0.9552237 0 -0.1944079 0.9809208 0 -0.3532029 0.9355468 0 -0.5023807 0.8646466 0 -0.6378551 0.7701565 0 -0.7559227 0.6546609 0 -0.7559096 0.654676 0 -0.8533619 0.5213192 0 -0.9275244 0.3737626 0 -0.927535 0.3737363 0 -0.9763971 0.2159835 0 -3.93627e-5 0 1 1.96295e-5 0 1 1.08644e-5 0 1 2.17703e-5 0 1 -1.96842e-5 0 1 2.18725e-5 0 1 2.17396e-5 0 1 -3.94753e-5 0 1 -8.21991e-6 0 1 -2.17394e-5 0 1 2.18995e-5 0 1 4.91168e-6 0 1 -1.97331e-5 0 1 1.95112e-5 0 1 -2.18062e-5 0 1 -1.97154e-5 0 1 -1.97241e-5 0 1 -1.22351e-5 0 1 -3.65168e-6 0 1 -1.97644e-5 0 1 -1.97501e-5 0 1 -5.49342e-6 0 1 -2.18726e-5 0 1 1.08997e-5 0 1 -1.97472e-5 0 1 -1.9729e-5 0 1 1.96919e-5 0 1 9.81812e-6 0 1 -1.71167e-5 0 1 3.65311e-6 0 1 4.38391e-5 0 1 1.97404e-5 0 1 -4.35055e-5 0 1 -1.22508e-6 0 1 9.83314e-6 0 1 1.37335e-6 0 1 -0.9619873 -0.2424424 -0.1257075 -0.9855509 -0.1116691 -0.1273559 -0.9536396 -0.2724466 -0.1278457 -0.9905344 0.0518828 -0.1270824 -0.9873346 -0.09622782 -0.1261368 -0.9906226 0.05191314 -0.12638 -0.8133316 -0.5674704 -0.1283324 -0.7087849 -0.6936472 -0.128365 -0.761418 -0.6360766 -0.1250973 -0.8477543 -0.5154033 -0.1251885 -0.9151178 -0.3831989 -0.1253728 -0.8957088 -0.4257737 -0.1281502 -0.540042 -0.8322659 -0.1252519 -0.4449993 -0.8863365 -0.1279972 -0.4099986 -0.903407 -0.1255266 -0.6580865 -0.7424722 -0.1251289 -0.5848723 -0.8009186 -0.1282727 0.03018307 -0.9914332 -0.1270802 0.02209544 -0.9917322 -0.126408 -0.132973 -0.9829386 -0.1270828 -0.2707966 -0.9543651 -0.1259221 -0.2929855 -0.947564 -0.1276013 0.3505172 -0.9277641 -0.1280295 0.4984422 -0.8573805 -0.1282728 0.4505862 -0.8838986 -0.1252815 0.1697777 -0.9774044 -0.1259217 0.1930036 -0.9728617 -0.1276314 0.313707 -0.9411821 -0.125556 0.6911919 -0.7117615 -0.1250969 0.7498631 -0.6490268 -0.1283343 0.7895599 -0.6007687 -0.1251894 0.5773655 -0.8068406 -0.1251294 0.6327791 -0.7636138 -0.1283931 0.9718766 -0.1988615 -0.1261349 0.9314684 -0.3414154 -0.1257075 0.9684832 -0.2140587 -0.1273549 0.919996 -0.3705009 -0.1278136 0.8702775 -0.4763392 -0.1253717 0.8464742 -0.5167778 -0.1281491 0.9855576 0.1116088 -0.1273567 0.9619873 0.2424424 -0.1257075 0.9873346 0.09622782 -0.1261368 0.9906226 -0.05191314 -0.12638 0.9905328 -0.0519132 -0.1270821 0.8477543 0.5154033 -0.1251885 0.8134433 0.5673106 -0.1283308 0.761418 0.6360766 -0.1250973 0.9151178 0.3831989 -0.1253728 0.9536698 0.272355 -0.1278151 0.8957675 0.4256505 -0.1281499 0.4099873 0.9034126 -0.1255231 0.540042 0.8322659 -0.1252519 0.4452798 0.8861954 -0.1279988 0.5850843 0.8007637 -0.1282723 0.6580891 0.7424751 -0.1250988 0.7089359 0.693493 -0.1283647 0.1333073 0.9828974 -0.1270509 -0.02209544 0.9917322 -0.126408 0.1255559 0.9840001 -0.1264105 0.2932899 0.9474698 -0.1276009 0.2707977 0.9543689 -0.1258921 -0.02984774 0.991447 -0.1270514 -0.1697777 0.9774044 -0.1259217 -0.1926697 0.9729317 -0.1276021 -0.3502111 0.9278839 -0.1279987 -0.3137082 0.9411857 -0.125526 -0.4981706 0.8575383 -0.1282736 -0.4505862 0.8838986 -0.1252815 -0.5773655 0.8068406 -0.1251294 -0.632565 0.7637962 -0.1283624 -0.7496923 0.6492246 -0.1283312 -0.6912069 0.7117466 -0.1250996 -0.8463815 0.5169297 -0.128149 -0.7895629 0.600771 -0.1251593 -0.8702775 0.4763392 -0.1253717 -0.9199706 0.3705641 -0.1278144 -0.9684895 0.2140296 -0.1273557 -0.9314684 0.3414154 -0.1257075 -0.9718766 0.1988615 -0.1261349 -0.125586 -0.9839963 -0.12641 0.1264421 0.991974 0 -0.02279764 0.9997401 0 -0.9986294 0.05233937 0 -0.9952675 -0.09717369 0 0.2729632 0.9620246 0 0.4134143 0.9105431 0 0.5446097 0.8386898 0 0.663492 0.7481834 0 0.7674678 0.6410875 0 0.8544024 0.5196119 0 0.8543941 0.5196255 0 0.9223068 0.3864588 0 0.9696215 0.2446103 0 0.9952616 0.09723412 0 -0.1714571 0.9851916 0 -0.3162095 0.9486895 0 -0.316182 0.9486985 0 -0.4540003 0.8910016 0 -0.5818443 0.8133003 0 -0.6966543 0.7174071 0 -0.7958464 0.6054988 0 -0.8772019 0.4801218 0 -0.8772147 0.4800983 0 -0.9388875 0.3442242 0 -0.9796604 0.2006625 0 -0.9796665 0.2006332 0 -0.9696523 -0.2444884 0 -0.9952704 -0.09714347 0 -0.7674528 -0.6411055 0 -0.8544514 -0.5195316 0 -0.7674402 -0.6411205 0 -0.9223548 -0.386344 0 -0.8544378 -0.5195538 0 -0.5444036 -0.8388234 0 -0.4133523 -0.9105713 0 -0.6633309 -0.7483264 0 -0.6633138 -0.7483414 0 0.02246212 -0.9997478 0 -0.1267763 -0.9919314 0 -0.2731125 -0.9619821 0 0.4542193 -0.89089 0 0.3163011 -0.948659 0 0.1713038 -0.9852182 0 0.6966695 -0.7173923 0 0.6966852 -0.717377 0 0.7958056 -0.6055521 0 0.5819684 -0.8132115 0 0.5819482 -0.8132259 0 0.8771492 -0.4802179 0 0.9388642 -0.3442878 0 0.9796665 -0.2006332 0 0.9796724 -0.2006039 0 0.9796485 -0.2007211 0 0.9387412 -0.3446232 0 0.79541 -0.6060718 0 0.696267 -0.717783 0 0.7958204 -0.6055328 0 0.877162 -0.4801945 0 0.8768602 -0.4807456 0 0.4539761 -0.8910139 0 0.3159623 -0.9487718 0 0.5816654 -0.8134281 0 -0.1271743 -0.9918804 0 0.02206486 -0.9997566 0 0.1709084 -0.985287 0 -0.4136259 -0.910447 0 -0.5446451 -0.8386667 0 -0.2735117 -0.9618687 0 -0.7678285 -0.6406556 0 -0.8547721 -0.5190037 0 -0.6636703 -0.7480252 0 -0.969721 -0.2442156 0 -0.922576 -0.3858156 0 -0.9387843 0.3445057 0 -0.9388741 0.3442609 0 -0.9796724 0.2006039 0 -0.6966695 0.7173923 0 -0.7954766 0.6059844 0 -0.6962359 0.7178131 0 -0.7958056 0.6055521 0 -0.8771492 0.4802179 0 -0.8769129 0.4806495 0 -0.3159072 0.9487901 0 -0.3163011 0.948659 0 -0.4537329 0.8911378 0 -0.581472 0.8135665 0 -0.4542193 0.89089 0 -0.5819684 0.8132115 0 -0.02240109 0.9997491 0 0.1268363 0.9919237 0 0.1267763 0.9919314 0 -0.1713038 0.9852182 0 -0.1710616 0.9852604 0 -0.02246212 0.9997478 0 0.2731125 0.9619821 0 0.4133523 0.9105713 0 0.2733262 0.9619215 0 0.4137133 0.9104073 0 0.5444036 0.8388234 0 0.5448296 0.8385468 0 0.6633309 0.7483264 0 0.7674402 0.6411205 0 0.6637669 0.7479395 0 0.7678435 0.6406376 0 0.8544514 0.5195316 0 0.8547503 0.5190395 0 0.9223548 0.386344 0 0.969645 0.244517 0 0.9225451 0.3858893 0 0.9697138 0.2442443 0 0.9952675 0.09717369 0 0.9952737 0.09711027 0 0.2708859 0.9541741 0.1271723 0.1478953 0.9809736 0.125769 0.1255563 0.9838503 0.1275706 -0.9905782 0.05209553 0.1266528 -0.9905836 0.05206525 0.126623 -0.9882805 -0.08588171 0.1261978 0.4102435 0.903134 0.1266865 0.2822151 0.9510226 0.1261376 0.4112455 0.9026954 0.1265629 0.539971 0.8320674 0.1268671 0.6432253 0.7552617 0.1258617 0.5320748 0.8372076 0.1264113 0.6579884 0.7421597 0.1274776 0.7417427 0.6588215 0.1255872 0.8258202 0.5498347 0.125312 0.7611168 0.6358968 0.1278141 0.847326 0.5154027 0.1280571 0.8940186 0.4301934 0.1251577 0.9146724 0.3833134 0.128239 0.9450363 0.3021125 0.1250383 0.9778152 0.1681016 0.1249774 0.9616013 0.2425977 0.1283335 0.9870334 0.09641128 0.1283348 0.9910866 0.04410046 0.1257093 0.9903709 -0.05185168 0.1283627 0.9906226 -0.05191314 0.12638 0.01058995 0.9920381 0.1254925 -0.02252298 0.9915307 0.127905 -0.1699935 0.9770811 0.1281207 -0.1271131 0.9839444 0.125282 -0.2623689 0.9568208 0.1251264 -0.3135526 0.9408714 0.128241 -0.3924716 0.91123 0.1250049 -0.4502415 0.8836367 0.1283308 -0.5770555 0.8065592 0.1283329 -0.5148894 0.8480979 0.124976 -0.6273221 0.7686566 0.1250371 -0.6909233 0.7114627 0.1282415 -0.7277892 0.6742891 0.1251283 -0.7893227 0.6004688 0.1280898 -0.870047 0.4761027 0.1278458 -0.8142971 0.5667608 0.1253093 -0.8849964 0.4483579 0.1255255 -0.9312666 0.3412975 0.1275097 -0.9384948 0.3215499 0.1258305 -0.9718126 0.1987084 0.1268669 -0.9739093 0.1884523 0.1264385 -0.9617661 -0.2423794 0.1275071 -0.9872124 -0.09619724 0.1271135 -0.9668583 -0.2221515 0.125832 -0.7611472 -0.6357746 0.1282414 -0.8474504 -0.5151906 0.128088 -0.7941993 -0.5946347 0.1251284 -0.914828 -0.3830832 0.1278164 -0.926765 -0.3540488 0.1255239 -0.8688475 -0.4789663 0.1252807 -0.5398874 -0.8318967 0.1283339 -0.4849762 -0.8655471 0.1250055 -0.4099055 -0.9030678 0.1282423 -0.7041012 -0.6990046 0.1250358 -0.6003161 -0.7899329 0.1250073 -0.6578449 -0.7421393 0.1283339 -0.2289814 -0.9653356 0.1252791 -0.0930528 -0.9877209 0.1254946 -0.1256453 -0.9837996 0.1278732 -0.3603765 -0.9243803 0.1251001 -0.270801 -0.9540753 0.128091 0.315175 -0.9405809 0.1263813 0.3137994 -0.940971 0.1268992 0.1818621 -0.9752007 0.1261345 0.170053 -0.9771944 0.1271735 0.02240121 -0.9915764 0.1275712 0.04483252 -0.9910461 0.1257691 0.5771166 -0.806651 0.1274784 0.6689248 -0.7326495 0.1255569 0.6908852 -0.7115769 0.1278128 0.4421953 -0.887992 0.1262281 0.5609132 -0.8182515 0.1258614 0.4504004 -0.8837407 0.1270509 0.7892189 -0.6006121 0.1280573 0.7641285 -0.6327758 0.12531 0.8445108 -0.5207085 0.1251568 0.8698899 -0.4762833 0.1282418 0.9084631 -0.398824 0.1250368 0.9310995 -0.3414449 0.1283317 0.9715701 -0.1989529 0.1283321 0.954909 -0.2692996 0.1250058 0.9810454 -0.1474696 0.1257093 -4.4272e-6 0 -1 -1.20992e-5 0 -1 0 -4.24446e-6 -1 -4.37647e-6 -6.99717e-6 -1 9.6173e-6 0 -1 -1.93623e-5 5.6866e-6 -1 -1.94824e-5 -6.52913e-6 -1 7.22188e-6 0 -1 9.65058e-6 0 -1 0 -2.32162e-6 -1 1.27703e-6 -1.1172e-5 -1 0 -1.2586e-6 -1 0 -1.79402e-6 -1 -1.33707e-5 -7.40819e-6 -1 -3.44457e-6 -9.02461e-6 -1 -1.76881e-5 0 -1 3.6742e-5 0 -1 1.94433e-5 0 -1 1.9377e-5 0 -1 -1.4416e-5 0 -1 9.60045e-6 0 -1 1.77113e-5 0 -1 -8.82151e-6 0 -1 -1.94254e-5 0 -1 -1.77025e-5 -2.78951e-6 -1 -8.78856e-6 -6.02564e-6 -1 -8.74995e-6 -6.56019e-6 -1 0 -6.97932e-6 -1 1.92513e-5 0 -1 8.8494e-6 0 -1 -8.85572e-6 0 -1 -1.75495e-5 0 -1 1.33601e-5 0 -1 9.65841e-6 0 -1 -9.6152e-6 0 -1 -8.86825e-6 0 -1 8.85114e-6 0 -1 1.3256e-5 0 -1 2.20513e-6 0 -1 -1.10297e-5 0 -1 -4.39551e-6 0 -1 1.92668e-5 0 -1 -1.91957e-5 0 -1 -9.09938e-6 0 -1 -0.9962421 -0.08661383 0 -0.9962341 -0.08670467 0 -0.9746785 -0.2236111 0 -0.9343683 -0.3563088 0 -0.9745807 -0.2240369 0 -0.8759465 -0.4824084 0 -0.9341236 -0.3569495 0 -0.8757019 -0.4828522 0 -0.8005453 -0.5992722 0 -0.7097722 -0.7044315 0 -0.8004539 -0.5993943 0 -0.6054454 -0.7958869 0 -0.7096658 -0.7045385 0 -0.6050662 -0.7961752 0 -0.4894061 -0.872056 0 -0.363817 -0.9314705 0 -0.4888348 -0.8723765 0 -0.2311515 -0.9729177 0 -0.3632679 -0.9316847 0 -0.2308778 -0.9729829 0 -0.09393626 -0.9955783 0 0.04480129 -0.998996 0 -0.09390604 -0.9955812 0 0.182593 -0.9831886 0 0.04507678 -0.9989836 0 0.1832049 -0.9830747 0 0.3170334 -0.9484145 0 0.4454548 -0.8953045 0 0.317674 -0.9482 0 0.5653664 -0.8248399 0 0.4458825 -0.8950915 0 0.5654923 -0.8247537 0 0.6742238 -0.7385272 0 0.7699496 -0.6381047 0 0.6743511 -0.7384108 0 0.8508799 -0.5253604 0 0.7702387 -0.6377558 0 0.8512263 -0.5247988 0 0.9154801 -0.4023632 0 0.9624399 -0.2714949 0 0.9156671 -0.4019376 0 0.978986 -0.2039274 0 0.9624639 -0.2714102 0 -0.9817289 0.1902847 0 -0.9459666 0.3242642 0 -0.9817165 0.1903493 0 -0.8920094 0.4520169 0 -0.9458287 0.3246661 0 -0.8917008 0.4526255 0 -0.8207117 0.5713426 0 -0.7335268 0.6796606 0 -0.8204502 0.571718 0 -0.6322618 0.7747549 0 -0.7334237 0.6797719 0 -0.6321436 0.7748513 0 -0.5189455 0.8548073 0 -0.3955946 0.9184253 0 -0.5185472 0.855049 0 -0.2644755 0.9643925 0 -0.3949798 0.9186899 0 -0.2638972 0.9645509 0 -0.1281805 0.9917509 0 0.01058995 0.999944 0 -0.1279065 0.9917863 0 0.1489627 0.9888429 0 0.01065099 0.9999434 0 0.1492701 0.9887965 0 0.284373 0.9587137 0 0.4144214 0.9100852 0 0.2849559 0.9585407 0 0.5366188 0.8438249 0 0.4150557 0.909796 0 0.5370118 0.8435748 0 0.6484711 0.7612394 0 0.7477242 0.6640096 0 0.648602 0.7611277 0 0.832421 0.5541437 0 0.7478386 0.6638807 0 0.8326883 0.5537421 0 0.9011294 0.4335504 0 0.9525173 0.3044845 0 0.9014192 0.4329473 0 0.9855456 0.1694102 0 0.9526525 0.3040614 0 0.9855559 0.1693509 0 0.9949403 0.1004676 0 0.9949374 0.1004978 0 1.3256e-6 0 1 -6.64254e-7 0 1 -0.9850159 0.05160838 -0.164561 -0.78799 0.0412932 -0.6143019 -0.8782719 0.04602241 -0.4759417 -0.8782534 0.04599255 -0.4759787 -0.9445434 0.04950237 -0.3246343 -0.9850109 0.05160814 -0.1645907 -0.9445354 0.04947143 -0.3246621 -0.5462338 0.02862703 -0.8371435 -0.401025 0.02099734 -0.9158264 -0.5462911 0.02859634 -0.8371072 -0.7880024 0.04126179 -0.6142879 -0.6764383 0.03543335 -0.7356465 -0.08252435 0.004303216 -0.9965798 -0.08243095 0.004303097 -0.9965875 0.08249157 -0.004303097 -0.9965825 -0.2451 0.01281803 -0.9694132 0.5461984 -0.02862679 -0.8371666 0.4010875 -0.0209974 -0.9157992 0.4011499 -0.02099746 -0.9157718 0.2451574 -0.01281785 -0.9693986 0.2451 -0.01281803 -0.9694132 0.08252435 -0.004303216 -0.9965798 0.7881217 -0.04129213 -0.614133 0.8782082 -0.04599177 -0.4760623 0.5462697 -0.02859681 -0.8371211 0.6764549 -0.03543257 -0.7356314 0.9850011 -0.0516076 -0.16465 0.944526 -0.04947096 -0.3246894 0.8782197 -0.04602289 -0.476038 0.9445449 -0.04947191 -0.3246348 0.8782406 -0.04599183 0.4760023 0.944482 -0.04947179 0.3248173 0.9445041 -0.04947137 0.3247534 0.9850011 -0.0516076 0.16465 0.6764549 -0.03543257 0.7356314 0.5462343 -0.02859658 0.8371442 0.67647 -0.03543341 0.7356173 0.7882154 -0.04129225 0.6140127 0.2451287 -0.01281797 0.9694059 0.08249157 -0.004303097 0.9965825 0.4011131 -0.02099716 0.9157879 0.5462557 -0.0285961 0.8371303 0.4011387 -0.02099686 0.9157767 -0.08252435 0.004303216 0.9965798 -0.2451 0.01281803 0.9694132 0.08252435 -0.004303216 0.9965798 -0.401025 0.02099734 0.9158264 -0.5462697 0.02859681 0.8371211 -0.5462906 0.02862679 0.8371064 -0.6764231 0.03543251 0.7356606 -0.6764383 0.03543335 0.7356465 -0.7880953 0.04129236 0.6141669 -0.8782847 0.04602307 0.4759181 -0.788069 0.04129254 0.6142006 -0.8782731 0.04599195 0.4759423 -0.9445041 0.04947137 0.3247534 -0.9850159 0.05160838 0.164561 -0.9850109 0.05160814 0.1645907 0.9986301 -0.05232596 -2.22127e-7 0.9986293 -0.0523402 0 -0.05233108 -0.9986298 1.31482e-7 -0.0523318 -0.9986298 0 -0.05233091 -0.9986298 1.32923e-7 -0.05233097 -0.9986298 0 -0.05232971 -0.9986299 4.73324e-7 -0.05233061 -0.9986299 3.82152e-7 -0.99863 0.05232894 0 0.05233103 0.9986298 -1.32923e-7 0.05233091 0.9986299 0 0.05232971 0.9986299 -9.46648e-7 0.05233091 0.9986298 0 0.05233103 0.9986298 0 0.05233067 0.9986299 0 0.9518777 0.3064784 0 0.9518688 0.3065061 0 0.9853453 0.1705722 0 0.9948755 0.1011081 0 0.8298984 0.5579146 0 0.7436765 0.6685397 0 0.7436916 0.6685228 0 0.8997579 0.4363896 0 0.4056259 0.9140393 0 0.5293542 0.848401 0 0.6427984 0.7660355 0 0.6428163 0.7660204 0 -0.002990841 0.9999956 0 0.136848 0.9905921 0 -0.003021359 0.9999955 0 0.2739673 0.9617391 0 -0.2799813 0.9600055 0 -0.4114608 0.9114275 0 -0.142891 0.9897384 0 -0.5347312 0.8450223 0 -0.6475635 0.7620117 0 -0.6475483 0.7620244 0 -0.7477242 0.6640096 0 -0.8332597 0.5528818 0 -0.9024274 0.430842 0 -0.9024156 0.4308669 0 -0.9304151 0.3665077 0 -0.93044 0.3664445 0 0.05234241 0.9986292 4.61167e-6 0.05233061 0.9986299 -2.99366e-6 0.05233091 0.9986298 -1.58173e-7 0.05234372 0.9986292 1.6572e-6 0.05233156 0.9986298 0 0.05233252 0.9986298 1.3688e-6 0.05232954 0.99863 -3.47751e-6 0.05233305 0.9986298 1.28496e-6 0.05233162 0.9986298 1.35269e-6 0.05233454 0.9986296 9.42322e-7 0.05232632 0.9986301 3.50524e-6 0.05233156 0.9986298 0 0.05233776 0.9986295 0 0.05233114 0.9986299 -1.61125e-7 0.05232787 0.9986301 0 0.05232971 0.9986299 -2.41495e-6 0.05232745 0.99863 -3.49269e-6 0.05233448 0.9986297 1.22093e-6 0.0523321 0.9986298 3.72312e-6 0.05233287 0.9986298 3.32619e-7 0.05232518 0.9986301 -3.73739e-6 0.05233097 0.9986299 0 0.05233621 0.9986296 0 0.05233043 0.9986299 3.55192e-6 0.05233395 0.9986297 -6.53638e-6 0.05232852 0.99863 -3.72445e-6 0.0523293 0.9986299 -2.53286e-7 0.05233395 0.9986296 3.38364e-6 0.05233097 0.9986298 -1.6631e-6 0.0523321 0.9986298 -1.52523e-6 0.05233103 0.9986298 -2.41686e-7 0.05233317 0.9986297 0 0.05233401 0.9986297 0 0.0523287 0.9986299 6.25935e-7 0.0523349 0.9986296 0 0.05232918 0.9986299 1.7106e-6 0.05232852 0.9986299 3.47906e-6 0.05233168 0.9986298 -9.42322e-7 0.05232739 0.99863 0 0.05233371 0.9986297 -1.28438e-6 0.05233603 0.9986296 4.9355e-6 -0.9986307 0.052316 0 -0.9986296 0.05233615 0 -0.05232775 -0.99863 0 -0.05232387 -0.9986302 5.55925e-6 -0.05233114 -0.9986298 0 -0.05232906 -0.9986299 2.88672e-6 -0.05233699 -0.9986295 3.73649e-6 -0.05233019 -0.9986299 2.12645e-6 -0.05232685 -0.9986301 3.35021e-6 -0.05233287 -0.9986298 -2.50071e-6 -0.05233633 -0.9986296 -5.93116e-6 -0.05232775 -0.9986301 1.62753e-6 -0.05233764 -0.9986295 0 -0.0523312 -0.9986299 1.48113e-7 -0.05232542 -0.9986301 0 -0.05233424 -0.9986296 0 -0.05232512 -0.9986301 3.71835e-6 -0.05232739 -0.99863 -3.22989e-6 -0.05232995 -0.9986299 -4.27694e-6 -0.05233639 -0.9986295 3.2794e-6 -0.05232661 -0.9986301 2.21961e-6 -0.05232906 -0.99863 0 -0.05233526 -0.9986296 -3.94329e-6 -0.05233067 -0.9986299 9.38819e-7 -0.05233097 -0.9986298 0 -0.05233132 -0.9986298 0 -0.05232703 -0.9986301 4.63021e-6 -0.05233162 -0.9986298 0 -0.05233073 -0.9986299 6.66471e-7 -0.05232822 -0.9986301 -6.05603e-7 -0.05232864 -0.99863 -2.21961e-6 -0.0523287 -0.9986299 4.21413e-6 -0.05232852 -0.99863 -4.6329e-6 -0.05233091 -0.9986298 1.48113e-7 -0.05233156 -0.9986298 -3.63212e-6 -0.05233138 -0.9986298 2.37869e-6 -0.0523349 -0.9986296 0 -0.05232864 -0.9986299 -2.24516e-6 -0.05233538 -0.9986296 3.4779e-6 -0.05233031 -0.9986299 8.37552e-7 -0.05233156 -0.9986298 0 -0.05233263 -0.9986298 -2.97875e-6 0.04968494 -0.9987651 0 -0.1022379 -0.99476 0 -0.978654 0.2055152 0 -0.9985972 0.05294966 0 0.20051 -0.9796916 0 0.3466712 -0.9379869 0 0.4848005 -0.8746248 0 0.4848239 -0.8746119 0 0.6117176 -0.7910763 0 0.6117324 -0.7910649 0 0.7244971 -0.6892779 0 0.8205375 -0.5715929 0 0.8975666 -0.4408788 0 0.9539583 -0.2999393 0 0.9739869 -0.2266044 0 -0.2517237 -0.9677992 0 -0.3952817 -0.91856 0 -0.5298069 -0.8481184 0 -0.6521376 -0.7581008 0 -0.7594397 -0.6505777 0 -0.7594549 -0.6505602 0 -0.8492562 -0.5279812 0 -0.9194605 -0.3931825 0 -0.9684315 -0.2492798 0 -0.9194495 -0.3932083 0 -0.9684242 -0.2493085 0 -0.995026 -0.09961551 0 -0.7836125 0.62125 0 -0.8699005 0.4932274 0 -0.9354004 0.3535905 0 -0.5574017 0.8302429 0 -0.4229038 0.9061746 0 -0.5574369 0.8302193 0 -0.6786147 0.7344946 0 -0.6786299 0.7344805 0 -0.1269903 0.991904 0 0.02731466 0.9996269 0 -0.2782745 0.9605017 0 0.4713057 0.88197 0 0.3299739 0.9439902 0 0.3300011 0.9439806 0 0.1808564 0.9835096 0 0.7172868 0.6967781 0 0.8160305 0.5780089 0 0.6014494 0.798911 0 0.6014688 0.7988964 0 0.8953166 0.4454304 0 0.8160161 0.5780292 0 0.9532552 0.3021668 0 0.9532436 0.3022032 0 0.9884204 0.1517407 0 0.9971869 0.07495534 0 0.9971893 0.074925 0 -1.52862e-6 0 -1 1.52861e-6 0 -1 -1.7529e-5 0 -1 5.0362e-6 0 -1 -5.83686e-6 0 -1 9.87603e-6 0 -1 -3.06064e-6 0 -1 8.5874e-6 0 -1 8.6296e-6 0 -1 9.62422e-6 0 -1 1.78528e-5 0 -1 -9.43835e-6 0 -1 7.98234e-6 0 -1 8.20928e-6 0 -1 -5.29936e-6 0 -1 5.38235e-6 0 -1 1.89234e-5 0 -1 -1.20335e-5 0 -1 1.95281e-6 0 -1 -8.77483e-6 0 -1 9.31496e-6 0 -1 -4.9473e-6 0 -1 -2.10983e-6 0 -1 -2.13156e-6 0 -1 -1.03446e-5 0 -1 -4.45655e-6 0 -1 8.87452e-6 0 -1 4.71239e-6 0 -1 1.894e-5 0 -1 -9.51332e-6 0 -1 -4.3219e-6 0 -1 -8.27964e-6 0 -1 -7.1339e-6 0 -1 4.33333e-6 0 -1 8.55887e-6 0 -1 -9.73723e-6 0 -1 8.85548e-6 0 -1 -3.09224e-6 0 -1 -9.05399e-6 0 -1 -4.53159e-6 0 -1 -0.1916301 -0.9814673 0 -0.05700981 -0.9983736 0 -0.3226478 -0.9465191 0 -0.4476286 -0.8942196 0 -0.5642768 -0.8255857 0 -0.6707215 -0.7417093 0 -0.7649342 -0.6441085 0 -0.8450673 -0.53466 0 -0.7649619 -0.6440756 0 -0.9095296 -0.4156393 0 -0.8450811 -0.5346382 0 -0.9095411 -0.4156141 0 -0.9573158 -0.2890442 0 -0.9746984 -0.2235242 0 0.07852607 -0.9969121 0 0.2124461 -0.9771729 0 0.3425198 -0.9395107 0 0.4664583 -0.8845433 0 0.5819135 -0.8132507 0 0.6865985 -0.7270369 0 0.7785142 -0.6276272 0 0.8561679 -0.5166978 0 0.9181762 -0.3961724 0 0.9633451 -0.2682656 0 0.9793277 -0.2022807 0 -4.3855e-7 0 1 -4.86865e-6 0 1 -8.66669e-6 0 1 -4.47204e-6 0 1 4.75044e-6 0 1 1.80638e-5 0 1 -1.86298e-5 0 1 1.31451e-5 0 1 -1.28159e-5 0 1 -9.72251e-6 0 1 1.00724e-5 0 1 -9.96855e-6 0 1 5.30621e-7 0 1 -6.12124e-7 0 1 -8.58739e-6 0 1 4.36463e-6 0 1 4.38596e-6 0 1 -7.6689e-6 0 1 1.31275e-5 0 1 -4.72334e-6 0 1 -9.7661e-6 0 1 2.48201e-6 0 1 -2.52962e-6 0 1 1.79809e-5 0 1 -8.64375e-6 0 1 -1.86055e-5 0 1 2.26877e-6 0 1 2.96732e-6 0 1 -1.88503e-5 0 1 2.10458e-6 0 1 -2.13155e-6 0 1 -8.91309e-6 0 1 -0.9986296 0.05233615 0 -0.9986307 0.05231606 0 0.05232661 0.9986301 3.56206e-6 0.05232816 0.99863 -8.55243e-7 0.05233091 0.9986298 0 0.05233466 0.9986297 -4.19113e-6 0.05232769 0.99863 -1.50351e-6 0.05232274 0.9986303 3.47868e-6 0.05233234 0.9986298 1.63639e-6 0.05233347 0.9986298 -2.70675e-6 0.05233317 0.9986297 -2.09418e-7 0.0523284 0.9986301 6.25988e-7 0.05233871 0.9986295 0 0.05233079 0.9986298 0 0.05233448 0.9986296 -4.63014e-6 0.05233585 0.9986296 0 0.05233764 0.9986295 1.24032e-6 0.05232697 0.9986301 0 0.05232775 0.99863 3.13265e-6 0.05233144 0.9986298 -2.97324e-6 0.05233436 0.9986297 3.03129e-7 0.05233186 0.9986298 -1.44123e-6 0.05233615 0.9986296 0 0.05233097 0.9986298 0 0.05233603 0.9986296 -2.50706e-6 0.05233371 0.9986297 0 0.05232357 0.9986302 6.8459e-7 0.05233025 0.9986299 -3.3391e-6 0.05233585 0.9986296 7.79411e-7 0.05232799 0.9986301 1.81993e-6 0.05233192 0.9986298 -2.02203e-7 0.05232453 0.9986302 -2.48037e-7 0.05232864 0.9986299 3.57143e-6 0.05232542 0.9986301 0 0.05233114 0.9986299 -1.48383e-7 0.05233007 0.9986299 -2.1284e-6 0.05233269 0.9986297 3.32948e-6 0.05232959 0.9986299 -1.49689e-6 0.05233436 0.9986297 0 0.05232697 0.9986301 0 0.05232739 0.99863 -4.1872e-6 0.05233389 0.9986297 1.16762e-6 0.05232775 0.99863 0 -0.05232775 -0.99863 -2.46736e-6 -0.05232936 -0.99863 0 -0.05233091 -0.9986298 1.58173e-7 -0.05233395 -0.9986296 0 -0.05233329 -0.9986298 0 -0.05233174 -0.9986298 4.57996e-7 -0.05233246 -0.9986297 1.67528e-6 -0.05233287 -0.9986298 -9.24116e-7 -0.05233293 -0.9986298 -2.02901e-6 -0.05233037 -0.9986299 -1.62749e-6 -0.05232793 -0.99863 3.63212e-6 -0.05233627 -0.9986295 -2.31679e-6 -0.05233091 -0.9986299 1.62129e-7 -0.0523352 -0.9986296 -1.87206e-6 -0.05232554 -0.9986301 4.5833e-6 -0.05232924 -0.9986299 0 -0.05233013 -0.9986299 -2.22999e-7 -0.05232995 -0.9986299 -1.87791e-6 -0.05232983 -0.9986299 8.93242e-7 -0.05232656 -0.9986301 1.37497e-6 -0.05233168 -0.9986298 0 -0.05233091 -0.9986299 1.37896e-7 -0.05233901 -0.9986293 2.33657e-6 -0.0523321 -0.9986298 -2.35804e-6 -0.05233311 -0.9986298 -1.78429e-6 -0.05233114 -0.9986299 1.87769e-6 -0.05232816 -0.9986301 -1.59992e-6 -0.0523259 -0.9986301 2.5256e-6 -0.05232816 -0.9986301 -1.00517e-6 -0.05232858 -0.99863 1.78249e-6 -0.05233252 -0.9986298 0 -0.05233108 -0.9986299 0 -0.05233317 -0.9986297 0 -0.05233049 -0.9986299 1.81691e-6 -0.05232882 -0.99863 3.50348e-6 -0.05232506 -0.9986302 1.66545e-6 -0.05233693 -0.9986295 -4.48852e-6 -0.05233067 -0.9986299 1.73856e-6 -0.05233359 -0.9986297 5.7536e-7 -0.05233144 -0.9986298 0 -0.0523312 -0.9986298 -2.62736e-7 -0.7879751 0.04129242 -0.6143209 -0.8782406 0.04599183 -0.4760023 -0.944556 0.04950141 -0.3245976 -0.9445449 0.04947191 -0.3246348 -0.4010507 0.02099704 -0.9158153 -0.5462906 0.02862679 -0.8371064 -0.7879604 0.04129165 -0.61434 -0.08249157 0.004303097 -0.9965825 -0.2451287 0.01281797 -0.9694059 0.5462343 -0.02859658 -0.8371442 0.2451287 -0.01281797 -0.9694059 0.08249408 -0.004303216 -0.9965823 0.7881226 -0.04126167 -0.6141338 0.8782336 -0.04599308 -0.476015 0.6764231 -0.03543251 -0.7356606 0.9445341 -0.04950189 -0.3246616 0.878221 -0.04599243 -0.4760387 0.9445354 -0.04947143 -0.3246621 0.8784816 -0.0461443 0.4755428 0.9445405 -0.04956322 0.3246333 0.9445532 -0.04956233 0.3245967 0.9850109 -0.05160814 0.1645907 0.9849803 -0.05160814 0.1647737 0.6762493 -0.03537195 0.7358232 0.5464176 -0.02865761 0.8370224 0.6766445 -0.03546345 0.7354553 0.8781222 -0.04602259 0.4762179 0.7879244 -0.04123193 0.61439 0.7883483 -0.04135382 0.613838 0.2454012 -0.01287889 0.969336 0.2447916 -0.01275682 0.9694919 0.08286029 -0.004364252 0.9965516 0.4014503 -0.02105826 0.9156387 0.5459015 -0.02856618 0.8373623 0.4007502 -0.02093631 0.9159482 -0.08218848 0.004242181 0.9966078 -0.08285778 0.004364132 0.9965519 -0.2447342 0.01275706 0.9695063 0.08218848 -0.004242181 0.9966078 -0.2453724 0.01287895 0.9693433 -0.4007134 0.02093595 0.9159643 -0.5459229 0.0285657 0.8373484 -0.4014132 0.02108842 0.9156543 -0.5464386 0.02868759 0.8370078 -0.6762169 0.03540241 0.7358517 -0.6766437 0.03549396 0.7354546 -0.787935 0.04126143 0.6143745 -0.8781558 0.04599219 0.4761586 -0.7882555 0.04132324 0.6139591 -0.8784121 0.0460844 0.4756768 -0.9445434 0.04950237 0.3246343 -0.9850126 0.05157768 0.1645909 0.0766828 -0.004018843 -0.9970476 0.07668787 -0.004018843 -0.9970471 0.9006255 -0.04719305 -0.4320262 0.9006251 -0.04720336 -0.4320258 0.8239435 -0.04318052 0.5650246 0.8239435 -0.04318052 0.5650245 -0.0766828 0.004018843 0.9970476 -0.07668781 0.004018247 0.9970471 -0.9006264 0.04719281 0.4320243 -0.9006246 0.04719352 0.4320281 -0.823945 0.04318028 -0.5650224 -0.8239424 0.04317063 -0.5650269 -0.05233174 -0.9986298 -5.83019e-6 -0.05232805 -0.9986301 0 -0.05233943 -0.9986293 -3.66292e-7 -0.05232143 -0.9986304 2.92888e-6 -0.05233061 -0.9986299 -4.19954e-7 -0.05232727 -0.99863 2.95635e-6 -0.0523197 -0.9986304 0 -0.05233657 -0.9986295 8.34621e-7 -0.05233037 -0.9986299 -3.66157e-7 -0.05233454 -0.9986296 -1.67382e-6 -0.05232697 -0.9986301 3.05863e-6 -0.0523321 -0.9986298 0 -0.05233144 -0.9986298 0 -0.05233055 -0.9986299 5.54111e-7 -0.05233502 -0.9986296 2.15136e-6 -0.05232971 -0.9986299 6.25572e-6 -0.05233085 -0.9986298 0 -0.0523315 -0.9986298 0 -0.05232858 -0.9986299 -7.3351e-6 -0.05232858 -0.9986299 0 -0.05233174 -0.9986298 4.02803e-7 -0.05233132 -0.9986298 -3.64257e-7 -0.05233776 -0.9986295 2.61885e-6 -0.05232632 -0.9986301 0 -0.0523315 -0.9986298 -4.19959e-7 -0.05233776 -0.9986295 0 -0.05233103 -0.9986299 -4.17373e-7 -0.05232983 -0.9986299 -3.65997e-7 -0.0523321 -0.9986298 -1.25552e-6 -0.05233764 -0.9986295 0 -0.05233258 -0.9986298 6.96375e-6 -0.05233049 -0.9986299 4.19981e-7 -0.05233603 -0.9986295 0 -0.05232977 -0.9986299 -6.25716e-6 -0.05232864 -0.99863 -1.00931e-6 -0.05233144 -0.9986298 5.99994e-6 -0.05233043 -0.9986299 -4.1908e-7 -0.05233544 -0.9986296 7.33812e-6 -0.05233061 -0.9986299 0 -0.05233919 -0.9986295 0 -0.05233526 -0.9986296 0 -0.05232715 -0.9986301 5.46532e-6 -0.05234372 -0.9986292 0 -0.05232024 -0.9986304 -2.35043e-6 0.05233114 0.9986298 2.9286e-6 0.05233114 0.9986298 0 0.05233234 0.9986298 0 0.05232793 0.9986301 2.95502e-6 0.05233734 0.9986295 0 0.0523234 0.9986302 5.12584e-6 0.0523386 0.9986295 6.10648e-6 0.0523321 0.9986298 -2.50381e-6 0.05232864 0.9986299 -2.92711e-6 0.05232965 0.9986299 1.25541e-6 0.05233353 0.9986297 -3.05803e-6 0.05233448 0.9986296 0 0.05233073 0.9986298 0 0.05233389 0.9986296 1.84653e-7 0.05232286 0.9986303 0 0.05232673 0.9986301 -2.01902e-7 0.05233049 0.9986299 0 0.05233061 0.9986299 0 0.05233377 0.9986297 0 0.05233162 0.9986298 -2.99723e-6 0.0523315 0.9986298 1.20853e-6 0.05232495 0.9986302 0 0.05233317 0.9986297 2.61862e-6 0.05232578 0.9986301 6.27596e-6 0.05233585 0.9986296 -6.6789e-6 0.0523312 0.9986299 -4.19957e-7 0.0523346 0.9986297 -2.19618e-6 0.05232989 0.9986299 0 0.05232858 0.99863 1.25544e-6 0.05233258 0.9986297 -3.05833e-6 0.05233258 0.9986298 0 0.05233055 0.9986299 0 0.05233603 0.9986295 0 0.05233043 0.9986299 -1.58386e-5 0.05232799 0.9986301 -9.08371e-6 0.05233269 0.9986298 0 0.05233007 0.9986299 0 0.05233544 0.9986296 1.46762e-5 0.05233263 0.9986298 0 0.05233383 0.9986297 0 0.05233824 0.9986294 0 0.05232983 0.9986299 7.28701e-7 0.05232858 0.9986299 6.9846e-6 0.0523312 0.9986298 -4.70185e-6 0.1174075 -0.006134331 0.9930649 -0.04736489 0.002471983 0.9988746 -0.04739534 0.002471983 0.9988732 0.5752875 -0.03012245 0.8173965 0.4330663 -0.02267569 0.9010769 0.2790101 -0.01461887 0.960177 0.2790383 -0.01461875 0.9601687 0.8091571 -0.04239124 0.5860613 0.8944562 -0.04684692 0.444695 0.7017908 -0.03674519 0.7114349 0.70179 -0.03677564 0.7114341 0.9901864 -0.05188214 0.1297664 0.9901825 -0.0518819 0.1297965 0.9980124 -0.05227959 -0.03518873 0.9553472 -0.05005168 0.2912156 0.8610075 -0.04510736 -0.5065881 0.9325404 -0.04886096 -0.3577445 0.932516 -0.04886132 -0.3578078 0.9786174 -0.05127161 -0.1991965 0.9786233 -0.05127197 -0.1991672 0.9980135 -0.05227965 -0.03515827 0.6500669 -0.03405982 -0.7591133 0.5164155 -0.02704 -0.8559112 0.6500845 -0.03405916 -0.7590982 0.7659639 -0.04013234 -0.6416298 0.7660065 -0.04013299 -0.6415789 0.2109771 -0.01104784 -0.9774286 0.210825 -0.01104784 -0.9774613 0.0474258 -0.002471983 -0.9988718 0.3687574 -0.01931828 -0.9293249 0.5164379 -0.02703958 -0.8558977 0.3686415 -0.01931864 -0.9293709 -0.4328817 0.02267563 -0.9011656 -0.2789738 0.01461857 -0.9601874 -0.2791872 0.01461851 -0.9601255 -0.1174977 0.006134271 -0.9930543 -0.1174376 0.006134331 -0.9930614 0.04736489 -0.002471983 -0.9988746 -0.7019599 0.03674447 -0.7112681 -0.8089625 0.04242116 -0.5863277 -0.7015749 0.03677558 -0.7116462 -0.4332141 0.02267545 -0.9010059 -0.5754122 0.03012257 -0.8173087 -0.5750722 0.03015291 -0.8175469 -0.9552358 0.05008119 -0.2915758 -0.9554527 0.05002033 -0.2908749 -0.9901381 0.0518828 -0.1301343 -0.8942908 0.04687678 -0.4450244 -0.8093371 0.04236054 -0.585815 -0.8945776 0.04684686 -0.4444505 -0.9980226 0.05230903 0.03485232 -0.9980021 0.05224853 0.03552412 -0.9786839 0.05130243 0.1988619 -0.9902315 0.0518524 -0.1294326 -0.9785509 0.05124086 0.1995311 -0.9326439 0.04886162 0.3574743 -0.861131 0.04513794 0.5063753 -0.9324153 0.04879981 0.358079 -0.8608505 0.04504609 0.5068602 -0.7661445 0.04013222 0.6414141 -0.7658126 0.04007136 0.6418141 -0.6502655 0.03405904 0.7589432 -0.5165315 0.02707022 0.8558402 -0.6498872 0.03399896 0.7592699 -0.5162859 0.02700906 0.8559903 -0.3687943 0.01931864 0.9293103 -0.3686681 0.01928788 0.929361 -0.2109479 0.01104789 0.9774349 0.9863675 0.1645573 0 -0.8795581 -0.4757915 0 -0.9458287 -0.3246661 0 -0.9863519 -0.1646513 0 0.245493 -0.9693984 0 0.2451558 -0.9694838 0 0.6771055 -0.735886 0 0.7890366 -0.6143463 0 0.8794214 -0.4760442 0 0.8794608 -0.4759715 0 0.9458287 0.3246661 0 0.245493 0.9693984 0 -0.245493 0.9693984 0 -8.83838e-5 0 1 -1.47311e-5 0 1 1.17847e-4 0 1 8.84285e-5 0 1 5.89379e-5 0 1 -1.1788e-4 0 1 -4.42058e-5 0 1 -4.42051e-5 0 1 2.20968e-5 0 1 -3.31662e-5 0 1 4.42599e-5 0 1 5.8924e-5 0 1 5.89657e-5 0 1 -4.41894e-5 0 1 -4.41984e-5 0 1 -4.42027e-5 0 1 2.21032e-5 0 1 6.63134e-5 0 1 2.76109e-5 0 1 -3.31612e-5 0 1 2.21087e-5 0 1 -8.84458e-5 0 1 2.94623e-5 0 1 2.94699e-5 0 1 4.4205e-5 0 1 4.42058e-5 0 1 4.42055e-5 0 1 -2.21024e-5 0 1 2.21025e-5 0 1 4.42057e-5 0 1 -4.42055e-5 0 1 -4.4205e-5 0 1 -2.21026e-5 0 1 4.6049e-7 0 -1 -6.90698e-7 0 -1 1.38156e-6 0 -1 1.84216e-6 0 -1 1.38139e-6 0 -1 -4.60433e-7 0 -1 9.20842e-7 0 -1 4.60386e-7 0 -1 -9.20662e-7 0 -1 -6.90709e-7 0 -1 9.20948e-7 0 -1 -1.8419e-6 0 -1 4.60478e-7 0 -1 -4.60477e-7 0 -1 -6.90717e-7 0 -1 9.20645e-7 0 -1 -6.90642e-7 0 -1 -3.45319e-7 0 -1 1.03594e-6 0 -1 -3.45302e-7 0 -1 -1.03589e-6 0 -1 -1.0359e-6 0 -1 -1.03589e-6 0 -1 4.60468e-7 0 -1 9.20941e-7 0 -1 9.20943e-7 0 -1 -3.45358e-7 0 -1 3.45355e-7 0 -1 3.45351e-7 0 -1 1.03605e-6 0 -1 -3.45357e-7 0 -1 -3.45355e-7 0 -1 -3.45351e-7 0 -1 1.72677e-7 0 -1 0.7891451 -0.6142068 0 -0.9863675 -0.1645573 0 -0.94581 -0.3247207 0 -0.8795581 0.4757915 0 -0.9458414 0.3246294 0 -0.677122 0.7358708 0 -0.8793959 0.4760915 0 -0.2458302 0.9693129 0 -0.245163 0.969482 0 -0.4013871 0.9159086 0 0.245163 0.969482 0 0.677122 0.7358708 0 0.7890366 0.6143463 0 0.8795581 0.4757915 0 0.9458414 0.3246294 0 0.9615298 0.274701 0 0.9936284 0.1127056 0 0.9995399 0.0303362 0 0.999538 0.03039723 0 0.7148314 0.6992969 0 0.9031847 0.4292523 0 0.2958568 0.9552323 0 0.5900067 0.8073984 0 0.5900266 0.8073839 0 -0.5024035 0.8646333 0 -0.637822 0.7701839 0 -0.3531929 0.9355506 0 -0.8533754 0.521297 0 -0.7558946 0.6546935 0 -0.9275456 0.37371 0 -0.8533535 0.5213328 0 -0.9764035 0.2159544 0 -0.9908891 0.1346801 0 1.84547e-5 0 -1 -9.32573e-6 0 -1 1.1776e-5 0 -1 1.16126e-5 0 -1 -1.17732e-5 0 -1 9.58692e-6 0 -1 1.13404e-5 0 -1 2.22609e-5 0 -1 1.10514e-5 0 -1 -1.91651e-5 0 -1 1.92962e-5 0 -1 1.3913e-6 0 -1 1.45976e-5 0 -1 -5.88672e-6 0 -1 -4.40818e-5 0 -1 2.44686e-6 0 -1 1.09552e-5 0 -1 9.12324e-6 0 -1 -4.6236e-6 0 -1 1.12248e-5 0 -1 -1.13352e-5 0 -1 0.05233073 0.9986299 -1.73237e-7 0.05233097 0.9986298 0 0.05233079 0.9986299 0 0.0523312 0.9986299 0 0.05233174 0.9986298 -1.21266e-7 0.05233037 0.9986299 0 0.05233097 0.9986298 0 0.05233108 0.9986298 0 0.05232465 0.9986302 -2.26796e-7 0.05233162 0.9986298 0 0.05233108 0.9986299 0 0.05233097 0.9986299 0 0.05233097 0.9986298 0 0.05233103 0.9986299 0 -1.77292e-6 0 -1 0.05233097 0.9986299 0 0.05233103 0.9986299 0 -1.7597e-6 0 1 -3.39592e-7 0 1 9.07497e-7 0 1 9.97269e-7 0 1 0.05233108 0.9986299 0 0.05233097 0.9986299 0 0.05233126 0.9986298 0 0.05233079 0.9986299 0 0.05233013 0.9986299 0 0.05233079 0.9986298 0 0.0523312 0.9986298 -1.65363e-7 0.05233097 0.9986298 -2.27374e-7 0.0523321 0.9986298 0 0.05233091 0.9986298 0 0.05233097 0.9986299 0 0.05233085 0.9986298 0 0.05233126 0.9986299 0 0.0523312 0.9986298 -1.51955e-7 0.05233085 0.9986299 0 0.05233097 0.9986299 0 0.9986299 -0.05232995 -1.90983e-7 0.9986297 -0.05233263 -1.76241e-7 0.9986301 -0.05232781 1.22042e-7 0.9986298 -0.05233108 -1.42718e-7 0.9986299 -0.05233067 -5.0273e-7 -7.34649e-6 0 1 1.47471e-5 0 1 2.64081e-5 0 1 3.86736e-5 0 1 3.41057e-5 0 1 1.48566e-5 0 1 8.34281e-6 0 1 4.43369e-5 0 1 -4.10123e-5 0 1 -2.95231e-6 0 1 1.45324e-5 0 1 -1.38004e-4 0 1 4.98121e-6 0 1 -7.36152e-6 0 1 -8.02603e-6 0 1 -0.9986299 0.05233025 1.38309e-7 -0.99863 0.05232936 2.03433e-7 -0.99863 0.05232948 1.47791e-7 -0.9986297 0.05233395 0 -2.95828e-6 0 1 -0.9986301 0.05232769 6.42586e-7 -0.99863 0.05232936 3.97937e-7 1.4776e-6 0 -1 -0.9986299 0.05233085 1.66527e-7 -0.9986299 0.05233103 0 -0.9986298 0.05233132 3.14441e-7 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47046e-7 0 -1 -1.47043e-7 0 -1 -1.47042e-7 0 -1 -1.47048e-7 0 -1 -1.47043e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47048e-7 0 -1 -1.47046e-7 0 -1 -1.47043e-7 0 -1 -1.4705e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47041e-7 0 -1 -1.47044e-7 0 -1 -1.47047e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47048e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 0.9986298 -0.05233162 -1.66611e-7 0.9986299 -0.05232977 -2.49727e-7 0.9986297 -0.05233258 0 1.75951e-6 0 -1 0.9986298 -0.05233168 -8.78039e-7 0.9986294 -0.0523383 0 0.9986299 -0.05233031 0 0.9986299 -0.05233019 1.02829e-6 0.99863 -0.05232834 0 0.9986298 -0.05233091 0 3.46764e-6 0 1 0.9986299 -0.05232942 -1.76533e-7 0.9986295 -0.05233705 -2.42085e-7 0.9986296 -0.05233514 -1.30483e-7 0.9986298 -0.05233073 -1.80137e-7 0.9986299 -0.05233013 -1.92206e-7 0.9986299 -0.05233108 0 0.9986299 -0.05232977 -1.1902e-6 -1.88111e-5 0 -1 1.87431e-5 0 -1 0.9986299 -0.05233043 0 0.9986298 -0.05233198 0 1.18411e-5 0 1 0.9986299 -0.05233037 0 0.9986298 -0.05233138 2.87534e-7 -3.59229e-7 0 -1 1.93489e-6 0 -1 0.9986294 -0.05233842 0 0.99863 -0.05232858 0 1.31727e-6 0 1 -0.9820938 0.1883923 0 -0.9926925 0.1206722 0 -0.9919117 0.1269302 3.05194e-5 -0.9821052 0.1883335 6.10382e-5 -0.9471309 0.3208477 2.13634e-4 -0.9796784 0.2005746 -2.44157e-4 -0.8771294 0.4802542 -2.13636e-4 -0.8987729 0.4384146 0 -0.8768274 0.4808053 3.05196e-5 -0.9471216 0.3208751 -3.05188e-5 -0.9796544 0.2006918 6.10377e-5 -0.9387645 0.3445595 9.1557e-5 -0.8988206 0.4383166 9.15576e-5 -0.4539761 0.8910139 0 -0.9389108 0.3441604 -3.96744e-4 -0.9919314 0.1267763 -1.83115e-4 -0.5816654 0.8134281 0 -0.696267 0.717783 0 -0.7958204 0.6055328 0 -0.7953988 0.6060864 0 -0.02206486 0.9997566 0 -0.170938 0.9852818 0 0.2734834 0.9618767 0 0.1271443 0.9918843 0 0.6636703 0.7480252 0 0.7674804 0.6410726 0 0.6635091 0.7481682 0 0.4136259 0.910447 0 0.5446451 0.8386667 0 0.9396562 0.3421204 0 0.9697373 0.244151 9.15566e-5 0.9754768 0.2201026 -3.05189e-5 0.7678009 0.6406886 0 0.922265 0.3865584 -1.22078e-4 0.9396134 0.342238 3.05188e-5 0.9225605 0.3858524 3.05191e-5 0.9754833 0.2200735 1.22077e-4 0.9696378 0.2445457 -2.1363e-4 0.99641 0.08465927 3.05189e-5 0.9952645 0.09720391 -1.22077e-4 0.9997463 0.0225231 -9.15574e-5 0.9998678 0.01626664 0 0.9952707 0.09714049 6.10371e-5 0.9964073 0.08468955 0 0.9997457 0.02255362 3.05191e-5 0.9998683 0.01623618 0 -0.3159897 0.9487626 0 -0.6966386 0.7174224 0 -0.03894281 -0.9992378 0.002716183 -0.0200206 -0.9997789 0.006439507 -0.02603268 -0.9996498 0.004760921 -0.06689846 -0.9975867 0.01858627 -0.033266 -0.9994149 0.007965505 -0.06546407 -0.9977397 0.01516813 -0.0689724 -0.9975371 0.01275682 -0.04541254 -0.9988931 0.01226866 -0.061679 -0.9980342 0.01110893 -0.05978673 -0.9981554 0.01055955 -0.05035686 -0.9986836 0.009766161 -0.0745573 -0.9971394 0.01242113 -0.0827977 -0.9964722 0.01370292 -0.003784358 -0.9999896 0.002533078 -0.08496487 -0.996384 -2.44152e-4 -0.04205578 -0.9991149 9.76622e-4 -0.04919618 -0.9987871 0.002014219 -0.1008972 -0.99475 0.01709085 -0.03118318 -0.9995137 2.09251e-4 -0.02993893 -0.9995514 7.93488e-4 -0.04934543 -0.9987815 7.12338e-4 -0.04635268 -0.998925 5.02846e-4 -0.06500482 -0.9977788 0.01455742 -0.06198406 -0.9980323 0.009460866 -0.0522176 -0.9986356 -5.18819e-4 -0.04092246 -0.9991555 -0.003699779 -0.04887562 -0.9988047 7.13977e-4 -0.05484247 -0.9984871 -0.003997921 -0.06570827 -0.9978318 -0.00375384 -0.04043722 -0.9991821 1.52593e-4 -0.07022434 -0.9974543 0.01239073 -0.03115445 -0.9995146 2.14419e-4 -0.03795754 -0.9992408 0.008788824 -0.04673832 -0.9989071 4.14548e-4 -0.04797637 -0.9988062 0.009186267 -0.1102641 -0.9938417 -0.01098668 -0.1717621 -0.9850381 -0.01406931 -0.09479284 -0.9954774 0.006256401 -0.03749895 -0.9947596 -0.09511756 -0.03905391 -0.9991953 0.009131968 -0.05435436 -0.9985218 0 -0.05478203 -0.9984983 3.9675e-4 -0.05438482 -0.9985201 0 -0.04818147 -0.9988384 6.66708e-4 -0.04958462 -0.99877 2.4944e-4 -0.04968112 -0.9987649 6.89761e-4 -0.05005693 -0.9987463 2.96463e-4 -0.05009382 -0.9987444 6.31266e-4 -0.04991781 -0.9987532 6.61269e-4 -0.05420219 -0.9985297 7.32463e-4 -0.05316424 -0.9985853 0.001037597 -0.05014306 -0.9987418 7.32461e-4 -0.05356156 -0.9985646 -2.44155e-4 -0.05013686 -0.9987422 6.2661e-4 -0.0539571 -0.998543 8.54525e-4 -0.05014252 -0.998742 3.07614e-4 -0.04988086 -0.9987552 2.7499e-4 -0.04877489 -0.9988098 2.32509e-4 -0.04925996 -0.998786 2.33814e-4 -0.04685646 -0.9989016 3.91314e-4 -0.0481407 -0.9988405 2.62732e-4 -0.04568421 -0.9989557 6.77047e-4 -0.04687231 -0.9989008 3.89067e-4 -0.06268572 -0.9979974 -0.008484244 -0.04493713 -0.9989895 8.92906e-4 -0.06741553 -0.9976828 -0.009186089 -0.07544356 -0.9971247 -0.007110953 -0.1014465 -0.994841 2.44155e-4 -0.09076362 -0.9958671 -0.003296017 -0.08932924 -0.9959889 0.005157709 -0.07764053 -0.9969363 0.009491384 -0.0486198 -0.9988167 0.001256406 -0.06485378 -0.9978944 9.46103e-4 -0.04568809 -0.9989558 3.54393e-5 -0.04725748 -0.9988827 5.11645e-4 -0.0466631 -0.9989106 3.50623e-4 -0.04760771 -0.998866 5.84439e-4 -0.03778296 -0.9992343 0.01016294 -0.04541176 -0.998968 -0.00100708 -0.04644995 -0.9989191 0.001800596 -0.01141417 -0.9999348 4.2727e-4 -0.04382354 -0.9990391 -6.44047e-4 -0.03994965 -0.9992004 0.001648008 -0.0582906 -0.9982953 0.002990782 0.002227842 -0.9999772 0.006378412 -0.01168882 -0.9999317 -2.13635e-4 0.05972564 -0.9982149 -1.83114e-4 0.05063164 -0.998625 0.01358109 -0.01626664 -0.9998677 -2.13634e-4 -0.03793489 -0.9992793 0.001403868 -0.07895219 -0.9968668 0.004821956 -0.09033519 -0.9940841 -0.06030482 -0.617195 -0.7867902 0.005619227 -0.03915643 -0.9990245 0.02041751 -0.03201401 -0.9994844 -0.002471983 -0.03799569 -0.9992719 -0.003479123 0.1590841 -0.987265 2.04623e-4 0.0523312 0.9986299 7.52924e-7 0.05232971 0.9986299 5.47245e-7 0.05233108 0.9986298 0 0.05233085 0.9986298 -1.30776e-7 0.05233156 0.9986298 0 0.05233037 0.9986299 0 0.05232995 0.9986299 3.52071e-7 0.05233246 0.9986298 -2.07943e-7 0.05233234 0.9986298 0 0.05233305 0.9986297 4.90001e-7 0.05232954 0.9986299 -5.21793e-7 0.05233514 0.9986296 -4.88045e-7 0.05232691 0.9986301 0 0.05233627 0.9986296 0 0.05233085 0.9986299 0 0.05233073 0.9986298 -2.44985e-7 0.05232888 0.9986299 0 0.05233216 0.9986298 0 0.05233103 0.9986298 1.64781e-7 0.05233126 0.9986298 8.58354e-7 0.05233037 0.9986299 -6.19194e-7 0.05232906 0.99863 -1.52564e-6 0.05233484 0.9986296 2.00414e-6 0.05233198 0.9986298 -4.07837e-7 0.05233073 0.9986298 0 0.05232948 0.9986299 5.85105e-7 0.05233365 0.9986296 -1.84873e-6 0.05232954 0.99863 0 0.05233234 0.9986298 0 0.05233043 0.9986299 1.84387e-7 0.05233108 0.9986298 0 0.05232954 0.9986299 0 0.05233168 0.9986298 6.52515e-7 0.0523281 0.99863 -4.87769e-7 0.05233252 0.9986297 -5.61785e-7 0.05233091 0.9986299 4.42538e-7 0.05232965 0.9986299 0 0.05232965 0.9986299 -3.50299e-7 0.05232989 0.9986299 -7.52906e-7 0.05233365 0.9986296 7.23431e-7 0.05233496 0.9986296 -6.68049e-7 -0.9952832 0.05090552 -0.0825842 -0.9952776 0.05096632 0.08261424 -0.9985305 0.05340874 0.009186267 -0.9681326 0.04950225 0.2454971 -0.9853999 0.052859 0.1618427 -0.947389 0.05078458 0.3160303 -0.9145721 0.04663348 0.4017256 -0.8360726 0.04257422 0.5469645 -0.8856607 0.04742646 0.4619047 -0.734717 0.03741639 0.6773412 -0.8039042 0.04303193 0.5932002 -0.7038983 0.03769135 0.7093002 -0.6133449 0.03125166 0.7891967 -0.4752767 0.02417123 0.8795044 -0.5863144 0.03140479 0.8094747 -0.3242673 0.01641935 0.945823 -0.3081167 0.01644957 0.9512065 -0.4528715 0.02423208 0.8912464 -0.1557707 0.00827074 0.9877586 -0.1643439 0.008240044 0.9863687 -0.08227944 0.004059016 0.9966011 -0.07831072 0.004089474 0.9969207 -0.9885336 0.05267536 -0.1415156 -0.9681075 0.04953306 -0.24559 -0.955485 0.05081391 -0.2906312 -0.8974726 0.04785376 -0.4384667 -0.9145341 0.04687726 -0.4017834 -0.8143078 0.04361164 -0.5787927 -0.8360363 0.04294013 -0.5469913 -0.7347831 0.03769135 -0.6772542 -0.7098677 0.03805696 -0.7033062 -0.5878546 0.03149545 -0.8083534 -0.6133775 0.03131282 -0.7891689 -0.4532727 0.02426284 -0.8910416 -0.4752767 0.02417123 -0.8795044 -0.3242946 0.01641917 -0.9458137 -0.3085203 0.01648044 -0.9510751 -0.1560136 0.008270621 -0.9877203 -0.1643736 0.008240044 -0.9863638 -0.08227944 0.004059016 -0.9966011 -0.07837378 0.004089593 -0.9969157 0.1737782 -0.009064257 0.9847432 0.08752948 -0.004577875 0.9961515 0.08710014 -0.00451672 0.9961894 0.6417344 -0.03354096 0.7661931 0.499211 -0.02606379 0.8660884 0.4993286 -0.02609407 0.8660197 0.3415981 -0.01782304 0.9396771 0.1733778 -0.00903356 0.984814 0.3415074 -0.01782304 0.9397101 0.8648256 -0.04526013 0.5000283 0.9382282 -0.04907518 0.3425195 0.8646827 -0.04523009 0.5002781 0.6419345 -0.03357076 0.7660242 0.7649931 -0.04001057 0.6427944 0.7648952 -0.04001027 0.6429111 0.9986308 -0.05230891 4.88298e-4 0.9835481 -0.05154722 -0.1731364 0.9833537 -0.05145508 0.1742637 0.9384273 -0.0491355 0.3419649 0.9834643 -0.05151551 0.1736207 0.7650448 -0.04013216 -0.6427255 0.8648979 -0.04535067 -0.4998951 0.864822 -0.0453515 -0.5000262 0.9384245 -0.04919636 -0.3419638 0.9385566 -0.04919689 -0.3416013 0.9834665 -0.05157667 -0.1735906 0.499504 -0.02621579 -0.8659149 0.6419984 -0.03366249 -0.7659667 0.6418996 -0.03366208 -0.7660496 0.7649618 -0.04013264 -0.6428242 0.4993274 -0.02618557 -0.8660176 0.3417248 -0.01794534 -0.9396287 0.34148 -0.01791477 -0.9397184 0.1733481 -0.009094655 -0.9848187 0.08664321 -0.004547297 -0.9962291 0.08710014 -0.004547238 -0.9961892 1.93436e-5 0 -1 9.12623e-6 0 -1 4.90875e-6 0 -1 -5.98108e-6 0 -1 -2.35571e-5 0 -1 -5.80665e-6 0 -1 4.6653e-6 0 -1 1.17799e-5 0 -1 -1.90209e-5 0 -1 -1.12281e-5 0 -1 -8.34756e-6 0 -1 9.91851e-6 0 -1 -1.17722e-5 0 -1 -1.90155e-5 0 -1 6.08893e-6 0 -1 9.13538e-6 0 -1 -1.16076e-5 0 -1 -5.61285e-6 0 -1 1.13354e-5 0 -1 -3.59357e-4 0 -1 -2.45316e-4 0 -1 1.49897e-4 0 -1 -1.50247e-4 0 -1 7.05963e-5 0 -1 -2.36933e-5 0 -1 -4.85963e-5 0 -1 2.65841e-5 0 -1 -6.38246e-5 0 -1 -1.23169e-4 0 -1 7.50593e-5 0 -1 2.42558e-4 0 -1 -2.04663e-4 0 -1 6.74674e-5 0 -1 -1.48111e-5 0 -1 6.93962e-5 0 -1 4.98305e-6 0 -1 3.98787e-5 0 -1 -4.51821e-5 0 -1 4.3979e-6 0 -1 -4.02304e-6 0 -1 2.4475e-6 0 -1 8.64708e-6 0 -1 1.83482e-6 0 -1 -4.40056e-6 0 -1 0 0 -1 5.27077e-7 0 -1 1.0135e-6 0 -1 5.34394e-7 0 -1 -8.89835e-7 0 -1 1.30398e-6 0 -1 1.63247e-6 0 -1 -1.83531e-7 1.22243e-7 -1 0 0 -1 -1.84787e-7 -1.43994e-7 -1 4.37208e-6 0 -1 -8.84414e-7 0 -1 -2.82432e-6 0 -1 -6.8068e-6 0 -1 -2.51312e-6 0 -1 4.17313e-6 0 -1 -4.71703e-6 0 -1 -1.21266e-7 0 -1 2.48043e-6 0 -1 0 1.55455e-6 -1 0 -9.45106e-6 -1 -3.05466e-6 5.56109e-7 -1 -4.17313e-6 9.23889e-7 -1 1.17918e-6 3.26032e-7 -1 0 0 -1 -3.80436e-6 1.75079e-7 -1 -1.22432e-7 -3.14441e-7 -1 2.69481e-6 0 -1 -3.68416e-6 0 -1 -1.81899e-7 -1.46884e-7 -1 2.86981e-6 0 -1 -1.34259e-7 -1.26366e-7 -1 -1.90561e-7 0 -1 -1.22432e-7 1.50582e-7 -1 3.79492e-6 0 -1 -1.57747e-6 0 -1 -1.0425e-6 0 -1 2.51061e-6 0 -1 7.3816e-6 0 -1 3.06267e-6 0 -1 -4.16993e-6 0 -1 -4.71974e-6 0 -1 3.05455e-6 0 -1 -1.21266e-7 0 -1 4.96076e-6 -1.26441e-5 -1 7.38204e-6 0 -1 0 1.56185e-6 -1 0 2.83616e-6 -1 0 5.55942e-7 -1 0 9.22363e-7 -1 1.17989e-6 3.26802e-7 -1 0 0 -1 0 1.73013e-7 -1 -1.57412e-7 -3.14445e-7 -1 2.69455e-6 0 -1 -1.81899e-7 -1.46886e-7 -1 -2.87007e-6 0 -1 -1.47251e-7 -1.26365e-7 -1 -1.25597e-7 0 -1 -1.39922e-7 1.5058e-7 -1 7.88796e-7 0 -1 6.10859e-6 0 -1 -2.35984e-6 0 -1 -4.96032e-6 0 -1 -0.9615298 -0.274701 0 -0.9936284 -0.1127056 0 -0.9995389 -0.03036671 0 -0.9936251 -0.1127358 0 -0.999538 -0.03039723 0 -0.8201987 -0.572079 0 -0.7148314 -0.6992969 0 -0.7148463 -0.6992816 0 -0.9031847 -0.4292523 0 -0.2958568 -0.9552323 0 -0.449056 -0.8935037 0 -0.5900266 -0.8073839 0 0.1944079 -0.9809208 0 0.03030574 -0.9995407 0 -0.1346201 -0.9908973 0 0.5024035 -0.8646333 0 0.6378401 -0.770169 0 0.3532029 -0.9355468 0 0.3531929 -0.9355506 0 0.7559096 -0.654676 0 0.8533619 -0.5213192 0 0.927535 -0.3737363 0 0.8533754 -0.521297 0 0.9763971 -0.2159835 0 0.9764035 -0.2159544 0 0.9908891 -0.1346801 0 -0.05233097 -0.9986298 1.46006e-7 -0.05233091 -0.9986298 0 -0.05233061 -0.9986299 0 -0.05233114 -0.9986298 0 -0.05233073 -0.9986299 0 -0.05233138 -0.9986298 3.49971e-7 0.9986296 -0.05233418 0 0.9986301 -0.05232691 0 -0.05233108 -0.9986298 0 -0.05233108 -0.9986298 0 -0.05233097 -0.9986298 0 -0.05233091 -0.9986299 0 -0.05233108 -0.9986298 0 -0.0523312 -0.9986299 0 -0.05233132 -0.9986298 0 -0.05233097 -0.9986298 0 0.02240109 -0.9997491 0 -0.1268363 -0.9919237 0 -0.2733262 -0.9619215 0 -0.4137133 -0.9104073 0 -0.4133775 -0.9105598 0 -0.5443682 -0.8388465 0 -0.5448511 -0.8385329 0 -0.6637347 -0.7479681 0 -0.6632987 -0.7483549 0 -0.8547503 -0.5190395 0 -0.9225343 -0.3859152 0 -0.9223811 -0.3862813 0 -0.9697138 -0.2442443 0 -0.9952645 -0.09720391 0 -0.9952737 -0.09711027 0 -0.9997478 -0.02246212 0 0.1712742 -0.9852234 0 0.1710913 -0.9852552 0 0.3159348 -0.948781 0 0.4536963 -0.8911564 0 0.5819337 -0.8132362 0 0.5814518 -0.8135809 0 0.6962359 -0.7178131 0 0.7954766 -0.6059844 0 0.8771365 -0.4802414 0 0.8769456 -0.4805896 0 0.9387978 -0.344469 0 0.9796544 -0.2006918 0 0.9919198 -0.1268664 0 0.9919275 -0.1268063 0 -0.05233091 -0.9986299 0 -0.05233103 -0.9986298 0 -0.0523321 -0.9986298 0 -0.0523312 -0.9986299 0 -0.05233097 -0.9986298 1.20312e-7 -0.05233091 -0.9986298 0 -0.05233097 -0.9986298 0 -0.05233091 -0.9986298 0 0.9613649 0.2752773 0 0.9935798 0.1131343 0 0.9614421 0.2750073 0 0.9935588 0.1133185 0 0.8200484 0.5722943 0 0.7146351 0.6994976 0 0.7146652 0.6994667 0 0.8204988 0.5716483 0 0.9035184 0.4285494 0 0.903214 0.4291907 0 0.2960047 0.9551866 0 0.4486901 0.8936875 0 0.2954517 0.9553578 0 0.4495194 0.8932706 0 0.5904305 0.8070885 0 0.5898146 0.8075387 0 -0.1948658 0.9808299 0 -0.1939793 0.9810057 0 -0.03058016 0.9995324 0 0.1342225 0.9909512 0 -0.02990841 0.9995527 0 0.1348939 0.9908602 0 -0.5024396 0.8646124 0 -0.6382221 0.7698523 0 -0.6381559 0.7699071 0 -0.3528052 0.9356969 0 -0.3535638 0.9354105 0 -0.5021908 0.864757 0 -0.9278059 0.3730634 0 -0.85334 0.521355 0 -0.9276938 0.373342 0 -0.8529823 0.5219401 0 -0.755669 0.6549538 0 -0.7561783 0.6543657 0 -0.9936835 -0.1122201 0 -0.9764849 0.215586 0 -0.9765185 0.215434 0 -0.9031965 -0.4292274 0 -0.820024 -0.5723291 0 -0.9616942 -0.2741245 0 -0.4491536 -0.8934546 0 -0.5899034 -0.8074739 0 -0.7146351 -0.6994976 0 0.03024476 -0.9995426 0 -0.1345602 -0.9909054 0 -0.2960047 -0.9551866 0 0.1942259 -0.9809569 0 0.1942552 -0.9809511 0 0.3529857 -0.9356288 0 0.5022857 -0.8647018 0 0.638189 -0.7698798 0 0.7562065 -0.6543332 0 0.9274016 -0.3740674 0 0.9763026 -0.2164102 0 -0.008905351 -0.9999604 0 -0.008905351 -0.9999604 0 0.8225359 0.5687132 0 0.7177377 0.6963136 0 0.8225502 0.5686926 0 0.9985433 -0.05395716 0 0.9748389 -0.222911 0 0.7177529 0.6962979 0 0.5945464 0.8040614 0 0.4546814 0.8906543 0 0.3799622 0.925002 0 0.9043707 0.4267477 0 0.9618343 0.2736327 0 0.9043825 0.4267228 0 0.9935934 0.1130138 0 0.99359 0.1130439 0 0.9246895 -0.3807222 0 0.9246743 -0.3807591 0 0.6202111 -0.784435 0 0.7444857 -0.6676384 0 0.8473908 -0.5309697 0 0.3249399 -0.9457347 0 0.160166 -0.9870901 0 0.478756 -0.8779481 0 0.07596129 -0.9971109 0 0.3027051 0.9530844 0 0.3027051 0.9530844 0 -0.9277911 0.3731002 0 -0.9760181 0.2176898 0 -0.9906551 0.1363905 0 -0.75371 0.6572073 0 -0.635046 0.7724744 0 -0.8535828 0.5209574 0 -0.1887625 0.9820228 0 -0.3483459 0.9373661 0 -0.4995402 0.8662908 0 -0.0247817 0.9996929 0 0.1412419 0.9899751 0 0.2230336 0.9748108 0 -0.9986298 0.05233192 0 -0.9986298 0.05233192 0 -0.3256427 -0.9454929 0 -0.32567 -0.9454836 0 -0.1695635 -0.9855192 0 -0.08951205 -0.9959858 0 -0.6084046 -0.793627 0 -0.7273626 -0.6862533 0 -0.4744456 -0.8802849 0 -0.9636167 -0.2672881 0 -0.908927 -0.4169552 0 -0.8297047 -0.5582028 0 -0.8297141 -0.5581886 0 -0.9939528 -0.1098085 0 -0.9996007 -0.02826088 0 -0.05233103 -0.9986299 1.39922e-7 -0.05233103 -0.9986298 1.39922e-7 0.9333871 -0.3588706 6.71414e-4 0.8985092 -0.4389544 -6.71417e-4 0.9744245 -0.2247146 -6.71428e-4 0.9917038 -0.1285446 0 0.9781118 -0.2080803 0 0.7830851 -0.6219146 0 0.6694705 -0.7428387 0 0.7772051 -0.6292474 -5.18828e-4 0.8656888 -0.5005826 1.52598e-4 0.2584661 -0.9660204 0 0.2584946 -0.9660128 0 0.406399 -0.9136958 0 0.4063876 -0.9137009 0 0.5449219 -0.8384869 0 0.104313 -0.9945445 0 0.02639895 -0.9996516 0 0.9986298 -0.05233073 0 0.9986299 -0.05233013 0 0.3580505 0.9337023 0 0.3580238 0.9337124 0 0.2076821 0.9781965 0 0.1307142 0.9914202 0 0.6295845 0.7769321 0 0.743446 0.6687961 0 0.6295511 0.7769591 0 0.4996582 0.8662227 0 0.4996944 0.8662019 0 0.9656694 0.2597743 0 0.9656673 0.259782 0 0.9135899 0.4066367 0 0.9136013 0.4066113 0 0.8385329 0.5448511 0 0.8385468 0.5448296 0 0.9945058 0.1046816 0 0.9945094 0.1046482 0 0.9997087 0.02414047 0 0.9997071 0.02420145 0 0.05233097 0.9986298 0 0.05233108 0.9986299 0 -0.93355 0.3584473 0 -0.9335743 0.3583839 0 -0.9781827 0.2077467 0 -0.9914647 0.1303763 0 -0.7771632 0.6292992 0 -0.6691654 0.7431135 0 -0.6692143 0.7430695 0 -0.7771361 0.6293326 0 -0.8659768 0.5000844 0 -0.8659218 0.5001795 0 -0.2587453 0.9659456 0 -0.2587737 0.965938 0 -0.4066991 0.9135622 0 -0.5447019 0.8386298 0 -0.5446805 0.8386437 0 -0.1045275 0.9945221 0 -0.1044973 0.9945253 0 -0.02615499 0.999658 0 -0.02618545 0.9996572 0 -0.9986297 0.05233281 0 -0.99863 0.05232924 0 -0.3909448 -0.9204142 0 -0.3906792 -0.9205269 0 -0.2249242 -0.9743763 0 -0.139165 -0.9902692 0 -0.1392889 -0.9902518 0 -0.2251403 -0.9743264 0 -0.6820801 -0.7312775 0 -0.7988192 -0.6015712 0 -0.7986871 -0.6017467 0 -0.682128 -0.7312329 0 -0.5445743 -0.8387126 0 -0.5447728 -0.8385838 0 -0.9563508 -0.2922217 0 -0.992547 -0.1218633 0 -0.9562857 -0.292434 0 -0.8909396 -0.4541219 0 -0.8911564 -0.4536963 0 -0.9925507 -0.1218333 0 -0.9993914 -0.03488272 0 -0.9993947 -0.03479123 0 -0.9986298 0.05233281 0 -0.9986299 0.05233007 0 -0.3906424 -0.9205426 0 -0.1391991 -0.9902644 0 -0.139259 -0.990256 0 -0.2250757 -0.9743414 0 -0.682017 -0.7313364 0 -0.7988449 -0.6015371 0 -0.6822226 -0.7311446 0 -0.5445173 -0.8387496 0 -0.9563225 -0.2923139 0 -0.8909519 -0.4540977 0 -0.8911255 -0.4537571 0 -0.9993904 -0.03491318 0 -0.05233097 -0.9986299 1.39922e-7 -0.05233097 -0.9986298 0 0.9335986 -0.3583205 0 0.9335398 -0.3584739 0 0.9781903 -0.2077113 0 0.9914647 -0.1303763 0 0.9914404 -0.1305603 0 0.9781703 -0.2078051 0 0.7771632 -0.6292992 0 0.6691823 -0.7430984 0 0.6691654 -0.7431135 0 0.8659009 -0.5002156 0 0.8659899 -0.5000615 0 0.2587376 -0.9659477 0 0.2587737 -0.965938 0 0.4066736 -0.9135735 0 0.4066991 -0.9135622 0 0.5446451 -0.8386667 0 0.5446805 -0.8386437 0 0.1045275 -0.9945221 0 0.02618545 -0.9996572 0 0.99863 -0.05232864 0 0.9986299 -0.05233073 0 0.3582939 0.9336089 0 0.2078635 0.9781579 0 0.1305303 0.9914444 0 0.2078989 0.9781503 0 0.6293326 0.7771361 0 0.7432001 0.6690694 0 0.6293659 0.7771092 0 0.4999665 0.8660449 0 0.965938 0.2587737 0 0.9659151 0.2588591 0 0.9134286 0.4069991 0 0.9134954 0.4068491 0 0.8386298 0.5447019 0 0.8386667 0.5446451 0 0.9945414 0.1043432 0 0.9996587 0.02612447 0 0.05233097 0.9986299 0 0.05233091 0.9986298 0 -0.9781703 0.2078051 0 -0.9914404 0.1305603 0 -0.9781903 0.2077113 0 -0.7772051 0.6292474 0 -0.6691823 0.7430984 0 -0.7771092 0.6293659 0 -0.8659086 0.5002024 0 -0.4067245 0.9135509 0 -0.5446451 0.8386667 0 0.9986299 -0.05232906 -3.30768e-7 0.9986298 -0.05233138 3.06062e-7 0.9986301 -0.05232769 0 0.9986298 -0.05233138 -1.66567e-7 0.9986299 -0.05233055 -7.18979e-7 0.9986298 -0.05233114 0 -1.47968e-6 0 1 0.99863 -0.05232924 -6.42758e-7 0.9986299 -0.05233067 -3.06235e-7 0.9986296 -0.05233365 -4.93703e-7 2.95828e-6 0 -1 0.9986302 -0.05232298 3.23374e-7 0.9986298 -0.05233132 -5.36148e-7 0.9986298 -0.05233323 -5.26481e-7 0.998629 -0.05234611 -1.53005e-7 0.9986295 -0.05233764 0 0.9986304 -0.05232262 0 0.9986301 -0.0523265 -2.63222e-7 0.9986304 -0.05232131 -3.68671e-7 0.9986302 -0.05232489 1.9553e-7 0.9986304 -0.05232191 -2.10492e-7 0.9986298 -0.05233192 -6.08622e-7 0.9986302 -0.05232387 0 0.9986302 -0.05232536 -1.51621e-7 0.9986287 -0.05235224 -4.00424e-7 0.9986292 -0.05234217 -1.22101e-7 0.9986298 -0.05233281 -2.60634e-7 0.9986305 -0.05231958 1.28675e-7 0.9986299 -0.05233043 -1.47796e-7 0.9986298 -0.05233079 -1.74524e-7 0.9986301 -0.05232781 -3.68349e-7 0.9986295 -0.05233639 2.33445e-7 0.9986298 -0.05233216 0 0.99863 -0.05232906 0 0.9986299 -0.05233037 -2.31386e-7 0.9986298 -0.05233228 2.54187e-7 -1.02888e-5 0 -1 9.3311e-6 0 -1 1.44018e-5 0 -1 5.52566e-6 0 -1 4.09799e-6 0 -1 3.17886e-6 0 -1 -3.41867e-6 0 -1 1.95749e-5 0 -1 6.90492e-6 0 -1 -2.35411e-5 0 -1 -2.23225e-5 0 -1 -0.9986298 0.05233108 1.91303e-7 -0.9986299 0.05232965 6.88178e-7 -0.9986299 0.05233019 1.66618e-7 -0.9986299 0.05233019 0 -0.9986301 0.05232763 -1.73604e-7 -0.9986299 0.05233019 0 -0.99863 0.05232936 -4.0407e-7 -0.9986296 0.05233544 8.6694e-7 5.32705e-6 0 -1 -8.28696e-6 0 -1 6.96745e-6 0 -1 -0.9986298 0.05233204 0 -0.9986298 0.05233222 0 7.91961e-6 0 -1 -0.9986297 0.05233252 0 -0.99863 0.05232852 -1.10708e-6 8.0042e-6 0 1 -0.9986299 0.05233043 0 -0.9986297 0.05233258 1.98692e-7 -0.9986299 0.05233091 0 2.00982e-6 0 1 1.41337e-5 0 1 -4.87183e-6 0 1 -1.41532e-5 0 1 -1.72655e-6 0 1 -0.9986297 0.05233365 -3.13716e-7 -0.9986299 0.05233055 4.52721e-7 -0.9986302 0.05232506 5.30767e-7 -0.9986294 0.05233925 -2.94754e-7 -0.9986294 0.05233883 9.18514e-7 -0.9986299 0.05233073 -3.58343e-7 -0.9986302 0.05232596 -1.76299e-7 -0.9986299 0.05233061 7.16546e-7 -0.9986301 0.05232805 1.82623e-7 -3.52213e-6 0 -1 -0.9986297 0.0523343 -3.08581e-7 -0.99863 0.05232894 3.20409e-7 -0.9986298 0.05233126 0 -0.9986298 0.05233198 1.35082e-7 -1.73235e-6 0 1 -0.9986299 0.05232918 6.55684e-7 -0.9986298 0.05233192 5.45965e-7 -0.9986293 0.05234187 -4.36985e-7 -0.9986299 0.05232888 2.25039e-7 -0.9986298 0.05233156 1.66364e-7 -0.9986298 0.05233234 0 -1.47043e-7 0 -1 -1.47048e-7 0 -1 -1.47044e-7 0 -1 -1.47046e-7 0 -1 -1.4705e-7 0 -1 -1.4699e-7 0 -1 -1.47067e-7 0 -1 -1.4704e-7 0 -1 -1.47047e-7 0 -1 -1.47048e-7 0 -1 -1.47047e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47044e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47043e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47047e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47043e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47048e-7 0 -1 -1.47045e-7 0 -1 -1.47039e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47046e-7 0 -1 -1.47048e-7 0 -1 -1.47046e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47037e-7 0 -1 -1.47047e-7 0 -1 -1.47046e-7 0 -1 -1.47042e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47046e-7 0 -1 -1.47043e-7 0 -1 -1.47049e-7 0 -1 -1.47044e-7 0 -1 -1.47043e-7 0 -1 -1.47049e-7 0 -1 -1.47047e-7 0 -1 -1.47044e-7 0 -1 -1.47041e-7 0 -1 -1.47043e-7 0 -1 -1.47052e-7 0 -1 -1.47008e-7 0 -1 -1.47032e-7 0 -1 -1.47139e-7 0 -1 -1.47037e-7 0 -1 -1.47071e-7 0 -1 -1.47059e-7 0 -1 -1.47052e-7 0 -1 -1.47051e-7 0 -1 -1.47037e-7 0 -1 -1.47048e-7 0 -1 -1.47043e-7 0 -1 -1.47044e-7 0 -1 -1.47036e-7 0 -1 -1.4705e-7 0 -1 -1.47049e-7 0 -1 -1.47041e-7 0 -1 -1.47046e-7 0 -1 -1.4704e-7 0 -1 -1.47052e-7 0 -1 -1.47041e-7 0 -1 -1.47044e-7 0 -1 -1.47042e-7 0 -1 -1.47047e-7 0 -1 -1.47044e-7 0 -1 -1.47046e-7 0 -1 -1.47042e-7 0 -1 -1.47041e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47046e-7 0 -1 -1.47043e-7 0 -1 -1.47049e-7 0 -1 -1.47041e-7 0 -1 -1.47043e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47047e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47042e-7 0 -1 -1.47033e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47048e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47038e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47043e-7 0 -1 -1.47042e-7 0 -1 -1.47036e-7 0 -1 -1.47045e-7 0 -1 -1.47054e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47047e-7 0 -1 -1.47045e-7 0 -1 -1.47047e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47043e-7 0 -1 -1.47049e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47048e-7 0 -1 -1.47045e-7 0 -1 -1.47043e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.4704e-7 0 -1 -1.47046e-7 0 -1 -1.47041e-7 0 -1 -1.47048e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47047e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47043e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47047e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47042e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47044e-7 0 -1 -1.47043e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47046e-7 0 -1 -1.47042e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47025e-7 0 -1 -1.47048e-7 0 -1 -1.47045e-7 0 -1 -1.47035e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47043e-7 0 -1 -1.47045e-7 0 -1 -1.47038e-7 0 -1 -1.47045e-7 0 -1 -1.47047e-7 0 -1 -1.47045e-7 0 -1 -1.47052e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.4704e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47042e-7 0 -1 -1.47049e-7 0 -1 -1.47045e-7 0 -1 -1.47047e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47046e-7 0 -1 -1.47047e-7 0 -1 -1.47061e-7 0 -1 -1.47044e-7 0 -1 -1.47042e-7 0 -1 -1.47045e-7 0 -1 -1.47047e-7 0 -1 -1.47045e-7 0 -1 -1.47043e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47046e-7 0 -1 -1.47051e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47046e-7 0 -1 -1.47046e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47034e-7 0 -1 -1.47071e-7 0 -1 -1.47037e-7 0 -1 -1.4705e-7 0 -1 -1.47045e-7 0 -1 -1.47042e-7 0 -1 -1.47045e-7 0 -1 -1.47043e-7 0 -1 -1.47053e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47043e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47045e-7 0 -1 -1.47045e-7 0 -1 -1.47044e-7 0 -1 -1.47048e-7 0 -1 -1.47045e-7 0 -1 -1.47041e-7 0 -1 -1.47069e-7 0 -1 0 9.58135e-6 -1 0 5.15033e-6 -1 0 4.90495e-6 -1 -6.4327e-6 6.33439e-6 -1 6.40159e-6 5.13839e-6 -1 1.43764e-5 -8.05064e-6 -1 0 8.85882e-6 -1 1.32429e-5 -1.83784e-6 -1 -3.63473e-7 0 -1 -1.67985e-6 7.52559e-6 -1 0 -3.81514e-7 -1 0 9.32673e-6 -1 0 1.48606e-5 -1 0 3.45572e-5 -1 -9.55603e-6 1.35537e-5 -1 0 3.47857e-5 -1 0.9986299 -0.05233079 3.69408e-7 0.9986299 -0.05232983 -7.25805e-7 0.9986298 -0.05233156 5.42135e-7 0.9986299 -0.05233013 -2.07949e-7 0.9986299 -0.05233013 3.64192e-7 0.9986298 -0.05233228 0 0.9986298 -0.05233156 1.3306e-7 0.9986298 -0.0523324 -3.61649e-7 0.9986299 -0.05232965 -4.68333e-7 0.9986296 -0.05233424 1.95576e-6 0.9986299 -0.05233061 -1.39525e-6 0.9986299 -0.0523312 -1.93926e-6 0.9986298 -0.05233132 4.66478e-7 0.9986299 -0.05232882 -5.97564e-7 0.9986299 -0.05233031 1.02539e-6 0.9986299 -0.05232977 -3.71266e-7 0.9986299 -0.05233019 -2.16917e-7 0.9986298 -0.05233186 3.66274e-7 0.9986298 -0.05233103 -2.21767e-7 0.9986299 -0.05233049 0 0.9986298 -0.05233103 -4.89833e-7 0.9986298 -0.0523324 0 0.9986299 -0.05232989 1.29934e-6 0.9986298 -0.05233144 -7.58426e-7 0.9986298 -0.05233138 0 0.9986299 -0.05233067 4.42124e-7 0.9986298 -0.05233246 -1.35495e-6 0.9986299 -0.05233037 -1.9128e-6 0.9986299 -0.0523312 1.82695e-7 0.9986299 -0.05233031 1.4439e-7 0.9986299 -0.05233067 7.75969e-7 0.9986299 -0.05232959 -9.0511e-7 0.9986299 -0.05233025 -2.59246e-7 0.99863 -0.05232942 8.33242e-7 0.9986299 -0.05232942 3.32886e-7 0.9986298 -0.05233108 4.00893e-7 0.9986298 -0.05233174 0 0.5154097 0.8569164 0.006882905 0.545573 0.8379074 0.01617038 0.4672155 0.8839526 0.01837241 0.5014262 0.8650593 0.01562565 0.3452031 0.9382222 0.02395755 0.36431 0.9309332 0.02533107 0.4223907 0.9061563 0.02160781 0.2973197 0.9542492 0.03177064 0.2633183 0.9640355 0.03604298 0.289775 0.9566388 0.02954208 0.5603495 0.8281608 0.01258271 0.1807359 0.9723482 -0.147897 0.1802181 0.974734 -0.1319666 0.1933359 0.9716238 -0.1362659 0.1799706 0.9759373 -0.1231137 0.1806718 0.9776423 -0.1075791 0.1807652 0.9786595 -0.09772247 0.1935238 0.9746389 -0.1123726 0.1941016 0.9769476 -0.08887165 0.1802753 0.9807259 -0.07535123 0.1940411 0.9786595 -0.06763052 0.1818321 0.9798736 -0.08237075 0.1827802 0.9812875 -0.06055027 0.1941623 0.9798149 -0.04757922 0.1807006 0.9820887 -0.05337703 0.1827466 0.9823394 -0.04016274 0.1804916 0.9829685 -0.03457844 0.194135 0.9805327 -0.02945137 0.184456 0.9826158 -0.02102744 0.1806723 0.9834129 -0.01602244 0.1832079 0.9830601 -0.005279839 0.1939514 0.9809275 -0.01281815 0.1939789 0.9810034 0.002166807 0.1806093 0.9835548 -5.18817e-4 0.184853 0.9827085 0.01065105 0.1804896 0.9834764 0.01406925 0.1832378 0.9828127 0.02243167 0.1936095 0.9809572 0.01544237 0.1807335 0.9831696 0.02670413 0.1937657 0.9806701 0.02722299 0.1804619 0.9830337 0.032839 0.1939206 0.9802847 0.03790515 0.1793894 0.9830406 0.03808742 0.180307 0.9827162 0.04193329 0.1939776 0.9798985 0.04660224 0.1804925 0.9824235 0.04761046 0.1800622 0.9823467 0.05072259 0.193643 0.9795989 0.05374395 0.1793612 0.9822906 0.05417156 0.1799384 0.9820317 0.05688691 0.1937059 0.9792419 0.05969572 0.1800311 0.9817937 0.06058001 0.1799392 0.9817306 0.06186169 0.1785979 0.9818919 0.0631746 0.1793015 0.9815954 0.06573873 0.1932791 0.9790002 0.06482309 0.1799401 0.9814002 0.06689769 0.1796056 0.9814677 0.06680655 0.1797248 0.9814522 0.06671392 0.1793316 0.9815323 0.06659317 0.1932775 0.9789312 0.06586021 0.179394 0.9815703 0.06586122 0.1808862 0.9817056 0.05945104 0.1937343 0.9790785 0.06222814 0.1798819 0.9816595 0.0631448 0.1974612 0.9776926 0.07159876 0.2047989 0.9750496 0.085648 0.1921204 0.9788227 0.07068324 0.5685154 0.8226509 0.005987465 0.5535703 0.8328018 -0.001111805 0.5648058 0.8252232 0.001165568 0.5413802 0.8407717 -0.003246963 0.5591564 0.8290458 0.005224168 0.5255944 0.850718 -0.005418062 0.5354912 0.8445254 0.005100548 0.5183094 0.8551788 0.004965364 0.4977613 0.8673006 0.004832983 0.484114 0.8749613 -0.008752822 -0.3934882 0.9192785 -0.009705185 -0.3379366 0.9411138 -0.01019328 -0.3380032 0.9410988 -0.009338915 0.1337646 0.9910116 -0.001800596 0.1337944 0.9910064 -0.002349913 0.1252176 0.9921281 -0.001556396 0.1680371 0.9857798 -0.001385807 0.1785216 0.9839349 -0.0015136 0.2001753 0.9797598 -8.3544e-4 0.2143921 0.9767468 -0.001331686 0.2143061 0.9767661 -0.001001894 0.1920881 0.9813771 -0.00100708 0.1770104 0.9842087 -7.93495e-4 0.1767981 0.9842464 -0.001159727 0.1754545 0.9844865 -0.00149542 0.1764325 0.9843111 -0.001831114 0.1782296 0.9839866 -0.002166807 0.1933388 0.9811296 -0.002197325 0.1960865 0.9805851 0.001739561 0.1840283 0.9829187 0.002105772 0.1849755 0.9827417 0.001739561 0.1953819 0.9807246 0.002319395 0.1823509 0.9832301 0.002655148 0.1836929 0.9829815 0.002105772 0.1955982 0.9806769 -0.003784358 0.2015486 0.9794521 -0.007202506 0.188732 0.982023 -0.003357112 0.1843934 0.9828518 0.00125122 0.1847932 0.9827765 0.001403868 0.1958109 0.9806413 9.15574e-4 0.1846993 0.9827946 0.001068115 0.2078998 0.9781501 2.64255e-4 0.182628 0.9831821 3.05194e-4 0.1845815 0.9828169 7.93505e-4 0.181922 0.983313 1.52594e-4 0.194678 0.9808672 1.22074e-4 0.179973 0.9836716 -3.35714e-4 0.1934919 0.9811018 -4.57788e-4 0.1792668 0.9838004 -4.27262e-4 0.1775289 0.9841153 -8.54532e-4 0.2037038 0.9790313 -0.001583814 0.1913831 0.981514 -0.001648008 0.2087116 0.9779743 -0.002404451 0.178995 0.983847 -0.002441525 0.1779282 0.984038 -0.003296077 0.1925749 0.9812775 -0.003082394 0.1759139 0.9844041 -0.001739561 0.2077671 0.9781774 -0.001394152 0.08691906 0.9962123 -0.00250256 0.08670425 0.9962296 -0.003021359 0.07532149 0.9971559 -0.00262463 -0.0295422 0.9995532 -0.004547297 -0.02993869 0.9995453 -0.003570675 -0.0440393 0.9990184 -0.004791498 -0.04400879 0.9990189 -0.004974603 -0.05850476 0.9982746 -0.005005061 -0.05856585 0.9982753 -0.004059016 -0.0731849 0.9973048 -0.005218744 -0.1385862 0.9903374 -0.005066096 -0.1203655 0.9927098 -0.006286799 -0.129677 0.9915454 -0.00463891 -0.07309371 0.9973102 -0.005462944 -0.08829146 0.9960796 -0.005493402 -0.2431486 0.9699701 -0.006073355 -0.2578853 0.9661393 -0.008362174 -0.2269102 0.9738982 -0.005829155 -0.0883221 0.9960803 -0.004821956 -0.1039189 0.9945693 -0.005737662 -0.1206737 0.9926742 -0.005981802 -0.1039488 0.994564 -0.006103813 -0.1381275 0.9903921 -0.00665307 -0.1668457 0.9859679 -0.005462825 -0.1781684 0.9839851 -0.005432307 -0.1572344 0.9875373 -0.00689727 -0.284343 0.9586849 -0.008514702 -0.2935948 0.9558921 -0.008514821 -0.2646318 0.9643146 -0.008209645 -0.1573538 0.9875203 -0.006591975 -0.2015193 0.9794577 -0.0072636 -0.2011494 0.9795312 -0.007599174 -0.2113773 0.9773833 -0.006439566 -0.3430361 0.9392901 -0.007782399 -0.359031 0.9333158 -0.004303216 -0.3148008 0.9491024 -0.01025426 -0.3840521 0.9232327 -0.01205503 -0.4710588 0.882026 -0.01156663 -0.4358175 0.8999876 -0.009247362 -0.476406 0.8791995 -0.006775259 -0.5901204 0.8072345 -0.01141417 -0.5034655 0.8640123 0.002288877 -0.5512688 0.834182 -0.01559531 -0.6677541 0.7443261 -0.009125113 -0.6628792 0.7485469 -0.01638883 -0.6215254 0.7833692 -0.006256401 -0.6747496 0.7380465 -6.40904e-4 -0.7089321 0.7050562 -0.01764011 0.1829219 0.9831267 -0.001258969 0.1868569 0.9823864 -0.001234769 0.1902126 0.9817422 -0.001252233 0.193715 0.9810569 -0.001356303 0.1946447 0.9808731 -0.001220822 0.1978476 0.9802324 -9.48183e-4 0.1993057 0.9799371 -7.72435e-4 0.1991744 0.9799641 -2.03837e-4 0.1989408 0.9800114 6.22767e-4 0.1948945 0.9808215 -0.002314209 0.197914 0.9802153 0.00282824 0.1795432 0.9837409 0.004265487 0.1814839 0.9833921 -0.001901924 0.168311 0.9857329 -0.001478552 0.1749637 0.9845734 -0.001691102 0.1919348 0.9814018 0.003440678 0.1729647 0.9849179 0.004475593 0.1615796 0.9868589 -0.001264631 0.1548317 0.9879404 -0.001049816 0.1527684 0.9882506 0.004756391 0.1460151 0.989271 0.004754483 0.1414309 0.989948 -6.2152e-4 0.1394059 0.9902242 0.00469923 0.1349513 0.9908522 -4.0761e-4 0.132994 0.9911063 0.004560291 0.1258295 0.9920519 -1.83847e-4 0.1241124 0.99226 0.004054427 0.1150895 0.9933551 2.09219e-4 0.1139238 0.993484 0.003318607 0.1071015 0.994248 6.26948e-4 0.1067117 0.9942876 0.002223432 0.1038298 0.9945943 0.00126338 0.1058285 0.9943842 7.5777e-4 0.1071915 0.994238 -9.96312e-4 0.115998 0.9932471 0.002162396 0.1160027 0.9932466 0.002175509 0.1230763 0.9923924 -0.003129243 0.12968 0.991553 0.002389907 0.1341019 0.9909577 -0.004429757 0.1426836 0.989765 0.002603709 0.165719 0.9861475 -0.007093012 0.1482686 0.9889305 -0.005732357 0.1588494 0.9872988 0.002812147 0.2014058 0.9795027 0.00322324 0.1868058 0.9823607 -0.008435308 0.2278124 0.973699 0.003423392 0.211075 0.9774196 -0.00992465 0.2573941 0.9662998 0.00361216 0.2387695 0.9710109 -0.0112704 0.2890374 0.9573103 0.003796279 0.2693332 0.9629707 -0.01212859 0.3017089 0.9533151 -0.01273554 0.3220347 0.9467196 0.00396806 0.3349882 0.942135 -0.01282799 0.3681046 0.9296983 -0.01265597 0.3551532 0.934799 0.004133045 0.4002787 0.9163135 -0.01211112 0.3876909 0.9217795 0.004285812 0.4307057 0.9024228 -0.01121133 0.4187904 0.9080721 0.004432916 0.4741743 0.8804185 0.004704415 0.4477429 0.8941507 0.004571914 0.5064559 0.8622366 -0.007115602 0.4587723 0.8884968 -0.01007407 0.549288 0.8356167 0.0052374 0.5699401 0.8216612 0.006418883 0.5652869 0.824886 0.003719031 0.5530371 0.8331341 0.006129086 0.561725 0.8272703 0.009439229 0.3611941 0.9322685 0.02035623 0.5269755 0.8497774 0.01324534 0.3733151 0.9275501 0.01693832 0.5373642 0.8433246 0.006596684 0.3242708 0.9455584 0.02771174 0.5015081 0.8648077 0.0244413 0.1872968 0.9818663 0.02929848 0.183265 0.9826122 0.02978628 0.1856148 0.9824588 0.01794499 0.1981908 0.9790213 0.04730457 0.1981924 0.9793953 0.03879004 0.1993482 0.979162 0.03875875 0.1992274 0.9798095 0.01678538 0.1986791 0.9800588 0.00338757 0.2023438 0.9793077 0.003692805 0.1932496 0.9680488 -0.1598002 0.1807366 0.9708569 -0.1573892 0.1784121 0.9669231 -0.182288 0.1809498 0.9682906 -0.1722518 0.1922708 0.9644063 -0.1815281 0.1803047 0.9643617 -0.1936414 0.191814 0.9605962 -0.2011529 0.1789026 0.9627841 -0.2025853 0.1895205 0.956728 -0.2208021 0.1772532 0.9581685 -0.2247099 0.1799388 0.960091 -0.2141199 0.1776847 0.9540408 -0.2413179 0.1865946 0.9561985 -0.2255372 0.1895844 0.9529581 -0.2364923 0.1821091 0.9520516 -0.2458335 0.1884551 0.9492336 -0.2518736 0.1757915 0.9498237 -0.2587127 0.1883368 0.9455905 -0.2653074 0.1756057 0.9455974 -0.2738765 0.1827201 0.9483317 -0.259385 0.1749364 0.9416719 -0.2874915 0.1772245 0.9439563 -0.2784564 0.1873582 0.942132 -0.2780007 0.1804898 0.9405678 -0.2876729 0.1898618 0.9388411 -0.2872801 0.1754879 0.9376856 -0.2999165 0.1904392 0.9368453 -0.2933497 0.1779848 0.9356412 -0.3047899 0.1771943 0.936847 -0.3015294 0.1687713 0.9320878 -0.320513 0.184181 0.9356766 -0.3009766 0.1875129 0.9362216 -0.2972006 0.1768572 0.9347038 -0.3083024 0.1775308 0.9354168 -0.3057424 0.1909302 0.9390251 -0.2859681 0.1704196 0.9371857 -0.3043686 0.1781408 0.9356893 -0.3045515 0.1956915 0.9463813 -0.2570358 0.1831139 0.9428229 -0.2784857 0.1746296 0.9453257 -0.2754338 0.2075774 0.9782173 -0.001630961 0.2067167 0.9783997 -0.001538395 0.2076897 0.9781945 -8.77358e-4 0.2074557 0.9782443 -4.47996e-4 0.2068206 0.9783784 9.95582e-4 0.2109478 0.9774951 0.002105772 0.2104271 0.9776086 0.001373291 0.2106438 0.9775619 0.001403868 0.2070488 0.9783286 0.001988172 0.2072914 0.9782771 0.002039432 0.2070945 0.9783174 0.002632319 0.2073543 0.9781947 -0.01181215 0.2049346 0.9787728 0.002410948 0.2117716 0.9748085 0.07001066 0.2064638 0.9748508 0.08389782 0.2061873 0.9757582 0.07336801 0.2065713 0.9742501 0.09036105 0.2071009 0.9761605 0.06496149 0.2099745 0.9756795 0.06293129 0.2070649 0.9761696 0.06493902 0.2066394 0.9760472 0.06805837 0.2080904 0.975858 0.06632995 0.2099106 0.9758496 0.06045842 0.2104571 0.9754396 0.06500488 0.207174 0.9759409 0.06795978 0.2100335 0.9761583 0.05478203 0.2101218 0.9765094 0.04773133 0.2101249 0.9768902 0.03915613 0.2072184 0.9762547 0.06314694 0.2102447 0.9772152 0.02911502 0.2102745 0.9774865 0.01745671 0.2090875 0.9717947 -0.1090759 0.2086625 0.9689056 -0.1329739 0.2103087 0.9776259 0.004242181 0.2103698 0.9775649 -0.01055967 0.2104264 0.9772391 -0.02691745 0.2102756 0.9766066 -0.04498493 0.2100349 0.9755547 -0.06464022 0.2095415 0.974005 -0.08606278 0.2078638 0.9656162 -0.1561344 0.207013 0.9621239 -0.1773787 0.2063993 0.9585378 -0.1964807 0.2056093 0.9549834 -0.2138496 0.2046628 0.9515021 -0.2296887 0.198011 0.9560867 -0.2160785 0.2038995 0.9481129 -0.2439408 0.2031642 0.9448649 -0.2568165 0.1520481 0.9479049 -0.2799248 0.178173 0.9476011 -0.2651538 0.2025893 0.9418972 -0.2679319 0.2282537 0.972009 -0.05566716 0.221144 0.9704275 -0.0967772 0.1983128 0.9365941 -0.2889006 0.1726133 0.9849888 -0.001342773 0.1250048 0.9494997 -0.2877919 0.2101227 0.9776733 -0.001831114 0.2129311 0.977066 -0.001586973 0.2133871 0.9769666 -0.001495361 0.2099416 0.9777132 -0.001281797 0.2130541 0.9770398 -0.001098632 0.2069954 0.9783415 -9.95803e-4 0.2076897 0.9781947 -3.98852e-4 0.213966 0.9768397 -0.001647949 0.2103981 0.9776157 -7.01937e-4 0.207224 0.9782936 1.35643e-4 0.2132645 0.9769945 1.22075e-4 0.2092101 0.9778707 -3.35713e-4 0.2105502 0.977583 4.57784e-4 0.2080493 0.9781176 0.001222133 0.2123814 0.9771867 -5.7986e-4 0.2101225 0.9776723 0.002319395 0.2092382 0.9778593 -0.003234982 0.2074782 0.9782358 0.002752304 0.2056977 0.9785904 -0.00701934 0.2091194 0.9750971 0.07385706 0.2110059 0.9751319 0.06778192 0.2101214 0.975409 0.06653082 0.2029504 0.9386988 -0.2786676 0.200756 0.9385603 -0.2807165 0.2042655 0.973107 -0.1064817 0.2136911 0.9769002 -0.00154978 0.21393 0.9768478 -0.00157094 0.2001706 0.9797602 -0.00132966 0.2137047 0.9768978 -0.001099407 0.2149021 0.9766321 -0.002632141 0.2134585 0.9769521 1.10197e-4 0.213528 0.9769365 9.93724e-4 0.2138229 0.9768723 4.98107e-4 0.2037617 0.9790064 -0.005264043 0.2046607 0.977159 0.0572232 0.2088735 0.9759433 0.06250333 0.2133314 0.9739178 0.07729166 0.2085397 0.9759832 0.06299221 0.2107931 0.9752578 0.06662243 0.2131149 0.9748498 0.06519216 0.2130805 0.9746642 0.06801879 0.2107659 0.975334 0.06558585 0.2085981 0.9761235 0.06058043 0.2087208 0.9764312 0.0549345 0.212967 0.9746921 0.06797361 0.2086298 0.9768307 0.04770159 0.212695 0.975085 0.06300956 0.2088713 0.9771541 0.03927779 0.2089627 0.9774892 0.02914547 0.2106105 0.975443 -0.06445574 0.2082911 0.9742838 -0.08594107 0.2090278 0.9777523 0.01754868 0.2089331 0.9779205 0.004303157 0.2089063 0.977877 -0.01071232 0.210949 0.9771348 -0.02661275 0.2106399 0.9765366 -0.04480141 0.2078669 0.9720394 -0.1092285 0.2091458 0.9688521 -0.1326045 0.2084751 0.9655287 -0.1558604 0.2059408 0.962349 -0.1774057 0.2069206 0.9585186 -0.1960252 0.2061283 0.9549534 -0.2134835 0.2035639 0.9517453 -0.229658 0.202528 0.9483355 -0.2442178 0.2019767 0.9450605 -0.2570335 0.2002356 0.9420625 -0.2691171 0.2009077 0.9489631 -0.2431157 0.2023711 0.959546 -0.1957485 0.1994428 0.9393498 -0.2790063 0.1991084 0.9375857 -0.285112 0.2063993 0.9784666 -0.00149542 0.211346 0.9774106 -0.00125128 0.2114688 0.9773836 -0.001556456 0.2064287 0.9784613 -8.85043e-4 0.211317 0.9774172 -8.85065e-4 0.2132019 0.9770081 -4.42488e-4 0.2141752 0.9767953 -1.04665e-4 0.2113753 0.977405 -2.13634e-4 0.2064934 0.978448 -3.05193e-5 0.2134763 0.9769483 1.15377e-4 0.2107315 0.9775438 5.18818e-4 0.2065517 0.9784352 0.001037597 0.2065514 0.9784334 0.00213629 0.213716 0.9768929 0.002408087 0.2106727 0.9775543 0.002166807 0.2063985 0.9784627 0.003234982 0.2039615 0.9789726 0.003540217 0.2052689 0.9787049 -0.001220703 0.2056057 0.9768791 0.05859625 0.2059425 0.976304 0.06647044 0.2055187 0.9764735 0.06528133 0.2046334 0.9766553 -0.0653423 0.2050257 0.9783737 -0.0273754 0.2048723 0.9777291 -0.04553395 0.2032899 0.969938 -0.1337667 0.202525 0.9665718 -0.1572346 0.201151 0.9594271 -0.1975802 0.2002348 0.9557622 -0.2154638 0.1995655 0.9423435 -0.2686306 0.2067039 0.9784023 -0.001586973 0.2044187 0.9788823 -0.001641571 0.2043021 0.9789072 -0.0011487 0.2040709 0.9789555 -0.001168251 0.2050558 0.9787503 -4.4999e-4 0.203486 0.9790779 -2.36152e-4 0.2042903 0.9789103 4.82599e-4 0.2053686 0.9786834 0.001616775 0.2035681 0.9790599 0.001304626 0.2043573 0.9788933 0.002471327 0.2041359 0.9789337 0.004184186 0.20186 0.9780144 0.05234801 0.2035394 0.9774738 0.05582791 0.2012724 0.9775216 0.06277745 0.2027678 0.9769724 0.06640917 0.2041628 0.9768168 0.06439286 0.2040561 0.9765737 0.06830149 0.2037819 0.9767921 0.06595551 0.201057 0.9774828 0.06405866 0.2012744 0.9776843 0.06018394 0.2026941 0.9769011 0.06767106 0.202708 0.9777108 0.05469024 0.2015506 0.9783322 0.0473662 0.2027065 0.9784662 0.03891158 0.2021294 0.9789378 0.02871865 0.2025862 0.9791158 0.01706022 0.2016701 0.9793878 -0.01135307 0.2013654 0.9732865 -0.1102962 0.2007529 0.9757485 -0.08725333 0.1991649 0.9634751 -0.1790226 0.1971548 0.9525688 -0.2318247 0.1955065 0.9490583 -0.2471147 0.1947765 0.9456518 -0.2603937 0.1955719 0.9370062 -0.2894323 0.2014783 0.9794917 -0.001645386 0.2020503 0.9793739 -0.001590013 0.2013993 0.9795083 -0.001334488 0.2023573 0.9793111 -0.001156389 0.2005289 0.9796875 -8.34465e-4 0.2046987 0.978825 5.34081e-4 0.2018017 0.9794263 5.39216e-4 0.2011998 0.9795475 0.002337515 0.2042037 0.9789255 0.00243473 0.2020866 0.9793512 0.005680084 0.2017021 0.9777774 0.05716264 0.201054 0.9773822 0.06558525 0.2008347 0.9772908 0.06758803 0.2006361 0.9773498 0.06732511 0.2003877 0.9793239 -0.02774173 0.2003897 0.9786319 -0.0460841 0.2000806 0.9775449 -0.06613403 0.1980096 0.9673724 -0.1580598 0.1987709 0.970752 -0.1346503 0.1958121 0.9564155 -0.2166264 0.1966036 0.9600984 -0.1988925 0.1933111 0.9380807 -0.287464 0.1932151 0.9424844 -0.2727473 0.1927277 0.9395285 -0.2830945 0.1924551 0.9375246 -0.2898425 0.1941335 0.9368201 -0.2909989 0.2001711 0.9797596 -0.001625776 0.1998759 0.9798207 -0.001119554 0.200135 0.9797674 -0.001340389 0.2022652 0.9793308 -1.69063e-4 0.2002121 0.9797523 -8.30931e-4 0.201909 0.9794043 -2.37091e-4 0.2014229 0.9795043 4.75531e-4 0.2023854 0.979305 0.001385033 0.2021037 0.9793633 0.00131148 0.2006519 0.9796609 0.001849412 0.1988547 0.9800276 0.001657068 0.1991342 0.9784586 0.05444526 0.1979468 0.9739253 -0.1108453 0.1959043 0.9640176 -0.1796984 0.1935811 0.9530122 -0.2330114 0.1935249 0.9480005 -0.252672 0.1916601 0.9413929 -0.2775714 0.1994822 0.9799002 -0.00163269 0.1997488 0.9798458 -0.001658797 0.1995164 0.9798935 -0.001415133 0.1995056 0.9798964 -7.46435e-4 0.200176 0.9797599 -3.68379e-4 0.1999489 0.9798062 5.29764e-4 0.1994808 0.9798995 0.002088189 0.1995441 0.9798861 0.002326607 0.1996509 0.9798658 0.001649618 0.2002211 0.9797474 0.002576649 0.1997808 0.9781539 0.05746853 0.1993797 0.978317 0.05606782 0.1986498 0.9800038 -0.01144468 0.198559 0.9796717 0.02859663 0.1936728 0.9583538 -0.2098783 0.1988629 0.9800268 -0.001076281 0.1988455 0.9800307 -6.83861e-4 0.1994353 0.979911 -2.98512e-4 0.1996738 0.9798623 6.04122e-4 0.1992107 0.9799561 0.001111149 0.1997127 0.9798531 0.001685678 0.1993541 0.9799269 0.001138985 0.1999436 0.9798029 0.002991557 0.1990745 0.9781906 0.05926758 0.198468 0.9797052 -0.0280779 0.1980716 0.9790964 -0.04623705 0.1982188 0.9779406 -0.06588983 0.1959648 0.9677688 -0.1581818 0.1965442 0.9711544 -0.1350173 0.193767 0.9567492 -0.2169921 0.1945268 0.9604267 -0.1993488 0.1909595 0.942651 -0.2737585 0.1902248 0.9396793 -0.2842842 0.1895828 0.9376291 -0.2913935 0.1903911 0.9367963 -0.2935371 0.1990832 0.9799813 -0.001668512 0.1991773 0.9799622 -0.001645326 0.1990631 0.9799857 -0.001422941 0.1992034 0.9799572 -0.001375854 0.1992324 0.9799517 -0.001122176 0.1991671 0.979965 -0.001074969 0.19913 0.9799729 -6.97187e-4 0.1992481 0.9799491 -1.69235e-4 0.1992582 0.9799471 1.75678e-4 0.1989519 0.9800091 6.2033e-4 0.1995572 0.9798817 0.00299853 0.1987939 0.9778887 0.06492179 0.1981307 0.9781711 0.06265592 0.1986767 0.9777495 0.06733256 0.1986811 0.9779498 0.06434363 0.198648 0.9777641 0.06720501 0.1986557 0.9777013 0.06809133 0.1987484 0.9778486 0.06566143 0.1988323 0.9780459 0.06238567 0.1984677 0.9782691 0.06000113 0.191598 0.9459658 -0.2616086 0.1991485 0.9799692 4.96254e-4 0.1991162 0.9799725 0.002626955 0.1986646 0.9776976 0.06811654 0.1987872 0.9778293 0.06583011 0.1988459 0.9780394 0.06244409 0.1981273 0.9786732 0.05426222 0.1971862 0.9764398 -0.0876519 0.1918098 0.9495272 -0.2482082 0.1987673 0.9800453 -0.001640439 0.1986738 0.980065 -0.001237332 0.1987672 0.9800457 -0.001460313 0.1975749 0.9802871 -0.001206159 0.1988587 0.9800272 -0.001424133 0.198683 0.9800634 -9.42654e-4 0.1987653 0.980047 -6.36239e-4 0.1988213 0.9800359 -2.61455e-4 0.1986765 0.9800637 0.001635432 0.1988613 0.9800243 0.002576649 0.1980931 0.9785186 0.0571025 0.1984052 0.9783766 0.05843526 0.1975506 0.9785362 0.05865782 0.1972445 0.9802107 0.01678544 0.1890042 0.9381238 -0.2901747 0.1984182 0.9801161 -0.001679778 0.198686 0.9800626 0.001051962 0.1988909 0.9800209 0.0012331 0.1987702 0.9800447 0.001702547 0.1988689 0.9800239 0.002093195 0.1987195 0.9800534 0.002449393 0.1981234 0.9801725 0.002997875 0.1972124 0.9802941 -0.0114445 0.1965145 0.9801006 -0.0280168 0.1965729 0.9742278 -0.1106314 0.1900436 0.936948 -0.2932777 0.198082 0.9801841 -0.001631021 0.1982393 0.9801526 -0.001463711 0.1980131 0.9801985 -0.001325011 0.1980459 0.9801924 -9.45255e-4 0.1981623 0.9801685 -0.001240074 0.1982554 0.9801503 -6.22066e-4 0.1983039 0.9801406 -1.93273e-4 0.1980507 0.9801914 -9.47286e-4 0.1980028 0.9802015 -4.33254e-4 0.1982977 0.9801418 5.01347e-4 0.1982941 0.980142 0.00105375 0.1979827 0.9802055 9.48487e-5 0.1980277 0.9801962 7.16602e-4 0.1984236 0.9801149 0.00170511 0.1979483 0.9802116 0.001330256 0.1983964 0.9801188 0.002461969 0.1980403 0.9801918 0.002013087 0.1984403 0.9801083 0.003034889 0.1878153 0.9822021 -0.002117097 0.1595256 0.9871827 0.004705071 0.1662743 0.9860687 0.004622161 0.1859419 0.9825525 0.004012703 0.1480965 0.9889726 -8.36836e-4 0.1934695 0.9794074 0.05771374 0.2031347 0.977891 0.04965442 0.2205303 0.9745327 0.04065126 0.1978341 0.9782066 0.06303548 0.2900699 0.9558065 0.04788899 0.1971836 0.9785326 0.05993938 0.1940119 0.9643833 -0.1797899 0.1917551 0.9533125 -0.2332924 0.1978281 0.9802365 7.17265e-4 0.1978091 0.9802324 0.00399065 0.1978241 0.9802302 0.003803074 0.1976242 0.9802696 0.004056274 0.1984901 0.9800962 0.003618836 0.1976964 0.9802552 0.004004657 0.1977756 0.9802396 0.003895461 0.1977717 0.9802447 0.00259453 0.1979002 0.9802144 0.00388807 0.1976245 0.9802773 -0.00101912 0.1978768 0.9802237 0.002512991 0.1783775 0.9839576 0.003021061 0.1978299 0.980158 -0.01240068 0.1975625 0.9801825 0.01454544 0.1964216 0.9798802 0.03540223 0.195718 0.979811 0.04080379 0.195966 0.9788839 0.05817019 0.1968166 0.9789257 0.05447632 0.1970321 0.9796367 0.03860682 0.1965702 0.9800736 0.02856534 0.1969365 0.9804102 0.003448545 0.1919355 0.9570837 -0.2171444 0.1930658 0.9607206 -0.1993528 0.1883671 0.9483361 -0.2552966 0.1923009 0.9733768 -0.1247316 0.1976958 0.980262 -0.001681089 0.1978262 0.9802358 -0.001643419 0.1975945 0.9802828 -0.001490533 0.1978191 0.9802377 -0.001326203 0.1977502 0.9802524 -4.33756e-4 0.1975492 0.9802926 -7.94596e-4 0.1978703 0.9802283 9.48933e-5 0.1974494 0.9803131 -1.72587e-4 0.1977221 0.9802573 0.001331627 0.1974706 0.9803088 4.34263e-4 0.1978154 0.9802373 0.002015173 0.1976571 0.9802708 9.34934e-4 0.1979708 0.9802069 0.001431822 0.197964 0.9802052 0.002822458 0.1976761 0.9802655 0.001927435 0.1975849 0.9802827 0.002506256 0.1970795 0.9803826 0.003122687 0.197969 0.9802021 0.00347191 0.197758 0.9802458 0.003144919 0.1976628 0.9802687 0.001610994 0.1984772 0.9800978 0.003882288 0.1976794 0.9802667 4.35476e-4 0.1975443 0.9802907 -0.002549886 0.1977499 0.980251 0.001714944 0.1976934 0.9802549 -0.00422275 0.1975171 0.9802995 2.5186e-4 0.1974917 0.9802901 -0.005325436 0.1978456 0.9802126 -0.006366252 0.1974167 0.980319 -0.001256406 0.1977009 0.9802259 -0.008466422 0.1974766 0.9802584 -0.009834825 0.1976174 0.9802178 -0.01097917 0.1975818 0.9802766 -0.004386723 0.1975101 0.9802298 -0.01180374 0.1976813 0.9801852 -0.01261752 0.1976938 0.9802417 -0.006596624 0.1975664 0.9802599 -0.007619678 0.1976861 0.9801842 -0.01261574 0.1975181 0.9802223 -0.01228457 0.1976143 0.9802107 -0.01165348 0.1976621 0.9802099 -0.01088213 0.1973317 0.9803187 -0.005953907 0.197676 0.9801874 -0.01252675 0.1975346 0.9802194 -0.01224637 0.1975902 0.9802839 -0.001287162 0.1974787 0.9802467 -0.01088958 0.1975814 0.9802781 0.00405693 0.1975787 0.9802608 0.007166922 0.1975703 0.9802304 0.01070326 0.1965135 0.980279 0.02087515 0.1958124 0.9803134 0.02536159 0.197549 0.9801155 0.01865577 0.1975865 0.9802851 8.02568e-4 0.1965135 0.9800346 0.03024458 0.1975696 0.9802629 0.00713098 0.1975688 0.9802307 0.01069551 0.1963918 0.9794262 0.04641985 0.1975588 0.9801835 0.01452684 0.1963002 0.9791509 0.05224901 0.1975493 0.9801154 0.01865863 0.1962966 0.9785231 0.06292968 0.1972863 0.9781049 0.06624937 0.1972851 0.9782301 0.06437736 0.1959606 0.9794673 0.047365 0.1943773 0.9809203 0.003601253 0.1944952 0.9808379 -0.01135289 0.1973392 0.9783765 0.06194186 0.1962693 0.9783255 -0.06601315 0.1941049 0.9681133 -0.1583663 0.1896755 0.9463024 -0.2617919 0.1890372 0.9429584 -0.2740339 0.196842 0.9804345 -0.001208662 0.197263 0.9803506 4.34692e-4 0.1974764 0.9803026 0.003147065 0.1974359 0.9803076 0.004028558 0.1976003 0.9802755 0.003764867 0.1965167 0.9804809 -0.006193816 0.1976601 0.9802678 -0.002378046 0.1965858 0.9804115 -0.01214522 0.1977353 0.9802196 -0.008405029 0.1973192 0.9802823 -0.01058447 0.1974716 0.9802624 -0.009524345 0.1973388 0.9803343 0.001473188 0.1972674 0.9803148 -0.008285522 0.1973344 0.9803265 -0.004372119 0.1973274 0.980332 0.003359198 0.1932156 0.9791401 0.06286907 0.1969912 0.9782303 0.0652697 0.1969767 0.9780929 0.06734025 0.1969662 0.9780458 0.06804877 0.1933402 0.9807096 0.02877974 0.1943782 0.9801619 0.03872913 0.1969636 0.9780992 0.06728619 0.1971555 0.9780329 0.06768554 0.1970988 0.9781773 0.06573748 0.1957191 0.9795724 -0.04617542 0.1941292 0.9716532 -0.134923 0.1948032 0.9745658 -0.1107842 0.1879067 0.9400525 -0.2845916 0.19665 0.9804722 -0.001756489 0.1968138 0.9804399 -0.001496255 0.1970505 0.9803919 -0.001679122 0.1968773 0.9804272 -0.001474499 0.1968476 0.9804334 -0.001210451 0.1970133 0.9804009 -9.47558e-5 0.1968525 0.9804328 -9.48777e-4 0.1965208 0.9804998 -1.48456e-4 0.196779 0.9804474 9.38936e-4 0.1967795 0.9804468 0.001440167 0.1966432 0.9804732 0.00193715 0.1965811 0.9804873 7.99943e-4 0.1969178 0.9804168 0.002514421 0.1967704 0.9804486 0.001445055 0.1969739 0.9804065 0.002089083 0.1969017 0.9804201 0.00252825 0.196603 0.9804751 0.003995597 0.1972211 0.9803541 0.003131806 0.1958215 0.9806331 0.003553688 0.1967269 0.9804551 0.002533495 0.1971824 0.9803625 0.002895355 0.1965627 0.9804906 0.001252532 0.1970156 0.9803699 -0.007736921 0.1968109 0.9803605 -0.01260125 0.1970183 0.9803943 -0.003307819 0.1970117 0.9803758 -0.007056355 0.194682 0.980399 0.03027504 0.1970119 0.9803968 -0.002899885 0.1963255 0.9785 0.06319922 0.1950166 0.9789593 0.06006145 0.1945294 0.9769809 -0.08755958 0.1876001 0.9417238 -0.279218 0.1892494 0.9500316 -0.248243 0.1959446 0.9806138 -0.001546144 0.195717 0.9806599 -0.001124143 0.1954464 0.9807143 -5.70759e-4 0.1955605 0.9806907 0.001454055 0.1966166 0.980475 0.003290534 0.1956684 0.9806663 0.002740085 0.1961885 0.9805586 0.003874123 0.1966264 0.9804706 0.003954768 0.1957765 0.9806485 2.64935e-4 0.1962589 0.9805518 -7.97823e-4 0.1960337 0.980593 -0.002873003 0.1965127 0.9804621 -0.008771538 0.1953286 0.9807376 -6.6881e-4 0.1953122 0.9806825 0.01073026 0.1955032 0.9806661 -0.008516192 0.1852831 0.981503 0.04819005 0.1854633 0.9818537 0.03958296 0.1884558 0.9809167 0.04782354 0.1955392 0.978309 0.06838136 0.1941317 0.9794481 0.05472064 0.194468 0.9807631 0.01690757 0.1955797 0.9784976 0.06550556 0.1914764 0.9752665 -0.1104179 0.1907449 0.9777432 -0.08737641 0.1905914 0.9612277 -0.1992893 0.191294 0.9649547 -0.1796357 0.1869904 0.9380348 -0.2917625 0.1884279 0.9369524 -0.2943047 0.1890951 0.9538376 -0.233317 0.1859839 0.9385567 -0.2907258 0.195962 0.9806101 -0.00165683 0.1957167 0.9806594 -0.001517534 0.1955716 0.9806892 -7.76519e-4 0.1954435 0.9807142 -0.001217365 0.1954699 0.9807097 -1.62357e-4 0.1954436 0.9807146 -8.31323e-4 0.1954894 0.9807057 -5.10188e-4 0.1954465 0.9807143 -1.76107e-4 0.1956892 0.9806656 8.13278e-4 0.1950832 0.9807868 1.48658e-4 0.1951765 0.980768 5.61588e-4 0.1955875 0.9806841 0.002104043 0.1954253 0.9807181 0.00100094 0.1952331 0.9807554 0.001699209 0.1954076 0.9807195 0.002295792 0.1954098 0.9807135 0.004003167 0.1956151 0.9806771 0.002731263 0.1951252 0.9807753 0.002453804 0.1948008 0.9808365 0.003542244 0.1955721 0.9806877 0.001783609 0.1958224 0.980635 0.002930521 0.1956256 0.9806755 -0.00248593 0.1956406 0.9806661 -0.004324734 0.1953935 0.9807249 -9.56383e-5 0.1950391 0.9807717 -0.006832718 0.195743 0.9806544 -0.001285672 0.1956947 0.9806292 -0.008383333 0.1956382 0.9806163 -0.01084065 0.1956556 0.9806632 -0.004313647 0.1953436 0.9806561 -0.01243066 0.1956655 0.9806519 -0.00607711 0.1955531 0.9806146 -0.01241952 0.1956604 0.980612 -0.01082026 0.1954231 0.9806392 -0.012515 0.1945109 0.9808958 0.002990126 0.1952643 0.9806792 -0.01184743 0.1955358 0.9806358 -0.01092034 0.1952859 0.9807356 0.00462073 0.1953046 0.980716 0.007224082 0.195315 0.9806321 0.01459127 0.1952843 0.980569 0.01867181 0.1953288 0.9807378 2.06044e-4 0.19358 0.9804434 0.03546267 0.1952882 0.9807196 0.007176876 0.1952945 0.9806864 0.01069205 0.1934617 0.9800047 0.04651135 0.1953016 0.9806353 0.0145542 0.1941017 0.9795727 0.05255395 0.1952992 0.9805654 0.01870203 0.1937071 0.9808347 0.02099734 0.1948876 0.9785525 0.06673759 0.1948984 0.9787262 0.06410801 0.1904667 0.9812655 0.02899265 0.1902552 0.9815816 0.01733475 0.1904081 0.9816439 -0.01095628 0.1902832 0.9817212 0.003967404 0.1934276 0.9807189 -0.02786356 0.1949488 0.978874 0.06165087 0.1931836 0.9789498 -0.06585943 0.1911119 0.9687438 -0.158151 0.1887887 0.9577379 -0.2170184 0.187646 0.9372347 -0.2939051 0.1867173 0.9469236 -0.2616728 0.1860768 0.9435381 -0.2740643 0.1949365 0.9808144 -0.001712918 0.1946447 0.9808725 -0.001597821 0.1945304 0.9808952 -0.001621603 0.1937723 0.9810466 1.49105e-4 0.1942442 0.9809466 0.00362724 0.1946832 0.9808584 0.003925323 0.1948755 0.9808237 0.002895534 0.1954457 0.9807131 0.001695811 0.1950349 0.9807573 -0.008745491 0.1937554 0.9809848 -0.01129853 0.193755 0.980979 -0.01180732 0.1945206 0.9808858 -0.004989087 0.1951795 0.9807108 -0.01055794 0.1945213 0.980884 -0.005310118 0.1945098 0.9808987 0.001941502 0.192512 0.980963 0.02551364 0.1902547 0.9799918 0.05847412 0.1893111 0.9798828 0.0631749 0.1927886 0.9795074 0.05829125 0.1928524 0.9803765 0.04086554 0.1944924 0.9785608 0.06776016 0.1943221 0.9787675 0.0652166 0.1946208 0.9785552 0.06747335 0.1924535 0.980152 0.04757928 0.1883322 0.9799315 -0.06531041 0.1922105 0.9802798 -0.045901 0.1906546 0.9723784 -0.1346516 0.1843985 0.9407925 -0.2844412 0.1876607 0.9593618 -0.210733 0.1942822 0.9809444 -0.001620173 0.1915934 0.9814733 -0.00145328 0.1936472 0.9810709 -8.50596e-4 0.1940538 0.9809902 -0.001175403 0.1938255 0.9810361 -8.35271e-5 0.1936823 0.981064 -8.39286e-4 0.1939892 0.9810036 -5.1425e-4 0.1936178 0.981077 -1.77731e-4 0.1938445 0.981032 7.55206e-4 0.1937741 0.9810462 1.4962e-4 0.1941229 0.9809771 5.64893e-4 0.1937814 0.9810419 0.002391457 0.1941324 0.9809737 0.001831591 0.1934103 0.9811152 0.002320528 0.1934624 0.9810993 0.004071056 0.1939905 0.9810023 0.001497745 0.1946042 0.9808753 0.003600835 0.192361 0.9813241 -5.44449e-4 0.1935679 0.9810832 0.002672314 0.1930003 0.9811967 -0.002016901 0.1940609 0.9809822 -0.003798007 0.1940078 0.9809844 -0.005533635 0.1944255 0.9809174 1.49915e-4 0.1949225 0.9808181 -0.001081764 0.1937565 0.9810456 -0.002848207 0.193598 0.9810718 -0.004259884 0.1931286 0.981152 -0.006498098 0.1935979 0.9810028 -0.01239705 0.1937617 0.9810121 -0.008473455 0.1928003 0.9811919 -0.009516716 0.1944774 0.9808459 -0.01095116 0.1937417 0.9809943 -0.01069229 0.193782 0.9810201 -0.006945133 0.1937527 0.9809727 -0.01235055 0.1936466 0.9810666 -0.003072321 0.19374 0.9809817 -0.01182103 0.1938604 0.9810013 -0.007406234 0.1936461 0.9810668 -0.003029525 0.190349 0.9808605 0.04098743 0.1902536 0.9806268 0.04663252 0.1918741 0.9809478 0.03042763 0.1918709 0.9795582 0.06042695 0.1934433 0.9790456 0.06363505 0.1890055 0.9809184 -0.04556518 0.1882094 0.9759609 -0.1098982 0.1854968 0.9734766 -0.133919 0.1854373 0.9508697 -0.247911 0.1852697 0.9375252 -0.2944856 0.1927942 0.9812376 -0.00179249 0.1914435 0.9815026 -0.001427531 0.1921916 0.9813574 4.02765e-4 0.1916012 0.9814722 0.001134514 0.1926397 0.9812688 0.001237511 0.1924628 0.9813028 0.001763463 0.1933097 0.9811375 8.42586e-4 0.1917521 0.9814398 0.002640128 0.1926164 0.9812707 0.002601325 0.1928331 0.9812303 0.001563549 0.1925189 0.9812887 0.002975285 0.193305 0.9811357 0.002421557 0.1927147 0.981247 0.003937304 0.1917164 0.9814432 0.003778696 0.1930668 0.9811787 0.003692626 0.1926595 0.981261 0.003069877 0.1933654 0.9811182 0.004146575 0.1931691 0.9811655 2.68962e-4 0.1917134 0.981444 -0.003738105 0.1927239 0.9812511 0.00197345 0.1913757 0.9814578 -0.01076924 0.1935647 0.9810501 -0.008581221 0.1913353 0.9814605 -0.01123887 0.1910365 0.9815631 -0.006239295 0.1919266 0.9813798 0.007608175 0.1930204 0.9811424 -0.01013469 0.1914475 0.9800965 0.05252367 0.1923104 0.9789606 0.06821262 0.1931971 0.9789581 0.06569606 0.1924173 0.9791266 0.06547337 0.1898884 0.980266 0.05496442 0.1901049 0.9809826 0.03915625 0.1924838 0.9789202 0.06830424 0.1872662 0.9658125 -0.1792701 0.1865912 0.9621012 -0.1988596 0.1835414 0.9387348 -0.2917009 0.1850078 0.9547649 -0.232801 0.1825646 0.9428843 -0.2786384 0.1817749 0.9395776 -0.2900892 0.1917259 0.9814471 -0.001694142 0.1915188 0.9814885 -9.94638e-4 0.1915612 0.9814805 -6.32099e-4 0.1921589 0.9813635 -8.46807e-4 0.1916576 0.9814619 8.0884e-5 0.1913431 0.9815229 8.28199e-4 0.1918904 0.9814164 -3.41999e-5 0.1909298 0.9816021 0.001821935 0.192367 0.981323 4.17762e-4 0.1917528 0.9814415 0.001857519 0.1914799 0.9814931 0.002618014 0.1917161 0.9814419 0.004104018 0.1916938 0.9814532 0.001739323 0.1917018 0.9814477 0.003321051 0.1914556 0.9815011 -5.75271e-4 0.1913788 0.9815138 -0.002225399 0.1917128 0.9814508 8.00942e-4 0.1917239 0.9814323 -0.005712687 0.1916359 0.9814661 -4.42033e-4 0.1917137 0.981449 -0.001977622 0.1909002 0.9815424 -0.01147317 0.1917246 0.9814417 -0.003728508 0.1914967 0.9814757 -0.005879342 0.1918678 0.981342 -0.01244062 0.1913768 0.9814826 -0.008180439 0.1920974 0.9813162 -0.01082456 0.1915022 0.9814281 -0.01122164 0.1920912 0.9812992 -0.01236236 0.1916291 0.981397 -0.01175957 0.1919457 0.9814056 2.78824e-5 0.191774 0.9813793 0.0108366 0.1917712 0.9813348 0.01435273 0.1919251 0.9812296 0.01879644 0.1919474 0.9814052 -4.84108e-4 0.1905589 0.9814519 0.02096635 0.1871442 0.9814694 0.04117047 0.1871425 0.9812166 0.04681611 0.1919337 0.9813954 0.004965484 0.1917873 0.9814097 0.00725913 0.1903481 0.9810694 0.03564637 0.1917837 0.9813771 0.01085859 0.1887306 0.9806119 0.05273711 0.1919347 0.981298 0.01467978 0.1936115 0.9809368 0.01666325 0.187082 0.9799422 0.06865572 0.1913844 0.9793974 0.06444245 0.1915807 0.9795188 0.06196564 0.1915142 0.9791901 0.06715083 0.1886716 0.9816603 -0.02731496 0.1834476 0.9826701 -0.0265817 0.1853409 0.9816386 -0.04510682 0.1842109 0.9767818 -0.109379 0.1865321 0.9697108 -0.1576917 0.1842117 0.9587802 -0.2163481 0.1841616 0.9379141 -0.2939415 0.1820756 0.9480384 -0.2609059 0.1813756 0.9446306 -0.2734521 0.1903349 0.9817175 -0.001821339 0.1787727 0.9838887 -0.001853585 0.1908168 0.9816242 -0.001731395 0.1893482 0.9819088 -0.001587867 0.1886509 0.9820432 -0.001424193 0.1902957 0.9817256 -0.001579105 0.1885091 0.9820711 -8.86798e-4 0.1902137 0.9817425 -7.91983e-4 0.1908548 0.9816173 -0.001432418 0.1908417 0.9816203 -9.98518e-4 0.1902314 0.9817391 6.8579e-4 0.1910347 0.9815833 1.28243e-4 0.189115 0.9819521 0.002368748 0.1904802 0.9816879 0.002524793 0.1909306 0.9816027 0.001333057 0.1897978 0.9818172 0.003428578 0.1907265 0.9816417 0.001743316 0.1909251 0.9816009 0.002692937 0.1906987 0.9816405 0.004024684 0.1902102 0.9817389 0.002981305 0.1886247 0.9820477 0.001707255 0.1908828 0.9816047 0.004011929 0.1904813 0.9816908 3.63827e-4 0.1886997 0.9820323 -0.002282857 0.1904799 0.9816889 0.00213027 0.1918064 0.9814011 -0.007891297 0.1902271 0.9816606 -0.01250386 0.1902056 0.9816958 -0.009763956 0.1899283 0.9817213 -0.01227027 0.1905448 0.9816647 -0.005216598 0.1890604 0.9819443 0.006460249 0.1902472 0.9816842 -0.01010692 0.1907026 0.9816421 0.003396749 0.1910386 0.9815398 -0.009159564 0.19063 0.9816453 -0.005717992 0.1889773 0.98151 0.03042799 0.1854014 0.9821851 0.03064078 0.1871728 0.9816734 0.03582924 0.1907013 0.9816467 0.001706361 0.1890327 0.9816337 0.02572721 0.1901067 0.9793803 0.06836473 0.1893382 0.9796664 0.06636911 0.1885145 0.9802021 0.06054925 0.1900167 0.9795833 0.06565278 0.1900412 0.9793901 0.06840682 0.1902621 0.9796956 0.06322163 0.18647 0.9786164 -0.08682602 0.1827454 0.9793729 -0.08621507 0.1790557 0.942156 -0.2833396 0.1787509 0.939961 -0.290726 0.188955 0.9819843 -0.001716196 0.1808738 0.9835047 -0.001793444 0.1892828 0.9819219 -0.001259088 0.1887807 0.9820193 -2.53279e-4 0.1893491 0.9819096 -7.46135e-4 0.1896313 0.981855 9.24669e-4 0.1886599 0.982041 0.001726329 0.1891628 0.9819454 8.60569e-4 0.1893813 0.981903 0.001121342 0.1891152 0.9819532 0.001841425 0.1889846 0.9819716 0.004102706 0.1890748 0.9819564 0.003523647 0.1895062 0.9818708 0.004151225 0.1894775 0.9818797 0.003254115 0.1881187 0.9821398 0.003570199 0.1890658 0.9819642 -7.02858e-4 0.1886994 0.9820275 -0.00383079 0.1890665 0.9819639 9.60826e-4 0.188631 0.9820308 -0.005833387 0.1889829 0.9819802 -7.64827e-4 0.1888716 0.9819705 -0.007837593 0.1893251 0.9819127 -0.00192964 0.1889516 0.9819797 -0.003646731 0.1893449 0.9818311 -0.01250433 0.1889178 0.9819768 -0.005622208 0.1879894 0.9821345 -0.008488774 0.189857 0.9817607 -0.01001262 0.1890471 0.981904 -0.01121062 0.189332 0.9819119 -0.001587033 0.1890768 0.9819622 5.89475e-4 0.1876298 0.9821397 0.01402908 0.1893283 0.981907 -0.003682374 0.1906857 0.9815066 0.01684671 0.1873236 0.9821523 0.01693785 0.1873552 0.9820659 0.02108848 0.1890776 0.9819599 -0.002103626 0.1890601 0.9819546 0.004632472 0.1852183 0.9812698 0.05295002 0.1870205 0.9806068 0.05859649 0.1892154 0.9818121 0.01557815 0.1891931 0.9817579 0.01890724 0.1887106 0.9800542 0.06230777 0.1886478 0.9797663 0.06685835 0.1816427 0.9383319 -0.2941758 0.1794848 0.9523287 -0.2466886 0.1809491 0.9501889 -0.2537683 0.1795434 0.9769445 -0.1155145 0.1871618 0.9823274 -0.001841306 0.1877808 0.9822095 -0.001765787 0.1849409 0.9827487 -0.001453638 0.1882207 0.9821258 -0.001427829 0.1872769 0.9823071 -3.31539e-4 0.1887383 0.982027 -8.85599e-4 0.1873871 0.9822862 2.64947e-4 0.1856886 0.9826084 7.4739e-4 0.1879713 0.9821745 -1.88108e-4 0.187509 0.9822627 7.41254e-4 0.1875087 0.9822629 3.55729e-4 0.1855018 0.9826413 0.002302169 0.1871127 0.9823365 0.001982808 0.1873936 0.9822812 0.00273472 0.1872926 0.9823025 0.001862227 0.1873114 0.9822955 0.003179848 0.1878111 0.9822019 0.002526223 0.1871668 0.9823191 0.0042153 0.1889631 0.9819792 0.003136992 0.1874542 0.9822733 3.92641e-4 0.1856721 0.9826093 -0.002212405 0.1874535 0.9822711 0.002203106 0.1852201 0.9826623 -0.008272767 0.1888793 0.9819443 -0.01049202 0.1873978 0.9822146 -0.01168948 0.1879138 0.982112 -0.01202827 0.1873778 0.982255 -0.008054554 0.1877095 0.9821484 -0.0122348 0.1868693 0.9823764 -0.004073798 0.1874569 0.9822666 0.003541588 0.1875054 0.9822272 -0.008460164 0.1876651 0.9821714 0.01100945 0.1832663 0.9828325 0.02130222 0.1853743 0.9823255 0.02594143 0.1874547 0.9822716 0.001818537 0.1831777 0.9822072 0.04141485 0.1831466 0.9819601 0.04703027 0.1876658 0.9822012 0.007897913 0.1876296 0.9821789 0.01095283 0.1872752 0.9801447 0.06515002 0.1674904 0.985654 0.02081418 0.1631866 0.9860476 0.03286921 0.157781 0.9872145 0.02264475 0.1870466 0.9801346 0.06595301 0.1851915 0.9806481 0.06351077 0.1851291 0.9808244 0.06091618 0.18531 0.9811178 0.05539155 0.1873124 0.9801345 0.06519627 0.1870133 0.9799572 0.06862932 0.1856795 0.9826 0.004516839 0.1870736 0.9802954 0.06343936 0.1857064 0.9825502 -0.01040685 0.1778347 0.9820128 -0.06344914 0.1775585 0.9804172 -0.08517801 0.1831744 0.9809692 -0.06439489 0.1760972 0.9720137 -0.1554965 0.1780772 0.9679037 -0.1773447 0.1812513 0.9708651 -0.1567447 0.1826287 0.966858 -0.178417 0.182018 0.963133 -0.1981018 0.1805187 0.9557879 -0.232126 0.1790786 0.939314 -0.2926093 0.180858 0.9613312 -0.2076846 0.1756039 0.9449772 -0.27601 0.185348 0.9826714 -0.001753687 0.1842963 0.9828703 -8.89345e-4 0.1863183 0.9824887 -0.001238524 0.1851652 0.9827075 1.40806e-4 0.1866645 0.9824237 -3.32908e-4 0.185753 0.9825957 0.001247644 0.1856886 0.9826086 2.67805e-4 0.186167 0.9825177 8.71575e-4 0.1832755 0.9830568 0.003074049 0.1835035 0.98301 0.004244089 0.1857649 0.9825856 0.004153132 0.1856656 0.9826065 0.003565967 0.1858677 0.9825659 0.004168033 0.1871939 0.982316 0.003695964 0.185602 0.9826238 0.001549839 0.1862936 0.9824942 -1.57895e-4 0.1856021 0.9826203 0.003062605 0.1856498 0.9826077 -0.004031836 0.1862927 0.9824939 8.8544e-4 0.1851846 0.9826852 -0.006047606 0.1857192 0.9826027 -5.80438e-4 0.1857241 0.9825996 -0.002174198 0.1851579 0.9826491 -0.01082944 0.1856167 0.9826139 -0.004056036 0.1862731 0.982421 -0.01230281 0.1861202 0.9825115 -0.005519807 0.183357 0.9829769 -0.01168793 0.1861349 0.9824938 -0.007737338 0.1862766 0.9824426 -0.0103724 0.1856905 0.98256 -0.009745895 0.1857205 0.9825804 -0.006624221 0.1855992 0.9826245 -0.001443922 0.1858006 0.9825267 -0.01093059 0.1855995 0.9826253 5.55154e-4 0.1858453 0.9825567 0.006635069 0.1834856 0.982919 0.01425474 0.1859053 0.9825425 -0.007035911 0.1855981 0.982621 -0.003100335 0.1832993 0.982907 0.0171824 0.1855988 0.9826247 -0.001444399 0.1809158 0.9830127 0.03091555 0.1832064 0.9824113 0.03610414 0.1858445 0.9825677 0.004764556 0.1807364 0.982087 0.05328702 0.1830533 0.9813405 0.05884075 0.1855115 0.9825185 0.01559096 0.1855161 0.9824558 0.01909291 0.1162793 0.9928299 -0.02771168 0.1251904 0.9916661 -0.03042781 0.1252485 0.992039 -0.01309245 0.1845625 0.9804131 0.06875276 0.1854537 0.9806625 0.06251567 0.1854028 0.9803661 0.06714361 0.178171 0.983664 -0.02569711 0.1716105 0.9848608 -0.02447652 0.175024 0.983614 -0.04324483 0.1807934 0.9825224 -0.04431325 0.1736826 0.9759613 -0.1316581 0.1795458 0.9747295 -0.1329121 0.1792092 0.9599537 -0.2153441 0.1748161 0.941712 -0.2874333 0.177285 0.9492636 -0.2597473 0.1741751 0.946625 -0.2712273 0.1831007 0.9830924 -0.00189501 0.1838354 0.9829555 -0.001809597 0.1804432 0.9835843 -0.001496315 0.1843254 0.9828643 -0.001459181 0.1818503 0.9833262 -1.89579e-4 0.1822571 0.9832509 -2.71018e-4 0.1849424 0.9827491 -8.85761e-4 0.1832545 0.9830651 8.94564e-4 0.184549 0.9828234 1.41525e-4 0.1822763 0.9832471 7.62908e-4 0.1834064 0.9830347 0.002204358 0.1842773 0.9828734 0.001349329 0.1801015 0.9836418 0.003538191 0.1839891 0.9829255 0.002341866 0.1845765 0.9828119 0.003514528 0.1832145 0.9830639 0.004225611 0.181266 0.983429 0.003195226 0.1840316 0.9829156 0.003046393 0.1846193 0.9827986 0.004766523 0.184113 0.9829049 -5.25714e-4 0.1846879 0.9827953 0.001939296 0.1831282 0.983089 3.9167e-4 0.1830589 0.9830273 -0.01211434 0.182835 0.9830901 -0.01026308 0.1836304 0.9829222 -0.01199322 0.1835032 0.9830086 -0.004536747 0.1837502 0.9829675 0.003313124 0.1843186 0.9828259 -0.008944988 0.1834971 0.9829568 0.01117461 0.1835047 0.9830056 -0.005098044 0.1782019 0.9837573 0.02157706 0.1808537 0.9831597 0.02624607 0.1837577 0.9829697 0.001964509 0.178047 0.9831346 0.04178029 0.1780801 0.9828739 0.04739642 0.1834998 0.9829837 0.008418977 0.1834905 0.982958 0.01116943 0.1831103 0.9809136 0.06541615 0.1831166 0.9808849 0.06582641 0.1805796 0.981484 0.06387579 0.18055 0.9816415 0.0614956 0.1805798 0.9819734 0.05584943 0.184006 0.9807196 0.06581068 0.180705 0.982326 0.0488004 0.1807929 0.9827033 0.04010158 0.1830749 0.980655 0.06927913 0.1808873 0.9833289 0.01855564 0.1809183 0.9834845 0.005188226 0.183084 0.9809954 0.06425273 0.1809766 0.9834387 -0.0097965 0.1798514 0.9776922 -0.1084968 0.1774092 0.9641991 -0.1970942 0.1760662 0.9569346 -0.2308179 0.1708172 0.9445764 -0.2803515 0.1718225 0.9421244 -0.2878866 0.1682117 0.985749 -0.001951336 0.1799415 0.9836769 -9.3514e-4 0.1818854 0.9833189 -0.001266896 0.1803501 0.9836024 5.3728e-4 0.1811223 0.9834606 -2.72737e-4 0.1800062 0.9836641 0.001674473 0.1824383 0.9832169 8.99007e-4 0.1806219 0.9835494 0.002559065 0.1817214 0.9833476 0.002227127 0.1813211 0.9834146 0.004314184 0.1815185 0.9833827 0.003109276 0.1812697 0.983424 0.004311442 0.1820065 0.9832956 0.001908719 0.1812064 0.9834452 -2.57426e-4 0.1820057 0.9832919 0.003325581 0.1817651 0.9833409 -0.001533567 0.1811946 0.9834459 0.001637876 0.1811231 0.983453 -0.003831088 0.1811185 0.9834439 -0.005859494 0.1817104 0.9833521 -1.42097e-4 0.1810839 0.9834341 -0.008136212 0.1810903 0.9834644 -0.002024829 0.1810884 0.9834063 -0.01090782 0.1811029 0.9834567 -0.003845572 0.1810889 0.9834492 -0.005881488 0.1785034 0.9838718 -0.01153671 0.1810991 0.9834313 -0.008125126 0.1812058 0.9833802 -0.01130598 0.1811164 0.983421 -0.008949458 0.1812036 0.983375 -0.0117923 0.1808839 0.9834849 -0.006204009 0.1811259 0.9834585 -0.001666665 0.1810686 0.9834051 -0.01135015 0.1814104 0.9834075 2.93542e-4 0.1783803 0.9838948 0.01146829 0.1811318 0.9834182 -0.008939206 0.1811181 0.9834378 0.006803691 0.1813812 0.9834087 -0.002899706 0.1782 0.9838384 0.01751786 0.1814104 0.9834067 -0.001258075 0.1751174 0.9840515 0.03125131 0.1780815 0.9833397 0.03647083 0.1811183 0.9834468 0.005355834 0.1749651 0.9831068 0.05374383 0.1779854 0.9822468 0.05926746 0.1810801 0.9833373 0.0160619 0.1810259 0.9832894 0.01928043 0.07553517 0.995813 -0.05148595 0.06415104 0.9968444 -0.04675519 0.06406003 0.9956621 -0.06747817 0.1810882 0.9810421 0.0690186 0.1830838 0.9809438 0.06503611 0.1782919 0.9818261 0.06503593 0.181369 0.9811744 0.06634908 0.1781979 0.9835222 0.03048801 0.1807188 0.9812139 0.06752806 0.1740822 0.9788771 -0.1072144 0.1665428 0.9803965 -0.105291 0.1662397 0.9775093 -0.1297689 0.172374 0.9692074 -0.1758533 0.1648964 0.9709142 -0.1735944 0.1644676 0.967243 -0.1933692 0.1741102 0.9611921 -0.2139984 0.1754707 0.9400187 -0.2925323 0.1730417 0.9540485 -0.2446388 0.1721281 0.9506112 -0.2582837 0.1716071 0.9535597 -0.2475379 0.175492 0.9844791 -0.001880466 0.1785215 0.9839342 -0.001886963 0.1550077 0.987911 -0.002105832 0.1485953 0.9888957 -0.002166807 0.1485357 0.9889055 -0.001800596 0.1785185 0.9839355 -0.001514077 0.1785184 0.9839361 -9.4724e-4 0.1785546 0.9839296 -9.4307e-4 0.178121 0.9840086 2.83202e-5 0.1792976 0.9837949 -1.92739e-4 0.1773749 0.9841427 0.001105785 0.1795173 0.9837547 5.40331e-4 0.1781471 0.9840012 0.002317845 0.1782156 0.9839864 0.003170251 0.1796245 0.9837338 0.001678287 0.1791201 0.9838239 0.002582788 0.1784232 0.9839441 0.004389941 0.1796633 0.9837218 0.003547668 0.1785869 0.9839143 0.004400014 0.1785082 0.9839333 0.003169238 0.1801192 0.9836444 9.5318e-4 0.1792843 0.983792 0.00326538 0.1792294 0.9838054 -0.001941919 0.1774662 0.9841248 0.002087116 0.1762157 0.9843356 -0.005633592 0.1771526 0.9841835 -8.85804e-5 0.1789863 0.9837806 -0.01181936 0.1754428 0.9844502 -0.008817076 0.1792252 0.9837565 -0.01008296 0.178502 0.9838669 -0.01196545 0.1759726 0.9843946 9.96702e-4 0.1784156 0.9839488 0.003574013 0.1752902 0.9843205 0.01966196 0.1794037 0.9837611 -0.005351006 0.1809751 0.9834001 0.01312297 0.1751779 0.9844453 0.01342827 0.1784158 0.9839518 0.002601385 0.1750902 0.9841919 0.02664345 0.1714235 0.9842891 0.04229891 0.1714565 0.9840288 0.047854 0.1783828 0.9839211 0.008886992 0.1783854 0.9838938 0.01147717 0.1747831 0.982503 0.06433433 0.1768251 0.9819077 0.0677514 0.165109 0.9839096 0.06827151 0.1576327 0.98538 0.0646401 0.1672158 0.9838845 0.06332772 0.1781765 0.9815496 0.0693801 0.1766836 0.9821026 0.0652489 0.1747542 0.982634 0.06238168 0.1747815 0.9829819 0.05655139 0.1795769 0.9814165 0.06763124 0.1748724 0.9833445 0.04953187 0.1749964 0.9837219 0.04083454 0.1787144 0.9814432 0.06950205 0.1750876 0.9843603 0.0194711 0.1751155 0.984529 0.006103694 0.1779764 0.9818882 0.06496083 0.1751816 0.9844961 -0.008881151 0.1623942 0.9833378 -0.08170062 0.156503 0.9823557 -0.1023923 0.1718236 0.9655083 -0.1956287 0.1705112 0.9583358 -0.2291692 0.1703885 0.9653213 -0.1977947 0.1649578 0.9490647 -0.2684495 0.1719253 0.9851082 -0.001905441 0.1417286 0.989903 -0.002288877 0.1411519 0.989986 -0.001983702 0.175337 0.9845067 -0.001893818 0.1749788 0.9845713 -0.001297056 0.1762964 0.984336 -0.001534581 0.1744179 0.9846717 -3.13054e-4 0.1767961 0.9842471 -9.57364e-4 0.1744856 0.9846594 7.81809e-4 0.1763234 0.9843323 2.82767e-5 0.1746107 0.9846353 0.002139568 0.1764826 0.9843032 0.001111805 0.1750082 0.984562 0.003135859 0.1757418 0.9844335 0.002353072 0.1754838 0.9844721 0.004476964 0.1755157 0.9844714 0.003225028 0.1755424 0.9844617 0.004480004 0.1754809 0.9844775 0.003276824 0.173365 0.9848548 0.002357542 0.1754421 0.9844892 0.001128971 0.1755133 0.9844716 0.003280758 0.1754584 0.9844857 -0.001576304 0.1761821 0.984351 -0.003603637 0.1755353 0.9844725 0.001142978 0.1761972 0.984323 -0.00792557 0.1761208 0.9843676 -0.001430869 0.1761636 0.9843086 -0.01016163 0.1761577 0.9843554 -0.003616809 0.1761559 0.984346 -0.005664467 0.1751152 0.9844783 -0.01171004 0.1761924 0.9843238 -0.007928073 0.1752067 0.9844747 -0.0105893 0.1748929 0.9845188 -0.01163959 0.1705617 0.9853426 -0.002955436 0.1754834 0.9844664 -0.005609571 0.1755395 0.9844715 -0.001323938 0.1768283 0.9841772 -0.01127672 0.1751502 0.9844912 0.009979784 0.1678833 0.9857537 0.01025426 0.1680685 0.9856746 0.01409977 0.1756539 0.9844136 -0.008708119 0.1782911 0.9839582 0.006225824 0.171913 0.9850895 0.006683588 0.1760304 0.9843703 -0.00534588 0.1716398 0.9849147 0.02197378 0.175968 0.9843955 -0.001038014 0.1715472 0.9844813 0.03698897 0.1679173 0.9852861 0.03186213 0.175325 0.9844927 0.005945086 0.1627891 0.9847918 0.06070256 0.1674895 0.9837264 0.06503647 0.171395 0.9833849 0.05981731 0.1753062 0.9843732 0.01664614 0.1753163 0.9843152 0.0196948 0.1751606 0.9820987 0.06928968 0.1745999 0.9823497 0.06711155 0.1733193 0.9825093 0.06808865 0.1715783 0.9846678 0.03146517 0.1515249 0.9882538 -0.01986759 0.1483538 0.9882423 -0.03698927 0.1577551 0.9866943 -0.03933954 0.1625151 0.9848876 -0.05987876 0.1514984 0.9868156 -0.05694925 0.1515292 0.9853214 -0.07861816 0.1712741 0.9832697 -0.06201511 0.1710616 0.9816896 -0.08380645 0.154978 0.9731451 -0.1702073 0.1609866 0.9752887 -0.1513121 0.1696233 0.9734267 -0.1538451 0.1677343 0.9627636 -0.2120179 0.1641615 0.9456303 -0.2807745 0.1664212 0.9558313 -0.2422615 0.1658389 0.9524295 -0.2556862 0.1656263 0.9491394 -0.2677733 0.1645883 0.9445898 -0.2840087 0.1722025 0.9850597 -0.00192219 0.1722199 0.9850577 -0.001303493 0.1673877 0.9858911 -5.80328e-4 0.1720509 0.9850872 -0.001320242 0.1721086 0.9850779 -3.10708e-4 0.1721015 0.9850791 7.42596e-4 0.172048 0.9850886 -3.17228e-4 0.1708285 0.9852995 0.001560628 0.1724134 0.9850243 7.91475e-4 0.1716965 0.9851469 0.002441704 0.1709173 0.9852782 0.003779947 0.1726941 0.9849731 0.002164959 0.1722348 0.9850453 0.004591822 0.1731986 0.9848819 0.003171086 0.1721203 0.9850654 0.004584729 0.1729664 0.9849198 0.003962874 0.1739694 0.9847511 -1.46221e-4 0.170853 0.9852905 0.003453373 0.172644 0.984979 -0.003222286 0.1704917 0.9853582 0.001342236 0.1720672 0.9850702 -0.005454599 0.1720936 0.985049 -0.007895588 0.1704997 0.9853568 -0.0013507 0.1720685 0.9850791 -0.003415644 0.1734494 0.9847758 -0.01148569 0.1720945 0.9850654 -0.005444824 0.1726637 0.9849503 -0.007762908 0.1705497 0.9852992 -0.009915471 0.1707547 0.9852656 -0.0097332 0.1711617 0.985217 -0.007156968 0.1726059 0.9849228 -0.01158934 0.1738688 0.9847688 4.27271e-4 0.1698701 0.9854663 -5.49346e-4 0.170146 0.9854125 0.003570735 0.1754242 0.9844873 0.003326535 0.1731256 0.9848613 -0.008703112 0.1631245 0.9863463 0.02261459 0.1715788 0.9850065 0.01797574 0.1630643 0.9864428 0.01846408 0.1737841 0.9847683 -0.005517482 0.1737147 0.9847904 -0.003326535 0.167886 0.9854339 0.02710103 0.1718965 0.9850686 0.009575307 0.1676737 0.9843431 0.05435508 0.1699001 0.983083 0.06842392 0.1717597 0.9826653 0.0697686 0.1699584 0.983128 0.06762933 0.1672434 0.984234 0.05755859 0.1672758 0.9846108 0.05060082 0.1674607 0.9849878 0.04190331 0.1720757 0.982608 0.06979686 0.1675511 0.9858351 0.007477223 0.1715471 0.9830007 0.06543123 0.167551 0.9858349 -0.007507741 0.1674574 0.9849988 -0.04165834 0.1501559 0.9775698 -0.1476838 0.156286 0.9795264 -0.1268965 0.1679784 0.9426773 -0.2883452 0.1632468 0.9602233 -0.2265434 0.1615084 0.9475038 -0.275956 0.1612008 0.9831056 -0.08670419 0.1658733 0.9861451 -0.001953244 0.1607451 0.986994 -0.002014219 0.1606809 0.987005 -0.001709043 0.1681784 0.9857546 -0.001954078 0.1684745 0.9857051 -0.001333534 0.1672983 0.9859063 3.69137e-4 0.1690963 0.9855996 -3.16603e-4 0.1679264 0.9857987 0.001366853 0.1678791 0.9858055 0.002106964 0.1690114 0.9856139 7.56959e-4 0.1686958 0.9856669 0.001581132 0.1670957 0.9859352 0.003322362 0.1691492 0.9855874 0.00248003 0.1679847 0.9857784 0.004710018 0.1693128 0.985555 0.003817737 0.1681669 0.9857473 0.004724025 0.1682135 0.9857418 0.004157781 0.1681451 0.9857589 0.002580225 0.1681272 0.9857566 0.004143834 0.1680878 0.9857721 1.07819e-4 0.1681606 0.9857562 0.00258255 0.1681255 0.985761 -0.00301063 0.1681314 0.9857505 -0.005270481 0.1681626 0.9857593 1.18883e-4 0.1681385 0.9857346 -0.007538616 0.1696289 0.9854589 -0.009844183 0.168133 0.9857597 -0.003008723 0.1681418 0.9857488 -0.005267024 0.1674938 0.9858078 -0.01134407 0.1676994 0.9858083 -0.007683515 0.167296 0.9858697 -0.008548617 0.1667197 0.985941 -0.01117795 0.1702982 0.9853794 -0.005096733 0.165964 0.9861092 -0.006683707 0.1658087 0.9861545 -0.002624571 0.1655367 0.9862008 0.00238049 0.1608367 0.9869637 0.005859673 0.1656269 0.9861625 0.007171928 0.1693795 0.9855037 -0.009651243 0.1702054 0.9853724 -0.008453786 0.1697118 0.9854894 -0.0029096 0.1607126 0.9866157 0.02758908 0.1631238 0.9858843 0.03772139 0.1631533 0.9856646 0.04297041 0.1630016 0.9854258 0.04864716 0.1678323 0.9856601 0.01750952 0.1604683 0.9846004 0.06936943 0.1653192 0.9838275 0.06894147 0.1678027 0.9833183 0.07019585 0.1676697 0.9833418 0.0701844 0.1628521 0.9863907 -0.02264547 0.1592202 0.964874 -0.208967 0.1579667 0.9581769 -0.2386286 0.1575111 0.9548631 -0.2518468 0.15705 0.9517304 -0.2637134 0.1575406 0.9596794 -0.2328012 0.1559513 0.9476411 -0.2786677 0.1549435 0.9879215 -0.001922667 0.1657794 0.9861614 -0.001709043 0.1604384 0.9870454 -0.00100708 0.1658388 0.9861524 -0.001068115 0.1606811 0.9870064 0 0.1660863 0.9861112 -2.74674e-4 0.1659329 0.9861368 7.6298e-4 0.1607108 0.9870011 0.00100708 0.1658387 0.9861515 0.001678526 0.1606807 0.9870041 0.002166807 0.1658384 0.9861494 0.002655088 0.1608337 0.986976 0.003326535 0.1660851 0.9861035 0.003967463 0.1606844 0.986996 0.004425287 0.1605011 0.9870257 0.004455804 0.1657481 0.9861574 0.004608333 0.1661447 0.9860952 0.00350964 0.160408 0.9870467 0.002868771 0.1662049 0.9860901 0.001464843 0.1601957 0.9870852 4.57789e-4 0.1661456 0.9861004 -0.001342833 0.1605916 0.9870187 -0.00213629 0.1550964 0.9878931 -0.00350964 0.1606848 0.9869986 -0.003784358 0.1657783 0.986155 -0.003997921 0.1605592 0.9870073 -0.006103694 0.165811 0.9861374 -0.006317436 0.1658386 0.9861204 -0.008026361 0.1604366 0.9870045 -0.009064018 0.16575 0.9861077 -0.01089537 0.1658114 0.9861092 -0.009766161 0.1607418 0.986943 -0.01028478 0.160988 0.9869254 -0.007812857 0.1608974 0.9869615 -0.004364192 0.1547902 0.9879474 4.88297e-4 0.1609286 0.9869661 1.52597e-4 0.1608957 0.9868902 0.01266533 0.1553404 0.9876781 0.01901316 0.1608029 0.9864553 0.03238028 0.1551601 0.9871466 0.0383017 0.1603783 0.9855259 0.0549345 0.1550044 0.985998 0.06149512 0.160439 0.9848523 0.06576871 0.1479265 0.9864715 0.07065188 0.1543048 0.9855851 0.06936997 0.1545177 0.9854891 0.07025474 0.1604699 0.9846407 0.06879025 0.08655238 0.9960852 -0.01797574 0.07559525 0.9966245 -0.03201425 0.08652174 0.9955956 -0.03610414 0.1577206 0.9857238 0.05893158 0.1577536 0.986105 0.05206567 0.1576618 0.986531 0.0435813 0.1162154 0.9921345 -0.04651057 0.1250966 0.9909151 -0.0493794 0.1580289 0.9873905 0.009338855 0.1579989 0.9874243 -0.005462944 0.1439277 0.9819498 -0.122717 0.1399592 0.9796231 -0.1440487 0.1421258 0.9723886 -0.1850962 0.1349549 0.9707785 -0.1984344 0.1481091 0.9676079 -0.2044474 0.1546406 0.9695326 -0.1899817 0.1535118 0.9627602 -0.2225463 0.1514658 0.9508805 -0.2699711 0.1530837 0.9729177 -0.1731957 0.1521078 0.9504909 -0.2709802 0.152534 0.954421 -0.2565428 0.1067257 0.9942859 -0.002288937 0.1071211 0.9942423 -0.002716124 0.1172251 0.9931021 -0.002563595 0.1547947 0.9879457 -0.001434385 0.1550676 0.9879037 -5.18825e-4 0.1550676 0.9879038 2.44153e-4 0.1550078 0.9879122 0.001464903 0.1487489 0.9888724 0.00225836 0.1548836 0.9879289 0.002777218 0.1484446 0.9889086 0.004913508 0.1548826 0.9879222 0.004608273 0.1549426 0.987916 0.003875851 0.1550956 0.9878882 0.004730343 0.1484456 0.9889149 0.003387629 0.1549431 0.9879187 0.003082334 0.1549736 0.9879184 7.01928e-4 0.1549139 0.9879271 -0.001342773 0.1484148 0.9889135 -0.004822015 0.1548219 0.9879242 -0.006012201 0.1549127 0.9878891 -0.00878936 0.1547027 0.9879125 -0.009796679 0.1548845 0.9879041 -0.007507681 0.1548234 0.987934 -0.004028499 0.1546384 0.9879527 0.006042659 0.155157 0.9878292 0.01095616 0.148414 0.9885109 0.02862679 0.1549738 0.987523 0.02795505 0.1553102 0.9875884 0.02340787 0.154854 0.9873854 0.03302168 0.1551275 0.9877747 0.01538151 0.1482937 0.9876683 0.05020433 0.1551583 0.9866471 0.04953223 0.155188 0.9869165 0.04373341 0.1548242 0.9863828 0.05548399 0.1479884 0.9864469 0.07086592 0.1547014 0.9857371 0.06625699 -8.24003e-4 0.998478 -0.05514711 -8.24017e-4 0.9973047 -0.07336801 0.01309251 0.9979341 -0.06289923 0.1547924 0.9873513 0.03430336 0.116064 0.9909843 -0.06692826 0.1249438 0.9896929 -0.06997948 0.1332173 0.9839468 -0.1187511 0.1334608 0.9864751 -0.09515911 0.1243959 0.9854928 -0.1154538 0.1442656 0.9846197 -0.09854739 0.1276015 0.975674 -0.1782637 0.1427367 0.9758408 -0.1654123 0.1469178 0.9612528 -0.2332557 0.1465514 0.958108 -0.2460733 0.1462156 0.955147 -0.2575176 0.1460024 0.9514574 -0.2709468 0.1452107 0.9514384 -0.2714384 0.148506 0.988911 -0.001037597 0.1484121 0.9889255 3.66224e-4 0.1483224 0.9889383 0.001281797 0.1487186 0.9888737 0.003418087 0.1413639 0.9899445 0.005127131 0.1483552 0.9889228 0.004730463 0.1487194 0.9888789 0.001037597 0.1483522 0.9889331 -0.001739561 0.148689 0.9888492 -0.008301138 0.1480763 0.9889253 -0.01001006 0.1485355 0.9888738 -0.008117973 0.1485979 0.9888827 -0.005462884 0.1486597 0.9888875 -0.001403868 0.1487184 0.9888725 0.003753781 0.1413353 0.9898356 0.01580899 0.1483827 0.9888114 0.01532042 0.1485077 0.9888616 0.009918808 0.1484448 0.9887266 0.01959323 0.148444 0.9886299 0.02398782 0.1412425 0.9891858 0.03952223 0.1483523 0.9881712 0.03885054 0.1484134 0.9883545 0.03360128 0.1483241 0.9879427 0.04437512 0.1410903 0.9879984 0.06286954 0.1481986 0.9870037 0.06213593 0.148231 0.987352 0.05624657 0.1481406 0.9866887 0.06708139 0.116218 0.9918821 0.05160838 0.1250977 0.9908935 0.04980713 0.1250367 0.990467 0.05780315 0.1485655 0.9867031 0.06592059 0.1486877 0.98704 0.06036621 0.1486871 0.9874328 0.05356031 0.1487789 0.9878314 0.04532033 0.1484771 0.9882809 0.03543305 0.1487802 0.988572 0.02429312 0.1489324 0.9887833 0.01126146 0.1487783 0.988865 -0.003326475 0.1158804 0.9892712 -0.08896267 0.1247008 0.9879015 -0.09219801 0.1332446 0.9884091 -0.07275658 0.1410582 0.9659835 -0.216745 0.1396556 0.9549747 -0.2617627 0.1393483 0.9559675 -0.2582797 0.1399896 0.9600594 -0.242258 0.1417627 0.9667949 -0.2126289 0.1070608 0.9942497 -0.00238043 0.1163079 0.99321 -0.002563536 0.1415451 0.9899308 -0.001434326 0.1414555 0.9899445 -5.79861e-4 0.1412718 0.9899709 -3.05189e-5 0.1412418 0.9899745 0.00112915 0.1411817 0.9899808 0.002411007 0.1412707 0.9899634 0.003875851 0.141304 0.9899522 0.005279779 0.1413947 0.9899464 0.003723323 0.141485 0.9899372 0.002533018 0.1335807 0.9910364 0.001739561 0.1412419 0.9899751 1.83114e-4 0.1413349 0.9899551 -0.003662288 0.1413655 0.9899554 -0.001983702 0.1410896 0.9899777 -0.006164848 0.141424 0.9899072 -0.009125113 0.1415188 0.9898998 -0.008423328 0.1335495 0.9910318 -0.004547238 0.1413341 0.9899494 -0.005005121 0.1413657 0.989957 -9.15581e-4 0.1413645 0.9899484 0.004272639 0.1413624 0.9899032 0.01040685 0.1413326 0.9897561 0.02020341 0.1335514 0.9905877 0.0300002 0.1413052 0.9895334 0.02926814 0.1413316 0.9896568 0.02459794 0.1412743 0.9893782 0.03424274 0.13343 0.9897073 0.05173003 0.1411824 0.988674 0.05090624 0.1412135 0.9889524 0.0450772 0.1411187 0.9883499 0.05700904 0.1332755 0.9884116 0.07266521 0.140907 0.9874172 0.07178103 0.1410269 0.9876765 0.06787353 0.1409657 0.9874311 0.07147467 0.1410267 0.9877369 0.06698846 0.1410888 0.9880796 0.06158709 0.1411485 0.9884666 0.05487239 0.1412115 0.9888777 0.04669409 0.1412733 0.9892794 0.03698921 0.141272 0.9896365 0.02572739 0.1413027 0.9898819 0.01293998 0.1413357 0.9899607 -0.001434385 0.1417289 0.9897527 -0.01739567 0.1413934 0.9893269 -0.03521865 0.1415759 0.9884375 -0.05429261 0.1413046 0.9870873 -0.0754438 0.1149648 0.9813361 -0.1541511 0.1054119 0.9802331 -0.1674261 0.1151481 0.9783163 -0.1721575 0.1235711 0.9796575 -0.1581185 0.1267158 0.9696261 -0.2092092 0.1178969 0.9691776 -0.2163223 0.1333386 0.9649882 -0.2258729 0.1330627 0.9620803 -0.2381091 0.1326386 0.9594782 -0.2486134 0.1319023 0.9567341 -0.2593488 0.1356587 0.9902626 -0.03125184 0.1335508 0.9910414 -0.00112915 0.1336109 0.9910338 -3.05187e-4 0.1337348 0.991017 6.10382e-4 0.1251876 0.9921317 0.001709043 0.1337046 0.9910195 0.001922667 0.1338241 0.9910001 0.003173887 0.1337327 0.9910019 0.005554378 0.1335835 0.9910268 0.00463891 0.1252495 0.9921084 0.005798578 0.1336129 0.9910184 0.005493402 0.1335839 0.9910292 0.004089593 0.1251277 0.9921407 0 0.1332471 0.9910829 -3.66231e-4 0.1337944 0.9910065 -0.002319395 0.1336135 0.9910231 -0.004547357 0.1334916 0.9910242 -0.00714147 0.133367 0.9910357 -0.007843315 0.1339769 0.9909413 -0.009247124 0.1334609 0.991054 -3.96751e-4 0.1333995 0.9910507 0.004822015 0.1335508 0.9909797 0.01110887 0.1253418 0.9919617 0.01736533 0.133583 0.9909012 0.01644986 0.13358 0.9908182 0.02087473 0.1335826 0.9907147 0.02530038 0.1251578 0.9912835 0.04113942 0.1334916 0.9902308 0.04028552 0.1335198 0.9904277 0.03500509 0.1334919 0.9899893 0.04584014 0.1250067 0.9900441 0.06470078 0.1333363 0.9890202 0.06372308 0.1333997 0.9893735 0.05783396 0.1332758 0.9886888 0.06878948 0.1249154 0.9894352 0.07358199 0.1249762 0.9894025 0.0739175 0.1159433 0.9904167 0.07504725 0.1333057 0.9884098 0.07263451 0.116095 0.9910501 0.06589096 0.106756 0.9923912 0.06134349 0.1161562 0.9914484 0.05948197 0.133307 0.9887248 0.06821 0.1333395 0.9890744 0.06287008 0.1333997 0.9894649 0.05624699 0.1334595 0.9898836 0.04815894 0.1335225 0.9902947 0.03857654 0.1335532 0.9906619 0.02743697 0.1335825 0.9909282 0.01474076 0.1336109 0.9910338 4.5778e-4 0.1335813 0.9909186 -0.01538151 0.1335215 0.9905008 -0.03286916 0.1334282 0.9896948 -0.05197352 0.1152696 0.9842326 -0.1341608 0.1057171 0.9830411 -0.1498473 0.1323927 0.9810736 -0.1413044 0.132634 0.9778782 -0.1617487 0.1143863 0.9754269 -0.188304 0.104834 0.9748498 -0.1966668 0.1143567 0.9726273 -0.2022835 0.1054132 0.9722186 -0.2089952 0.1261658 0.9842096 -0.1241515 0.1255871 0.9665174 -0.2237679 0.1250073 0.9620929 -0.2423849 0.1264396 0.9736123 -0.1899798 0.1341921 0.9909524 -0.002441465 0.1259535 0.9920329 -0.002533078 0.09720355 0.9952608 -0.002716183 0.1252814 0.9921189 -0.002197325 0.1255558 0.9920864 -7.01941e-4 0.1253418 0.9921137 0 0.1166128 0.9931774 3.66227e-4 0.1252515 0.9921246 0.001037657 0.116492 0.9931889 0.002319455 0.1251572 0.992133 0.002838194 0.1251605 0.992128 0.004120111 0.1251295 0.9921246 0.005615532 0.1252804 0.992111 0.004547297 0.1252511 0.9921213 0.002746701 0.1165222 0.9931856 -0.00225836 0.1252511 0.9921211 -0.002838253 0.1251298 0.9921268 -0.005188286 0.1250977 0.9921144 -0.007721304 0.1253114 0.9920846 -0.008087515 0.1163706 0.9931942 -0.004822015 0.1255239 0.9920755 -0.005493342 0.1254317 0.9921004 -0.001922667 0.1163707 0.9931642 0.009094774 0.1256152 0.9920433 0.008423149 0.1254652 0.9920943 0.002746701 0.1163385 0.9928448 0.02691775 0.1252207 0.9917865 0.0260635 0.1252489 0.9918894 0.02163773 0.1252191 0.9916512 0.03079354 0.1254013 0.9920102 0.01379442 0.1251907 0.9914856 0.03582984 0.1162164 0.9917771 0.05359137 0.1250986 0.9907482 0.05261528 0.1251274 0.9910398 0.04672437 0.1250672 0.9904056 0.05877977 0.1160038 0.9904119 0.07501637 0.1249457 0.9897077 0.06976693 0.124944 0.9897251 0.06952184 0.125006 0.9900681 0.06433409 0.1251583 0.9913174 0.04031556 0.1251909 0.9917001 0.02929866 0.1252493 0.9919844 0.01672428 0.1252813 0.992118 0.002594113 0.09598141 0.9847481 -0.1451166 0.09622716 0.9873894 -0.1257088 0.08572894 0.9864474 -0.1399008 0.1060216 0.985812 -0.1301313 0.1240304 0.9826601 -0.1378251 0.1051086 0.9774734 -0.1830245 0.09521865 0.977029 -0.1906509 0.1230539 0.9735358 -0.1925769 0.1294309 0.9583567 -0.2545587 0.1172224 0.9666497 -0.2277001 0.1170088 0.9643306 -0.2374356 0.1207041 0.9613603 -0.2474206 0.1169179 0.9628101 -0.2435713 0.05142444 0.9986728 -0.002868771 0.05246239 0.9986169 -0.003479182 0.06534159 0.9978556 -0.003845393 0.116308 0.9932112 -0.002044737 0.1163383 0.9932093 -9.15569e-4 0.1068467 0.9942756 1.83113e-4 0.116278 0.993216 0.00125128 0.1164615 0.9931887 0.003601253 0.116675 0.9931571 0.005096673 0.1161856 0.9932081 0.006225824 0.1163696 0.9931855 0.006378471 0.1164007 0.99319 0.004974603 0.1164014 0.9931969 0.003296077 0.1164924 0.9931915 4.5779e-4 0.1164007 0.993191 -0.00476098 0.1163992 0.9931778 -0.00701934 0.1162786 0.9931901 -0.007263541 0.1163985 0.9932019 -0.001190185 0.1163978 0.9931966 0.003479063 0.1069402 0.9940802 0.01919674 0.1163701 0.9930372 0.01831156 0.1163673 0.9931054 0.01416057 0.1163372 0.9929558 0.02246171 0.1163098 0.9927077 0.03167921 0.1068781 0.9933379 0.04309302 0.1162773 0.9923248 0.04208564 0.1163072 0.9925334 0.03674465 0.1162462 0.9920759 0.04767042 0.1067265 0.9920353 0.06689864 0.1161263 0.9910566 0.06573879 0.1161541 0.9914302 0.05978608 0.1160942 0.990707 0.07086503 0.1066944 0.9919891 0.06763005 0.1066628 0.9916433 0.07257336 0.09680622 0.9928744 0.06949174 0.1160633 0.9907041 0.0709564 0.02664303 0.9991912 -0.03012222 0.01309281 0.9996317 -0.02377456 0.01309281 0.9989932 -0.04291033 0.1162465 0.9923219 0.04223811 0.1162773 0.9927212 0.0313735 0.1163085 0.9930323 0.01895236 0.1163404 0.993197 0.004974663 0.1163389 0.9931535 -0.01055961 0.0639671 0.9939625 -0.089145 0.07544428 0.9945099 -0.07251441 0.0861563 0.9913013 -0.09949326 0.08633828 0.9932717 -0.07718253 0.07532155 0.9926697 -0.09451812 0.08594191 0.9889429 -0.1208559 0.07513719 0.9904565 -0.1155441 0.09647053 0.9898836 -0.1040392 0.1156067 0.9869599 -0.1120054 0.09546369 0.9794799 -0.1774991 0.08508634 0.9792256 -0.1840587 0.1080385 0.9658463 -0.2355179 0.1088913 0.9737659 -0.1998071 0.1082212 0.9691696 -0.2213562 0.1096242 0.9807893 -0.161354 0.08789354 0.9961268 -0.002502501 0.07953149 0.9968292 -0.002533018 0.07605421 0.997098 -0.003387629 0.01345902 0.9999051 -0.002960324 0.004882991 0.9999821 -0.003448605 -4.88307e-4 0.9999913 -0.004150569 0.1071816 0.9942379 -0.001739561 0.1067561 0.9942848 -9.76614e-4 0.09671384 0.9953073 0.00314337 0.1070908 0.9942449 0.002929806 0.1070308 0.9942544 0.001648008 0.1071205 0.9942368 0.004303097 0.1069381 0.9942433 0.006683588 0.1069388 0.9942502 0.00552392 0.1069388 0.9942508 0.005432367 0.106908 0.9942473 0.006561577 0.09704905 0.9952719 0.003936886 0.1067556 0.99428 0.003234982 0.1067259 0.9942883 -7.62982e-4 0.1072453 0.9942319 0.001159727 0.1068762 0.9942665 -0.003448605 0.1069986 0.9942391 -0.006317377 0.1068778 0.9942504 -0.006592094 0.09704929 0.9952742 -0.003295958 0.1069697 0.9942541 -0.004059016 0.1069706 0.9942621 -4.27272e-4 0.1069696 0.994253 0.004303157 0.09705001 0.9952206 0.01083415 0.1069685 0.9942126 0.009949088 0.1069683 0.9941491 0.01501518 0.09699016 0.9948666 0.02887117 0.1069378 0.9938753 0.02786362 0.1069372 0.993991 0.02337723 0.1069084 0.9937325 0.03265541 0.1068786 0.9935563 0.03772187 0.09689766 0.9937279 0.05581915 0.1068156 0.9927754 0.05465906 0.1068462 0.9930803 0.04873842 0.1067557 0.9924194 0.06088554 0.09668481 0.9923013 0.07739669 0.10648 0.9913716 0.07644951 0.1066937 0.9916777 0.07205486 0.09674423 0.9925289 0.0743435 0.09665423 0.9922397 0.07822066 0.08633947 0.9933469 0.07620704 0.1065131 0.9913655 0.07648187 -0.08838254 0.9955248 -0.03344863 -0.07318425 0.9961974 -0.04727375 -0.07324582 0.9966015 -0.03769105 0.1068153 0.9928336 0.05359077 0.1068484 0.9932847 0.04437518 0.106878 0.9937032 0.03363204 0.1069086 0.9940394 0.02136337 0.1069374 0.994237 0.007568597 0.1069372 0.9942353 -0.00778222 0.1069067 0.993961 -0.02475059 0.1068468 0.9933307 -0.04333686 0.1067239 0.9922544 -0.06357043 0.1065405 0.9906349 -0.0853911 0.1062986 0.9884275 -0.1082213 0.06338846 0.9854663 -0.1576013 0.0632652 0.9835867 -0.1689819 0.07455784 0.9835047 -0.1648024 0.07443493 0.9814182 -0.1768555 0.0852704 0.9814947 -0.1714563 0.08536267 0.9753078 -0.2036863 0.07571828 0.9764338 -0.2020986 0.08548384 0.973527 -0.2119852 0.1001645 0.971401 -0.2152836 0.09949243 0.9697763 -0.2227897 0.1042843 0.9677048 -0.2295048 0.1005914 0.9930967 0.06033653 0.03177005 0.9994902 -0.003173947 0.02685701 0.9996318 -0.003875911 0.04016286 0.999189 -0.002899289 0.09692853 0.9952876 -0.002746701 0.05234068 0.9986237 -0.003326594 0.06442606 0.9979178 -0.003082394 0.09683799 0.9952983 -0.001953184 0.09704977 0.995279 -0.00100708 0.09717369 0.9952675 -2.13636e-4 0.09735506 0.9952495 7.93489e-4 0.08661377 0.9962415 0.001037597 0.09677457 0.9953045 0.001922667 0.09701853 0.995272 0.004577755 0.09711146 0.9952554 0.006012201 0.08658355 0.9962148 0.007721364 0.09698975 0.9952594 0.007202506 0.09695959 0.9952625 0.007171988 0.09705108 0.9952618 0.005920708 0.09701943 0.9952809 0.001770079 0.09701955 0.9952825 -2.13632e-4 0.09723377 0.9952576 -0.002868771 0.09702086 0.9952655 -0.005798637 0.09692722 0.9952744 -0.005829036 0.09704983 0.9952795 3.05188e-4 0.0970515 0.9952662 0.005127191 0.0866118 0.9960972 0.01699882 0.09701895 0.9951541 0.0159918 0.09702044 0.9950779 0.02017313 0.09702026 0.9949845 0.02435421 0.08655244 0.9954448 0.03998011 0.09695976 0.9945322 0.03878998 0.09699022 0.9947149 0.03369325 0.09692841 0.9943099 0.04419153 0.09689879 0.9940442 0.04986852 0.08639818 0.9938385 0.06942981 0.09680658 0.9929695 0.06811863 0.09683674 0.9933626 0.06207561 0.09677577 0.9926007 0.07333719 0.08640009 0.993098 0.07931965 0.05221766 0.9974769 0.04809761 0.05224907 0.9979512 0.03692835 0.0641815 0.9969348 0.04474085 0.09683793 0.9932835 0.06332767 0.09686797 0.993736 0.05572801 0.09692931 0.9941968 0.04666399 0.09695774 0.9946335 0.03610354 0.09699082 0.9949955 0.02401882 0.0970202 0.9952281 0.01040697 0.09701848 0.9952712 -0.004760861 0.09699046 0.9950528 -0.02151614 0.09692829 0.9944918 -0.03988832 0.09686821 0.9934944 -0.05987882 0.0966829 0.9919767 -0.08145415 0.07477134 0.9857615 -0.1506109 0.06354075 0.9875373 -0.1439891 0.09570878 0.9820834 -0.1623326 0.07434433 0.9795388 -0.1870206 0.06311345 0.9819514 -0.1782925 0.06296145 0.9803127 -0.1871447 0.09488475 0.9747895 -0.2019468 0.09531015 0.9700705 -0.2233365 0.09399724 0.9711933 -0.2189709 0.09164792 0.9946381 -0.0479145 0.08951175 0.9765422 -0.1958394 0.089908 0.9813888 -0.1696838 0.09042704 0.9879532 -0.1255847 0.08652025 0.9962494 -0.001159667 0.08673483 0.99623 -0.001770079 0.08652031 0.9962502 -1.83112e-4 0.07547348 0.9971478 1.22076e-4 0.08664381 0.9962359 0.00262463 0.08661299 0.9962326 0.004364192 0.08658182 0.9962253 0.006225824 0.08661401 0.9962139 0.007477223 0.08682662 0.9962019 0.006561577 0.07541352 0.9971314 0.006470084 0.08682751 0.9962126 0.00463891 0.08676499 0.9962259 0.002441465 0.07568806 0.9971292 0.002197384 0.0867955 0.996226 4.88301e-4 0.08670455 0.9962329 -0.001586973 0.08636802 0.996254 -0.004333615 0.0865218 0.9962373 -0.005035638 0.08664381 0.9962365 -0.002411007 0.08664405 0.9962387 0.00125128 0.0866425 0.9962208 0.006103694 0.08664327 0.996169 0.01184135 0.08661276 0.9960163 0.02121067 0.08658176 0.9959195 0.02545267 0.07565563 0.9966462 0.03118997 0.08655118 0.9957965 0.02996939 0.08655071 0.9956387 0.03482168 0.08652061 0.995216 0.0453813 0.08646059 0.9946175 0.05710119 0.08652043 0.9949394 0.05108821 0.07556414 0.9954268 0.05844318 0.08642923 0.9942414 0.06335699 0.08636885 0.9934557 0.07474112 0.07538098 0.9938699 0.08087438 0.06402879 0.9947052 0.08038699 0.07532018 0.993812 0.08163756 0.06393635 0.9944471 0.08359026 0.0521571 0.9964487 0.06610435 0.05218732 0.9969613 0.05783331 0.06412106 0.9959366 0.06323599 0.08636832 0.9936938 0.07150566 0.08640015 0.9941055 0.06549441 0.08630889 0.9930716 0.07974725 0.08643084 0.9945653 0.05804783 0.08649057 0.9950388 0.04916596 0.08652102 0.9954959 0.03875899 0.08655089 0.9958847 0.02688688 0.08658349 0.9961532 0.01348954 0.08658343 0.9962436 -0.001464903 0.08643114 0.9946911 -0.05585062 0.05173021 0.989253 -0.136757 0.03940063 0.9908767 -0.1288838 0.03930807 0.9892034 -0.1411796 0.0516377 0.9873737 -0.1497555 0.08548372 0.9839326 -0.1567456 0.05145591 0.9843162 -0.1687425 0.05142527 0.9831541 -0.1753953 0.08487284 0.977182 -0.19471 0.07938003 0.9753585 -0.205851 0.07782441 0.977383 -0.1966363 0.07276433 0.9973375 -0.004828572 0.07565748 0.9971289 -0.003174006 0.07541269 0.997151 -0.001678526 0.07590061 0.997115 -9.46087e-4 0.06408995 0.9979421 0.002014219 0.07547342 0.997147 0.001342833 0.06424206 0.9979342 6.40895e-4 0.075625 0.9971337 0.002319395 0.07605415 0.997097 0.003692805 0.07550454 0.9971238 0.006592094 0.07574796 0.9971141 0.005066096 0.0755341 0.9971116 0.007934868 0.0755341 0.9971112 0.007995903 0.07547277 0.9971382 0.00439465 0.0755949 0.9971387 -2.4415e-4 0.07586979 0.9971114 -0.003570675 0.07538175 0.9971449 -0.004425227 0.07544308 0.9971489 -0.001586973 0.07556438 0.9971387 0.00213629 0.0755043 0.9971208 0.00701934 0.07532006 0.9970759 0.01290935 0.07571732 0.9969607 0.01834183 0.07565742 0.9968837 0.02234011 0.07565641 0.9967788 0.02661246 0.06424224 0.997235 0.03735506 0.0642122 0.997029 0.04254364 0.07562673 0.9964847 0.03604322 0.07562547 0.9962848 0.04120028 0.07559537 0.9960461 0.0466634 0.07559454 0.9957609 0.05240041 0.06412035 0.9957424 0.06622612 0.06408983 0.9953151 0.07239097 0.0755344 0.9950399 0.0647307 0.07550472 0.9946242 0.0708658 0.07547432 0.9942291 0.07623732 0.07544392 0.9940773 0.07822114 0.07547283 0.9944226 0.07367223 0.07550466 0.9948369 0.06781381 0.0755335 0.9953033 0.0605489 0.0755642 0.9957936 0.05182069 0.07559597 0.996268 0.04165863 0.07562577 0.9966858 0.02996951 0.07565641 0.9969927 0.01678538 0.07565772 0.9971317 0.002075314 0.07565718 0.9970334 -0.01416093 0.01306217 0.9965715 -0.08169966 -8.2401e-4 0.9960455 -0.08884054 0.02645969 0.992377 -0.1203658 0.01300126 0.9937116 -0.1112127 0.01303178 0.9924313 -0.1221083 0.02639853 0.9909073 -0.1319317 0.07495427 0.9881084 -0.1342523 0.04022449 0.9855619 -0.1644688 0.03897309 0.9867188 -0.1576931 0.07416182 0.9782647 -0.1936448 0.06869727 0.9887407 -0.1329389 0.06836265 0.9841481 -0.1636432 0.06903362 0.9942434 -0.08194309 0.06451737 0.9979138 -0.002349913 0.05218708 0.998635 -0.002166807 0.05215668 0.9986381 -0.001281738 0.06424206 0.9979342 -7.32451e-4 0.06399852 0.9979436 0.003570675 0.06399804 0.9979361 0.005279719 0.06454861 0.9978948 0.006286978 0.06399893 0.9979194 0.007812917 0.05249339 0.998596 0.007111012 0.05246222 0.9985837 0.008850514 0.06445622 0.9978815 0.008819997 0.06418102 0.9979035 0.008331596 0.06424236 0.9979084 0.007202446 0.06424313 0.9979206 0.005218803 0.05230957 0.9986129 0.006012201 0.05231016 0.9986236 0.003814876 0.06424176 0.99793 0.002960264 0.06430286 0.9979304 5.18818e-4 0.06436353 0.9979255 -0.001464843 0.06421113 0.997928 -0.004089474 0.06418108 0.9979354 -0.002441465 0.0643028 0.9979299 0.001098632 0.06427347 0.9979173 0.005493402 0.06427246 0.9978712 0.01104778 0.0642417 0.9977759 0.01779234 0.05240172 0.9983193 0.02475118 0.05227851 0.9982055 0.02920639 0.06415092 0.9976664 0.02337753 0.06424254 0.9975453 0.02786386 0.06424337 0.9974059 0.03247267 0.05224919 0.9974049 0.049533 0.05221879 0.9971017 0.05533176 0.06418144 0.9967814 0.04803687 0.06415176 0.9964886 0.05380564 0.06415104 0.9961422 0.05987834 0.0521878 0.9954749 0.07941091 0.05185168 0.9950703 0.08453744 0.0640586 0.9949072 0.0778225 0.06399846 0.9945245 0.08261507 0.03967487 0.9963281 0.07587057 0.03967469 0.9968124 0.06921714 0.05215746 0.995967 0.07300215 0.06405967 0.9950462 0.07602316 0.06405919 0.9954658 0.07031553 0.06412011 0.9964408 0.05472028 0.06421118 0.9973797 0.03332632 0.06421202 0.997728 0.02038669 0.0642125 0.9979187 0.005920708 0.06421232 0.9978858 -0.01004076 0.06421262 0.9975548 -0.02758944 -8.54543e-4 0.9948406 -0.1014465 0.01303178 0.9951193 -0.09781503 0.02649074 0.9939846 -0.1062684 0.06381547 0.9919022 -0.1098078 0.06366366 0.9897171 -0.1280903 0.03991878 0.985549 -0.1646193 0.05704092 0.9840711 -0.1683761 0.0636633 0.980098 -0.1880296 0.05594211 0.9796739 0.1926386 0.02105808 0.9997732 -0.003204464 0.04013246 0.9991928 -0.001770079 0.03988862 0.9992002 -0.002838253 0.05252355 0.9986197 0 0.03973513 0.9992085 0.001922667 0.05240178 0.9986253 0.001312315 0.03970474 0.9992113 4.88298e-4 0.05246245 0.9986185 0.002960324 0.05246204 0.9986109 0.004913508 0.05227953 0.9985914 0.009064197 0.05230885 0.9985997 0.007904291 0.05230885 0.9986301 0.001281738 0.05212622 0.9986389 -0.001770079 0.05252343 0.9986166 -0.00250256 0.05261486 0.9986149 4.88305e-4 0.03979676 0.9991921 0.005615472 0.0397973 0.9992064 0.001678526 0.05249261 0.9986119 0.004364192 0.05252283 0.9985758 0.009369254 0.05267596 0.9984937 0.01535111 0.05243188 0.9984038 0.02099716 0.05227881 0.9980589 0.03384542 0.03976565 0.9981697 0.04556417 0.05227899 0.9978789 0.03878957 0.03976613 0.9983967 0.04028499 0.05224841 0.997664 0.04400825 0.05221766 0.9967443 0.06143432 0.03970569 0.9963361 0.07574909 0.05218791 0.9963322 0.06781381 0.03970563 0.996792 0.06949251 0.0521568 0.9958928 0.07400834 0.05252319 0.99492 0.08588051 0.05209589 0.9952241 0.0825538 0.05212581 0.9955486 0.07852447 -0.2695797 0.2888376 0.9186402 -0.2832166 0.3818236 0.8797721 -0.2965518 0.3804787 0.8759526 -0.08835309 0.9957506 -0.02597182 -0.0732463 0.9969742 -0.02603292 0.05224859 0.9983393 0.0242626 0.05227905 0.9985818 0.01007121 0.05227929 0.998617 -0.005584955 0.05224877 0.9983732 -0.02282828 0.05221849 0.9977677 -0.0416283 0.0521565 0.9967116 -0.06201404 0.05206531 0.9951621 -0.08331674 0.05197334 0.9932623 -0.1035805 0.05188173 0.9912465 -0.1214032 0.01413047 0.9905375 -0.1365132 -8.85042e-4 0.992803 -0.1197553 -3.05187e-5 0.992622 -0.1212509 0.05154663 0.985704 -0.160408 0.01287889 0.9910364 -0.1329703 0.01409977 0.9924506 -0.1218322 0.02606368 0.9886501 -0.1479587 0.05047816 0.9837754 -0.1721569 0.05963414 0.9977894 0.02932876 0.04498547 0.9910854 -0.125404 0.04519814 0.9950309 -0.08871775 0.0453211 0.9985302 -0.02972579 -0.03936916 0.9992149 -0.004455685 0.03955215 0.9992114 -0.003479123 -0.02233994 0.9997448 -0.00338757 -0.0152291 0.9998746 -0.004364252 -0.01507657 0.9998769 -0.004364252 -7.93498e-4 0.9999908 -0.004211604 0.02670389 0.9996424 -0.001434326 0.02664285 0.9996423 -0.00238043 0.03967428 0.9992124 -8.54523e-4 0.03952169 0.9992123 0.003601193 0.03949213 0.9992062 0.005249321 0.02697861 0.9996145 0.006561517 0.02670449 0.9996331 0.004547357 0.03930872 0.9991996 0.007416129 0.03942996 0.9991776 0.009460747 0.02685654 0.9995836 0.01055949 0.02661263 0.9995923 0.01034593 0.03976625 0.9991626 0.009643971 0.03976666 0.999172 0.008606433 0.03979647 0.9991845 0.006836175 0.02670431 0.9996276 0.005615532 0.02670395 0.9996139 0.007690727 0.03979694 0.9991968 0.004699945 0.0397973 0.9992054 0.002227902 0.03976565 0.9992088 -7.01927e-4 0.03970474 0.9992108 -0.00112915 0.02673494 0.9995703 0.01202458 0.02673459 0.9996188 0.00689727 0.03982681 0.9991496 0.0106815 0.03982722 0.9990683 0.01663279 0.03979629 0.9989669 0.02194291 0.02670395 0.9991248 0.03219729 0.039797 0.9988622 0.026277 0.02670419 0.9992567 0.02780288 0.03976637 0.9987382 0.03067171 0.03976637 0.9985849 0.03531056 0.02667385 0.9979199 0.05868858 0.03973537 0.9979019 0.05111885 0.02667367 0.9982489 0.05279797 0.03973615 0.997586 0.05694907 0.03970557 0.9972181 0.06308335 0.02661275 0.9958439 0.08710199 0.0396744 0.9959194 0.08105784 0.02664291 0.996195 0.08298063 0.03964453 0.9956001 0.08490461 0.0396744 0.9953098 0.08822983 0.03946137 0.9955078 0.08606427 0.02661216 0.9965233 0.07895153 0.03967493 0.995902 0.08127254 0.02661275 0.996088 0.08426368 -8.24004e-4 0.9990891 0.04266506 0.01309251 0.9986958 0.04934883 -7.93486e-4 0.9985413 0.05398756 0.03970551 0.9973379 0.0611605 0.03970497 0.9978747 0.0516684 0.03973609 0.9983779 0.04077374 0.0397666 0.9988049 0.02841341 0.03976631 0.9991031 0.0145576 0.03976565 0.9992088 -7.62964e-4 0.03973633 0.9990546 -0.01764023 0.03973597 0.9985578 -0.0361042 0.03967469 0.9976369 -0.05609399 0.03961402 0.9962415 -0.07703071 0.03955227 0.9945142 -0.09683597 0.03946059 0.9926807 -0.1141398 -0.01351994 0.9940979 -0.1076408 -0.01516795 0.994371 -0.1048634 0.03927838 0.9877284 -0.1511623 -0.01513755 0.9954486 -0.09409105 -0.01504588 0.9967842 -0.0787087 -0.00137335 0.9937409 -0.1117008 0.03244149 0.9907642 -0.1316583 -0.00891143 0.9999473 -0.005096614 0.02661222 0.9996379 -0.003997921 -0.1016597 0.994807 -0.004944086 0.02664279 0.9996399 -0.003234922 0.02676492 0.9996418 -2.13631e-4 0.02670389 0.9996427 0.001159667 0.01324504 0.9999101 0.002105772 0.01324504 0.9999122 5.49335e-4 0.02670383 0.9996396 0.002746641 0.02725344 0.9995892 0.008881032 0.0269789 0.999593 0.00927776 0.02670377 0.9996382 0.003234922 0.02670395 0.9996433 3.35707e-4 0.01306194 0.9999139 0.00125122 0.01315349 0.9999124 0.001495361 0.02664291 0.9996451 3.05189e-5 0.02673429 0.9996382 0.002960264 0.02673494 0.9994799 0.01803696 0.02670395 0.9993686 0.02343839 0.02670449 0.9989622 0.03689795 0.01315379 0.998713 0.04898345 0.02670413 0.9987648 0.04190254 0.01315385 0.9989606 0.04364269 0.02670431 0.9985278 0.04721319 0.02667343 0.9975384 0.06485247 0.01309251 0.9967439 0.07956248 0.02664333 0.9970974 0.07132369 0.01312297 0.9972277 0.07324475 0.02664303 0.9966278 0.07760971 0.02658176 0.9955815 0.09006071 0.02627712 0.9956637 0.08923858 -7.93496e-4 0.9963262 0.08563655 0.01309245 0.996095 0.08731353 -7.93499e-4 0.9959027 0.09042835 -0.01507627 0.9981501 0.05890136 -7.93506e-4 0.9979556 0.06390774 -0.01507627 0.9975404 0.06845384 0.02661222 0.9970125 0.0725122 0.02664315 0.997547 0.064731 0.02664327 0.9981023 0.05551451 0.02664285 0.9986351 0.0449236 0.02667361 0.9991027 0.03289955 0.02667331 0.9994564 0.01937931 0.02667319 0.9996346 0.00439465 0.02667391 0.9995712 -0.01208567 0.02664333 0.998408 -0.04971587 0.02658206 0.9971792 -0.07019376 0.02655178 0.9956317 -0.08951312 0.0263378 0.9896683 -0.1409364 0.02630722 0.9885664 -0.1484742 -0.02957296 0.9968146 -0.07406979 -0.02972525 0.9980542 -0.05481159 0.03198397 0.9888793 -0.1452403 0.01928812 0.9966042 -0.08005183 0.03283864 0.9943765 0.1006828 0.01940977 0.9991474 -0.03643912 0.01937961 0.999318 0.03143465 -0.06744801 0.9977119 -0.004669427 0.01327586 0.9999048 -0.003784358 0.01321488 0.9999086 -0.002868771 0.01321452 0.9999108 -0.001922667 0.01324504 0.999912 -7.93484e-4 -6.10385e-4 0.999994 0.003418147 -6.10388e-4 0.9999986 0.001617491 0.01324534 0.9999048 0.003906428 0.01333677 0.9998939 0.005859613 0.01342815 0.9998796 0.00778222 0.01300114 0.9998714 0.00939989 0.01330608 0.9998502 0.01107823 0.01303148 0.9998561 0.01086467 0.01318436 0.9998753 0.008697986 -7.62963e-4 0.99997 0.007721185 -7.93492e-4 0.9999527 0.009705007 0.01315361 0.9998916 0.006622552 0.01315379 0.9999043 0.004303216 0.0131843 0.999904 0.004272699 0.01318395 0.9998787 0.008301019 -7.32451e-4 0.9998871 0.01501524 -7.32454e-4 0.9999518 0.009796559 0.01318401 0.9998221 0.01348924 0.0131843 0.9997218 0.01956284 0.01315379 0.9996003 0.02502584 -7.62968e-4 0.9993664 0.0355848 0.01315385 0.9994806 0.02942067 -7.62965e-4 0.9995152 0.03112894 0.01315361 0.9993405 0.03384542 0.01315373 0.9991679 0.03860676 -7.62986e-4 0.9980464 0.06247323 0.01315355 0.9984219 0.05459809 -7.62978e-4 0.9984028 0.05649089 0.01312297 0.9980809 0.06051838 0.01315349 0.9976835 0.06674414 -7.93497e-4 0.995808 0.09146577 0.01309263 0.9962954 0.08499562 -7.62973e-4 0.9961992 0.08710104 0.01309263 0.995927 0.08920705 0.01303148 0.9956442 0.09231925 -7.9349e-4 0.9955548 0.09418112 0.01312327 0.9956937 0.09177166 -7.9349e-4 0.995494 0.09482198 0.01309251 0.9965285 0.08221745 0.01309251 0.9970179 0.07605278 0.01309251 0.9975643 0.0685144 0.01309281 0.9981363 0.05960434 0.01309281 0.9992049 0.03766089 0.01309257 0.999614 0.02450662 0.01309263 0.9998652 0.009918689 0.01312315 0.999895 -0.006164789 -0.04403913 0.996084 -0.07666409 -0.04406964 0.9961154 -0.0762369 -0.02951192 0.9955017 -0.09003126 -0.02899271 0.9953046 -0.09234941 0.0127266 0.9915464 -0.1291278 -0.0299701 0.996003 -0.08414214 0.005829155 0.9959987 -0.08917748 0.001403808 0.9298146 0.3680256 -5.79866e-4 0.9999943 -0.003357112 -0.01507616 0.9998824 -0.002838194 -0.01507616 0.9998794 -0.003753781 -8.54542e-4 0.999997 -0.002319455 -6.71427e-4 0.9999992 -0.001159727 -6.40908e-4 0.9999999 6.10389e-5 -5.49342e-4 0.9999853 0.005401849 -7.93483e-4 0.9999713 0.00753808 -0.01486289 0.9998454 0.00939995 -0.01504576 0.9998589 0.007477104 -0.001037597 0.9999533 0.009613454 -9.76617e-4 0.9999334 0.01150572 -8.54543e-4 0.9999373 0.01117008 -0.01477122 0.9998351 0.01055955 -0.01504594 0.9998093 0.01245182 -7.62975e-4 0.999985 0.005432367 -7.93502e-4 0.9999961 0.002685666 -0.01519864 0.9998771 0.003875911 -0.01513761 0.9998773 0.004028558 -8.54541e-4 0.9999964 0.002563595 -7.62974e-4 0.9999837 0.005676507 -7.32459e-4 0.9997754 0.02118021 -7.6297e-4 0.9996439 0.02667343 -0.01504588 0.9987658 0.04733496 -7.62969e-4 0.9991843 0.0403763 -0.01504564 0.9989943 0.04223763 -7.62966e-4 0.9989668 0.04544222 -7.62978e-4 0.9987078 0.05081433 -7.62975e-4 0.9976351 0.06872874 -0.01501512 0.9963718 0.08377355 -7.62964e-4 0.9971638 0.07525879 -0.01501512 0.9968898 0.07736462 -7.62977e-4 0.9966617 0.08163851 -0.01504564 0.9954876 0.09369218 -0.01516801 0.99514 0.09729522 -0.02951222 0.996886 0.07312446 -0.01504594 0.9969412 0.07669478 -0.02951222 0.9962747 0.08102893 -7.93497e-4 0.9968149 0.07974642 -7.93501e-4 0.9973694 0.07248324 -0.3185644 0.4370113 0.8411529 -0.3333315 0.3948889 0.8561267 -0.3010436 0.3696513 0.879051 -8.24007e-4 0.9995514 0.02993893 -8.24023e-4 0.9998757 0.01574796 -8.24025e-4 0.9999998 9.15583e-5 -8.24006e-4 0.9998553 -0.01699894 -8.24003e-4 0.9993631 -0.03567624 -0.05752831 0.996263 -0.06442564 -0.05877906 0.9966507 -0.05685639 -0.05798655 0.9962403 -0.06436508 -8.85041e-4 0.9937794 -0.1113626 -0.0441001 0.9967848 -0.06689786 -0.0441311 0.9976199 -0.05298173 -9.76616e-4 0.99505 -0.09937071 -0.007141351 0.9995189 -0.03018301 0.006103813 0.9843704 0.176005 -0.00714147 0.9997463 0.02136337 -0.00827074 0.9948748 0.1007754 -0.05102699 0.9986892 -0.004028439 -0.01507622 0.9998852 -0.001525878 -0.01507622 0.9998864 1.22075e-4 -0.01507622 0.9998847 0.001831114 -0.02978622 0.9995482 0.004028439 -0.02975589 0.9995552 0.001983702 -0.01507616 0.9998796 0.003692746 -0.01507645 0.9998698 0.00576812 -0.01467955 0.9998272 0.01141399 -0.01507639 0.9998058 0.0126959 -0.02914559 0.9995266 0.009857594 -0.02935916 0.9994933 0.01229906 -0.01529014 0.999844 0.008850574 -0.01495432 0.9998661 0.00665313 -0.01504582 0.9998614 0.007141411 -0.0150457 0.9998227 0.01132237 -0.02954208 0.9993953 0.01834172 -0.02954274 0.9994798 0.01294022 -0.01504594 0.999748 0.01666343 -0.01504594 0.9996256 0.02285885 -0.01504564 0.9994831 0.02841275 -0.0295422 0.9987903 0.03930824 -0.01504588 0.9993454 0.03289949 -0.02954268 0.998959 0.03476148 -0.01504576 0.9991865 0.03741604 -0.01504588 0.9984935 0.05276751 -0.02948182 0.9973466 0.06656301 -0.0150457 0.9981756 0.05847382 -0.02951192 0.9977306 0.06051933 -0.01501512 0.9978058 0.06448578 -0.01501512 0.9973795 0.0707727 -0.02945113 0.9949295 0.09616631 -0.01501524 0.995889 0.08932846 -0.02942067 0.9953594 0.09161919 -0.01498502 0.9954826 0.09375566 -0.01519823 0.9951189 0.09750682 -0.04391664 0.9953739 0.08545291 -0.02948147 0.9957177 0.08762043 -0.04388588 0.9948183 0.09170871 -0.01501536 0.9958972 0.08923763 -0.01504588 0.9963866 0.08359169 -0.08829188 0.9956565 0.0295425 -0.07321572 0.9970952 0.02099722 -0.07321482 0.9966865 0.03543245 -0.01510691 0.9987357 0.04794538 -0.01510685 0.9992514 0.03561556 -0.01510685 0.9996464 0.02188199 -0.01510685 0.9998634 0.006714165 -0.01510691 0.9998371 -0.009888172 -0.01510679 0.9994934 -0.02801632 -0.01510667 0.9987822 -0.0469681 -0.01510703 0.9977983 -0.06457883 -0.01510709 0.9967347 -0.07932001 -0.01504576 0.9957087 -0.09131246 -0.01529008 0.9949574 -0.09912645 -0.07330602 0.9969254 -0.02768045 -0.0585348 0.9971364 -0.04788374 -0.05893146 0.9966172 -0.05728346 -0.05856585 0.9977867 -0.03149551 -0.02273684 0.9989875 -0.0388205 -0.1156669 0.9932708 -0.005859613 -0.02957284 0.9995562 -0.003601193 -0.04403942 0.9990216 -0.004059076 -0.0439164 0.9990305 -0.003082334 -0.02954244 0.9995606 -0.002441525 -0.02966445 0.9995593 -0.00112915 -0.02972549 0.9995581 2.13633e-4 -0.04407006 0.9990231 0.003265559 -0.04406958 0.9990131 0.005554437 -0.0298478 0.9995351 0.006225883 -0.02932906 0.9995382 0.007965505 -0.02969533 0.9995092 0.009979784 -0.02972507 0.9994832 0.0122379 -0.02960348 0.99947 0.01355046 -0.02948153 0.9994739 0.01352 -0.02942073 0.9995421 0.007080495 -0.02969461 0.9995459 0.005127072 -0.02963358 0.9995458 0.005493342 -0.02954232 0.9995258 0.008697867 -0.02954256 0.9992601 0.02462899 -0.02954256 0.9991069 0.03021395 -0.04400765 0.9977116 0.05133211 -0.02954256 0.9985875 0.0441612 -0.04400813 0.9979664 0.04611396 -0.0295121 0.9983471 0.04931914 -0.0295118 0.9980621 0.05478155 -0.04388654 0.9956879 0.0817303 -0.02948129 0.9969028 0.07290983 -0.04391723 0.9962102 0.07507741 -0.02945119 0.996397 0.07953351 -0.02945071 0.9958622 0.08597171 -0.0295118 0.9945824 0.09967488 -0.02954256 0.9944984 0.1004997 -0.04342824 0.9939364 0.1010172 -0.04382592 0.9936835 0.1033084 -0.02945101 0.9948347 0.09714263 -0.02948164 0.995236 0.09293138 -0.05844485 0.9961878 0.06476241 -0.07309329 0.9955039 0.06024473 -0.05850452 0.9968361 0.05380463 -0.02954244 0.9975165 0.06393748 -0.02957314 0.9981332 0.05343925 -0.02957278 0.9986994 0.04153615 -0.02960342 0.9991614 0.0282911 -0.02963399 0.9994682 0.01361149 -0.02963393 0.9995577 -0.002471983 -0.029603 0.9993607 -0.02005064 -0.02960336 0.9988242 -0.03839284 -0.02957278 0.9980285 -0.05536121 -0.02957302 0.9971526 -0.06937003 -0.02957272 0.9963176 -0.08047813 -0.07324486 0.9964964 -0.04037618 -0.08844506 0.9960603 -0.006439566 -0.02975583 0.9994603 0.01391655 -0.02136331 0.9656534 0.2589542 -0.02954208 0.9970462 0.07089495 -0.03622621 0.9839078 0.1749664 -0.07943981 0.9968282 -0.004791378 -0.05850499 0.9982785 -0.004150569 -0.04394704 0.9990323 -0.001800596 -0.04391664 0.9990352 -4.88302e-4 -0.04409933 0.9990265 0.00125122 -0.04410058 0.9989929 0.00827074 -0.04428243 0.9989646 0.0104373 -0.05853611 0.9982272 0.0107733 -0.05862766 0.9981968 0.01287913 -0.04379421 0.9989664 0.01217693 -0.0439164 0.9989387 0.01388597 -0.04437446 0.9989147 0.01416075 -0.04419142 0.9989459 0.01242119 -0.04419142 0.9989769 0.009613454 -0.05856508 0.9982316 0.01019316 -0.05862706 0.9982476 0.00802648 -0.0440998 0.9990055 0.006592035 -0.04406923 0.9990048 0.006897211 -0.04403883 0.9989767 0.01031535 -0.04403913 0.9989229 0.01461863 -0.05850487 0.9981536 0.01632761 -0.05850404 0.9980487 0.02182072 -0.04403901 0.9988286 0.020051 -0.04400879 0.9986823 0.02639913 -0.04403865 0.9985148 0.03207528 -0.04400795 0.9983587 0.03665292 -0.05847436 0.9975433 0.03857594 -0.05847394 0.9973533 0.04321455 -0.04400813 0.9981801 0.04123091 -0.04397755 0.9974151 0.05682593 -0.05838227 0.9961916 0.06476068 -0.05838292 0.9957759 0.07086521 -0.04397839 0.9970678 0.0626257 -0.04394775 0.996669 0.06869894 -0.0438863 0.9951329 0.08823037 -0.05835187 0.9936299 0.09640878 -0.05832165 0.9932078 0.1006819 -0.04385566 0.9946117 0.09393721 -0.04385578 0.9941567 0.0986374 -0.04379504 0.9937356 0.1028192 -0.0587179 0.9926807 0.1055335 -0.05835241 0.9925716 0.1067557 -0.04382514 0.9943677 0.09650081 -0.05826115 0.9930648 0.1021173 -0.05823081 0.9936782 0.0959832 -0.05838263 0.9948548 0.0827977 -0.07300144 0.9941263 0.07989877 -0.05841416 0.9955134 0.0744369 -0.04394745 0.9959909 0.07791525 -0.04400873 0.9966368 0.06912606 -0.04403948 0.9972829 0.05905503 -0.04407 0.9978933 0.04761028 -0.04406905 0.9984215 0.03482186 -0.04409933 0.9988129 0.02069157 -0.04413062 0.9990128 0.005096673 -0.0441308 0.9989553 -0.01187193 -0.04410016 0.9985875 -0.02963411 -0.04406952 0.9979735 -0.04590064 -0.04403924 0.9972775 -0.05914628 -0.04406946 0.9966299 -0.06918662 -0.08841246 0.9958536 -0.02142405 -0.1040705 0.994438 0.01620566 -0.08829164 0.9951044 0.04440522 -0.102057 0.9882506 0.1137765 -0.07968586 0.9943799 0.06970608 -0.04403948 0.998503 -0.03244209 -0.05157637 0.9985679 0.0142216 -0.05252385 0.9967637 0.06085568 -0.0521577 0.9907531 0.1252518 -0.1506415 0.9885694 -0.006134271 -0.05853563 0.9982804 -0.003112912 -0.05850541 0.9982854 -0.001831114 -0.05853593 0.9982853 9.15578e-5 -0.05853581 0.9982828 0.002258419 -0.05853533 0.9982752 0.00451678 -0.05856668 0.9982588 0.00701946 -0.07336735 0.9972655 0.008880972 -0.05853515 0.9982411 0.009399771 -0.05868875 0.998167 0.01477134 -0.05856537 0.9981752 0.01471 -0.05865818 0.9981971 0.01272654 -0.05853563 0.99825 0.008392751 -0.07318359 0.9972261 0.01358073 -0.05850493 0.9982162 0.01190239 -0.07309257 0.9968674 0.03021365 -0.05847495 0.9978896 0.0282303 -0.05847519 0.9977108 0.03396809 -0.07309377 0.9960592 0.05023479 -0.05844461 0.9971299 0.04812908 -0.0584433 0.9968628 0.05337715 -0.05841428 0.9965532 0.05890262 -0.05835318 0.9953008 0.07727527 -0.07294046 0.9941576 0.07956314 -0.05832147 0.9947612 0.08395725 -0.05829113 0.9941846 0.09054964 -0.07275789 0.991815 0.1049252 -0.07290965 0.9928411 0.0946086 -0.08792674 0.9917625 0.09314554 -0.07297104 0.9934562 0.08786433 -0.05832123 0.9942383 0.08993858 -0.05853533 0.9974209 0.04153627 -0.05856674 0.9978937 0.02789473 -0.0585668 0.9982001 0.01290971 -0.05859643 0.9982757 -0.003479123 -0.05856639 0.998071 -0.02060049 -0.05856543 0.9976272 -0.03619521 -0.05847501 0.997097 -0.04876989 -0.1040381 0.9945725 -0.001312255 -0.1205202 0.9918732 0.04077357 -0.1037641 0.9919238 0.07294005 -0.1192684 0.9812784 0.1512218 -0.0587188 0.9982501 -0.006988823 -0.04776275 0.9392944 0.3397721 -0.05075281 0.8398782 0.5403969 -0.06366199 0.9654893 0.2525422 -0.0731852 0.9973089 -0.004364252 -0.0731855 0.9973132 -0.003235042 -0.07318574 0.9973163 -0.002044796 -0.07339835 0.9973025 -5.18824e-4 -0.07315325 0.9973198 0.001373291 -0.07318544 0.997312 0.003570735 -0.07321488 0.9972977 0.006073236 -0.08829069 0.9960399 0.01046788 -0.07333713 0.9972391 0.01165825 -0.07361078 0.9971946 0.01358073 -0.07309323 0.9972122 0.01501536 -0.07284903 0.9972113 0.0162056 -0.0884754 0.9959359 0.01684659 -0.07303106 0.9971966 0.01629692 -0.0732451 0.997202 0.0149542 -0.07312238 0.9972538 0.01174962 -0.07361102 0.9971975 0.01336717 -0.07327592 0.9972671 0.009430348 -0.07321482 0.9972663 0.009979665 -0.07315474 0.997157 0.01806741 -0.0730316 0.9970513 0.02356052 -0.08810859 0.9953801 0.03814882 -0.0731551 0.9966735 0.03592133 -0.07312279 0.9964967 0.04058986 -0.07309335 0.9962977 0.04525989 -0.07306313 0.9957827 0.05548399 -0.08804798 0.9937064 0.06924813 -0.07300209 0.9950815 0.06695932 -0.07306152 0.9954561 0.0610677 -0.07297146 0.994652 0.07309353 -0.07290917 0.9935973 0.08630686 -0.08774346 0.9909672 0.1014162 -0.07281851 0.9924193 0.09900385 -0.07287991 0.9930045 0.09290057 -0.07315397 0.9913482 0.1089833 -0.07287961 0.9912909 0.1096856 -0.08734595 0.9901649 0.1092892 -0.07287955 0.9918705 0.1043142 -0.07294142 0.9922782 0.1003174 -0.1038567 0.9932461 0.05172997 -0.1037946 0.9925652 0.06357079 -0.1203674 0.9908644 0.06082457 -0.07303136 0.9948198 0.07071191 -0.1565929 0.9871973 0.03033584 -0.1576609 0.9867691 0.03781294 -0.1780766 0.9826107 0.05258369 -0.07315409 0.996141 0.04849469 -0.07324558 0.9973003 0.005218744 -0.07324647 0.997251 -0.0112006 -0.1381887 0.9893866 0.04492354 -0.1567146 0.982831 0.09738582 -0.1379778 0.9881236 0.06763076 -0.1205815 0.9924852 0.02081406 -0.07336831 0.9961488 -0.04800677 -0.07330662 0.9972696 -0.00891155 -0.07315379 0.9971747 0.01706004 -0.08041697 0.9890834 0.123479 -0.07941091 0.9777741 0.194041 -0.1917496 0.9814236 -0.006317377 -0.0882616 0.996087 -0.004547357 -0.08826202 0.9960915 -0.003418147 -0.08835327 0.9960878 -0.001709043 -0.08838367 0.9960865 2.44154e-4 -0.08844399 0.9960784 0.002349913 -0.08847349 0.9960671 0.004791378 -0.08847469 0.9960502 0.007507681 -0.1039797 0.994537 0.009186327 -0.08816957 0.9959896 0.01519846 -0.08823007 0.9960141 0.01309257 -0.1041918 0.9944307 0.01586985 -0.088261 0.995958 0.01666337 -0.08835178 0.9959799 0.01477104 -0.08822983 0.9960422 0.0107426 -0.08832144 0.9960123 0.01260423 -0.08859771 0.9959993 0.01165837 -0.08835375 0.9959713 0.01532071 -0.1036126 0.9944974 0.01547318 -0.0884127 0.9958871 0.01980662 -0.08853638 0.9957523 0.02526992 -0.08798742 0.9956652 0.03015315 -0.1038249 0.9941188 0.03079342 -0.08819931 0.9951875 0.04269576 -0.08813822 0.9947291 0.0524007 -0.08816909 0.9949774 0.04739582 -0.1037653 0.9930953 0.05472093 -0.08801579 0.9955188 0.0345776 -0.08810889 0.9944376 0.05771178 -0.08807808 0.9940986 0.06332713 -0.08801561 0.9932582 0.07544195 -0.08792483 0.9921686 0.08871835 -0.08795535 0.9927483 0.08194315 -0.1034899 0.990433 0.0912823 -0.08786368 0.9915566 0.0953713 -0.08786559 0.9902961 0.1076727 -0.08786463 0.989767 0.1124325 -0.08789592 0.9911487 0.09949326 -0.08774244 0.9906503 0.1044669 -0.1033362 0.9891099 0.1048011 -0.08771246 0.9898325 0.1119753 -0.1201539 0.9893702 0.08191341 -0.1037038 0.9918395 0.07416135 -0.1036419 0.9910985 0.08356046 -0.08798772 0.9924336 0.08563774 -0.08804655 0.9931408 0.07693773 -0.08813899 0.9938532 0.0669893 -0.08819866 0.9945394 0.05578792 -0.08826011 0.9951543 0.04333657 -0.3347703 0.404996 0.8508274 -0.3519142 0.4760348 0.8059449 -0.3695595 0.3996822 0.8388564 -0.08832198 0.9959878 0.01440495 -0.08835333 0.9960884 -0.001281797 -0.08835375 0.9959713 -0.01532071 -0.2658809 0.8654559 0.4246099 -0.2457089 0.9196918 0.3062587 -0.2733643 0.8897387 0.3655641 -0.2227914 0.9521127 0.2093933 -0.2204102 0.9417029 0.2541951 -0.1987094 0.9656831 0.1672443 -0.1571133 0.9849796 0.07162874 -0.1769207 0.9755514 0.1303787 -0.08829212 0.9955682 -0.03238087 -0.1413029 0.9515822 0.2729924 -0.1532684 0.961758 0.2270033 -0.1662667 0.9268887 0.3365011 -0.08838188 0.9959749 0.01492357 -0.1105713 0.9746021 0.1947433 -0.07278764 0.9038185 0.4216802 -0.09048831 0.9390643 0.3316175 -0.1039465 0.9945718 -0.004730343 -0.1039469 0.994576 -0.003692746 -0.1040712 0.9945667 -0.002533078 -0.103857 0.994592 -7.93501e-4 -0.1039475 0.9945822 0.001190185 -0.1039772 0.9945734 0.003540158 -0.1205215 0.9927077 0.002441525 -0.1039789 0.9945601 0.006225883 -0.1038872 0.9944976 0.01348942 -0.1038557 0.994519 0.01208543 -0.104101 0.9944076 0.0177927 -0.1040378 0.9944175 0.01760917 -0.1039468 0.9944524 0.01611387 -0.1039164 0.9944844 0.01422172 -0.1039187 0.9945071 0.01251298 -0.1037648 0.9945247 0.01239073 -0.1036728 0.9943066 0.02462875 -0.1037355 0.9944143 0.01947134 -0.1204286 0.9923611 0.02676528 -0.103949 0.993925 0.03616547 -0.103826 0.9935804 0.04492413 -0.1038269 0.9937718 0.04046869 -0.1203377 0.9916039 0.04733544 -0.1037945 0.9933571 0.04968458 -0.1037347 0.9927898 0.06006175 -0.1036735 0.9920245 0.07168942 -0.1037021 0.9924337 0.065737 -0.1201527 0.9899702 0.07431334 -0.1036119 0.9915614 0.07791489 -0.1035498 0.9910331 0.08444517 -0.1033697 0.9891995 0.103919 -0.1034297 0.9898004 0.09796679 -0.1198165 0.9870365 0.106785 -0.1033076 0.9887011 0.1086179 -0.1033075 0.987876 0.1158814 -0.1028493 0.9882388 0.1131648 -0.1033977 0.9878633 0.1159104 -0.1034585 0.9884107 0.1110882 -0.1376102 0.9855812 0.09845435 -0.1200636 0.9886168 0.09067326 -0.1199697 0.9878959 0.0983318 -0.1034612 0.9897181 0.0987612 -0.1035522 0.990384 0.0917412 -0.1039187 0.9938351 0.03863757 -0.1039788 0.9942843 0.0242322 -0.10404 0.9945302 0.009247303 -0.1039769 0.9945715 -0.004058957 -0.1043139 0.9944618 -0.01281797 -0.1032446 0.9944509 -0.02020335 -0.1032753 0.9944526 -0.01995921 -0.1909608 0.9288018 0.3175866 -0.1854007 0.902314 0.3891736 -0.1716096 0.9473473 0.2703393 -0.1044362 0.994464 -0.01159721 -0.1039481 0.9937641 0.04034626 -0.1084032 0.956341 0.2714048 -0.1385283 0.9238274 0.3568654 -0.1207045 0.9926761 -0.004944145 -0.1207653 0.992675 -0.003479182 -0.1205818 0.9927018 -0.001770079 -0.1380061 0.9904272 -0.002868711 -0.1205182 0.9927111 1.52593e-4 -0.1205203 0.9926979 0.005066156 -0.1205216 0.9926783 0.008026599 -0.1204878 0.9926506 0.01129186 -0.1377003 0.9904235 0.01001012 -0.1206099 0.9925906 0.01474052 -0.120642 0.9925426 0.01745688 -0.1207623 0.992497 0.01913517 -0.1205184 0.9925296 0.01898258 -0.1204878 0.9925593 0.01757872 -0.1204876 0.9925885 0.01583915 -0.1204907 0.9926139 0.01413047 -0.1206104 0.9925945 0.01446592 -0.1383122 0.9902511 0.01651078 -0.1204578 0.9925645 0.01748728 -0.1204593 0.9924844 0.02154654 -0.1203984 0.9921804 0.03289973 -0.1203967 0.9919832 0.0383926 -0.1203666 0.9918044 0.04284858 -0.1203382 0.9913635 0.05212718 -0.1202449 0.9907689 0.06259447 -0.1202775 0.9910915 0.05719357 -0.1379137 0.9882847 0.06537085 -0.1202135 0.9903958 0.06830102 -0.1200923 0.9894879 0.08057022 -0.1199386 0.9883186 0.09402817 -0.1200311 0.9889365 0.08716213 -0.1375494 0.9857349 0.09698951 -0.1198792 0.9876607 0.1007742 -0.1198179 0.986468 0.1119134 -0.1201826 0.9855098 0.1196943 -0.1197583 0.9860528 0.1155771 -0.1372156 0.9831857 0.120491 -0.1194514 0.9855204 0.1203365 -0.119725 0.9859998 0.1160628 -0.1564111 0.981163 0.113379 -0.1374871 0.984872 0.1054729 -0.1373953 0.9842293 0.1114239 -0.1198185 0.9866262 0.1105102 -0.1198797 0.9872381 0.1048337 -0.1570508 0.9850316 0.07104825 -0.1778933 0.9812973 0.07354998 -0.1571723 0.9857912 0.05926769 -0.1202454 0.9901325 0.07196408 -0.2557482 0.9563702 0.1412413 -0.22694 0.9690122 0.09753906 -0.2566049 0.9577819 0.1296452 -0.1204288 0.9915384 0.04846447 -0.1204881 0.9921039 0.03482186 -0.1205517 0.9924914 0.02069216 -0.1206115 0.9926646 0.008362233 -0.1205818 0.9927022 -0.001586973 -0.1205516 0.9927046 -0.002227902 -0.1206128 0.9926753 0.006958425 -0.211531 0.9047216 0.3697749 -0.2039608 0.8732197 0.4425917 -0.1203669 0.9904022 0.06793522 -0.1199697 0.9873465 0.1037031 -0.09659343 0.8600021 0.5010651 -0.09125196 0.7257431 0.6818872 -0.1174376 0.9019016 0.4156707 -0.1382222 0.9903845 -0.00576812 -0.1381292 0.990404 -0.00451678 -0.1380665 0.9904225 -9.76597e-4 -0.1380365 0.9904265 0.001190185 -0.1380057 0.9904244 0.003753781 -0.1575402 0.9875102 0.002197325 -0.1380078 0.9904088 0.00665313 -0.137945 0.9903357 0.01437431 -0.1379477 0.990355 0.01294022 -0.1573557 0.9874405 0.01416075 -0.137914 0.990301 0.01684629 -0.1380664 0.9902388 0.01910465 -0.1573875 0.9873574 0.01883029 -0.1382507 0.9901863 0.02044767 -0.1383745 0.9901683 0.02047842 -0.1570799 0.9873421 0.02194297 -0.1381604 0.9902256 0.01910501 -0.1376723 0.9903186 0.01776218 -0.13813 0.990288 0.01580893 -0.1381588 0.9902145 0.01968461 -0.1381589 0.9901233 0.02383518 -0.1381305 0.9899861 0.02911543 -0.1572347 0.9870511 0.03173989 -0.1380978 0.9897879 0.03534084 -0.1380977 0.9895727 0.04092568 -0.1380395 0.9891659 0.04996031 -0.138066 0.9893815 0.04541158 -0.1571425 0.986162 0.05282843 -0.138008 0.988915 0.05478203 -0.137945 0.9886265 0.05990839 -0.1377945 0.9874514 0.07715272 -0.1378538 0.9878966 0.07110899 -0.1568368 0.9843576 0.08026474 -0.1377012 0.9869505 0.08346915 -0.137641 0.9863765 0.0900923 -0.1374565 0.9850546 0.1037943 -0.1373034 0.9837993 0.1152689 -0.137368 0.9844045 0.1099005 -0.1562572 0.9805448 0.1188104 -0.1373041 0.9826444 0.1247304 -0.1368769 0.9832555 0.1203052 -0.137517 0.9827613 0.12357 -0.1563205 0.979826 0.1245192 -0.1373044 0.9836841 0.1162464 -0.1775926 0.9796133 0.0939083 -0.1569267 0.9842253 0.08169829 -0.1567759 0.9834125 0.09122115 -0.1377316 0.9863387 0.0903663 -0.1378227 0.9871295 0.08111888 -0.1379472 0.98791 0.07074373 -0.1380664 0.9886518 0.05920618 -0.1381278 0.9893261 0.04641896 -0.1382192 0.989844 0.03323483 -0.1382802 0.9901488 0.02200394 -0.1383726 0.9902769 0.01431334 -0.1381283 0.9903368 0.01239061 -0.1383121 0.989975 0.02862679 -0.1387084 0.9901554 0.01876908 -0.2425957 0.7912974 0.561245 -0.225292 0.7361817 0.6381849 -0.2231253 0.8367734 0.5000254 -0.1376389 0.985629 0.09793418 -0.1369717 0.9810509 0.1370328 -0.13572 0.9730522 0.1864129 -0.1572954 0.9875366 -0.005462884 -0.1573559 0.9875338 -0.004028499 -0.1574806 0.9875195 -0.002319455 -0.1782944 0.9839769 8.24024e-4 -0.1575108 0.9875172 -2.44155e-4 -0.1575683 0.9874954 0.005005061 -0.1572628 0.9875235 0.008117914 -0.1576308 0.987443 0.01043748 -0.1571415 0.9874984 0.01239061 -0.1783251 0.9837943 0.01867789 -0.1575087 0.9873827 0.01632767 -0.1574452 0.9873058 0.02093571 -0.157387 0.9872932 0.02194321 -0.1572621 0.9873363 0.02087467 -0.1574175 0.9873544 0.01873868 -0.1783244 0.9837599 0.02041739 -0.1574476 0.9873513 0.01864707 -0.1572973 0.9873048 0.02206557 -0.1572655 0.9872052 0.02633804 -0.1572332 0.986828 0.03805702 -0.1572051 0.9865986 0.04370367 -0.1571708 0.9863921 0.0482499 -0.1570832 0.9858977 0.05771207 -0.1778066 0.9814463 0.07175135 -0.1569622 0.9852335 0.06839436 -0.1570515 0.9855853 0.06289994 -0.1568992 0.984824 0.07419216 -0.1567441 0.9838315 0.08664256 -0.1565338 0.9825711 0.1002561 -0.1566545 0.9832341 0.0933274 -0.1773159 0.9786556 0.103887 -0.156441 0.9818611 0.1071221 -0.1563181 0.981185 0.1133169 -0.1562294 0.9798599 0.124367 -0.156226 0.9792889 0.1287896 -0.1563482 0.9792292 0.1290948 -0.156228 0.9805529 0.1187809 -0.1768606 0.9760447 0.126717 -0.1772865 0.9779902 0.110022 -0.200084 0.9721899 0.1217106 -0.2002375 0.9729571 0.1151495 -0.1565318 0.9818566 0.10703 -0.1566531 0.9826144 0.09964394 -0.1572352 0.9864437 0.04696911 -0.157875 0.9869251 0.03247225 -0.1573864 0.9867399 0.03967463 -0.1572633 0.9861541 0.05261439 -0.1798467 0.1576291 0.9709832 -0.145361 -0.01489317 0.9892666 -0.1666669 0.104987 0.980408 -0.1560751 0.9790253 0.1309579 -0.1550683 0.972527 0.1736241 -0.1192699 0.8041257 0.5823715 -0.1446294 0.8508083 0.5051808 -0.1784132 0.9839282 -0.007355034 -0.1782318 0.983968 -0.006347954 -0.1782922 0.9839644 -0.005096673 -0.1782934 0.9839711 -0.0035097 -0.1782943 0.983976 -0.001525938 -0.1782934 0.983971 0.003570735 -0.1779844 0.9840109 0.00665301 -0.2012131 0.9795142 0.008087575 -0.2014272 0.9794551 0.009735643 -0.1782299 0.9839266 0.01107829 -0.1779858 0.9839882 0.009399771 -0.1782603 0.9838955 0.01315355 -0.1781706 0.9838756 0.01562577 -0.1783854 0.9837294 0.02133297 -0.1785067 0.9836639 0.02325558 -0.1783821 0.9836807 0.02349942 -0.1785053 0.9836867 0.02227878 -0.1783208 0.9837399 0.02139359 -0.1781994 0.9836831 0.02475076 -0.1781702 0.983568 0.02914565 -0.2015456 0.9789489 0.03222775 -0.2015481 0.9787474 0.03784364 -0.1781411 0.983393 0.03470039 -0.1780815 0.9831566 0.0411098 -0.1780799 0.9829033 0.04678601 -0.1780176 0.9826827 0.05142456 -0.2011806 0.9780092 0.05499505 -0.2011219 0.9777457 0.05969566 -0.1779866 0.9824363 0.05603283 -0.1779237 0.9821514 0.06100678 -0.1778642 0.9818241 0.066226 -0.1777147 0.9810169 0.0776109 -0.2005711 0.9751445 0.09415125 -0.1776232 0.9805288 0.08374536 -0.2006934 0.9757252 0.08765077 -0.1775307 0.9799743 0.09018445 -0.1774367 0.9793504 0.09689736 -0.1771633 0.9779229 0.1108148 -0.1998693 0.9715744 0.1268677 -0.1770397 0.9772127 0.1171007 -0.1999939 0.9722579 0.1213148 -0.1768559 0.9765682 0.1226242 -0.1770092 0.9757787 0.1285453 -0.1770092 0.9750769 0.133764 -0.1768892 0.9749049 0.1351695 -0.199501 0.970252 0.1371512 -0.1764626 0.9754582 0.1316908 -0.1996235 0.9696133 0.1414242 -0.1999289 0.9715065 0.1272941 -0.1770097 0.9766052 0.1221061 -0.1996533 0.9709524 0.1318713 -0.1771344 0.9772609 0.1165535 -0.1774392 0.9787843 0.1024532 -0.1777443 0.9804626 0.08426374 -0.2892587 0.9399229 0.1813131 -0.3288195 0.9158662 0.2303628 -0.3265859 0.9096247 0.256758 -0.1780761 0.9820279 0.0625326 -0.4049288 0.410117 0.8172127 -0.3650429 0.449429 0.8153265 -0.3850303 0.5135467 0.7668256 -0.178139 0.9825879 0.05279773 -0.1781069 0.9819379 0.06384503 -0.1777761 0.9808665 0.0793507 -0.17744 0.9789112 0.101233 -0.2200772 0.1766477 0.9593548 -0.1806757 0.1611737 0.970247 -0.2053937 0.2123215 0.9553707 -0.1758196 0.970075 0.1674574 -0.1742047 0.9612693 0.2135747 -0.1791492 0.544345 0.8195084 -0.1426159 0.4516528 0.8807215 -0.1611702 0.6504185 0.7422803 -0.1683146 0.8785628 0.4469875 -0.2014856 0.9794727 -0.006073236 -0.2014872 0.9794805 -0.004577815 -0.2015178 0.9794812 -0.002685666 -0.2273972 0.9738008 -0.001678526 -0.2274893 0.9737728 -0.003906428 -0.2015185 0.9794847 -3.9675e-4 -0.2015181 0.9794823 0.00225836 -0.2011816 0.9795396 0.005310297 -0.2014582 0.9794268 0.01174992 -0.2277609 0.973607 0.01464891 -0.2277677 0.9736359 0.01245194 -0.2014234 0.9794063 0.01385545 -0.2015446 0.9793407 0.01648002 -0.2276998 0.9734849 0.02191239 -0.2014544 0.979317 0.01883006 -0.2275835 0.9735706 0.01913565 -0.2012733 0.9792962 0.02163797 -0.20121 0.9792544 0.02398771 -0.2014549 0.9791671 0.02545273 -0.2013315 0.9791909 0.02551358 -0.2012133 0.9792401 0.02453744 -0.2015193 0.9792135 0.02304208 -0.2275508 0.9734084 0.02639901 -0.2278542 0.9733398 0.02630728 -0.201731 0.9791435 0.02414053 -0.2274913 0.9732013 0.03357124 -0.201484 0.9790989 0.02774143 -0.2274287 0.9733475 0.02951198 -0.227396 0.9724837 0.05066126 -0.2013352 0.9785071 0.04458856 -0.2272108 0.9728103 0.04489278 -0.2012114 0.9782543 0.05032569 -0.2010607 0.9774397 0.06470078 -0.2270612 0.970595 0.07992917 -0.2009674 0.9770951 0.06997996 -0.2271527 0.971022 0.07428312 -0.200905 0.976692 0.07556444 -0.2008135 0.9762347 0.08148509 -0.2004473 0.9744954 0.1008951 -0.2261456 0.9667192 0.1196344 -0.2002964 0.9737706 0.1079457 -0.2263309 0.9675221 0.1125856 -0.2001426 0.9730021 0.114934 -0.1996879 0.9710029 0.1314467 -0.2252025 0.9633748 0.1455774 -0.1994414 0.9703201 0.1367555 -0.2255654 0.963971 0.1409974 -0.1995022 0.9696781 0.1411501 -0.2259942 0.9654425 0.1297979 -0.2549854 0.9558214 0.1462466 -0.2552936 0.9562602 0.1427996 -0.2263878 0.9670464 0.1164899 -0.2004188 0.9737725 0.1077018 -0.2261788 0.9662119 0.1236033 -0.2006036 0.9746353 0.09921836 -0.2007856 0.9755147 0.08975684 -0.2009708 0.9763183 0.08008313 -0.2014873 0.9767647 0.07303225 -0.2006044 0.9770503 0.07162916 -0.2014245 0.9762375 0.07992887 -0.200726 0.9753996 0.09113085 -0.2004466 0.9735454 0.1096841 -0.1997192 0.9705488 0.1347128 -0.1971224 0.958023 0.2081703 -0.1946215 0.9464034 0.257766 -0.1531739 0.3367446 0.9290538 -0.1409703 0.7363175 0.6617885 -0.1714273 0.782181 0.5990038 -0.1226557 0.5877952 0.7996578 -0.2276417 0.973711 -0.00814855 -0.2274921 0.9737542 -0.007080495 -0.227552 0.9737493 -0.005676567 -0.2586157 0.9659787 -0.001800596 -0.258709 0.9659548 0.00100708 -0.2273395 0.9738152 9.46103e-4 -0.2272443 0.97383 0.003906428 -0.2275216 0.9737499 0.006714224 -0.2277349 0.9736876 0.008331716 -0.2277953 0.9736542 0.01034599 -0.2277602 0.9735736 0.01672416 -0.2576405 0.9659231 0.02478134 -0.2583149 0.96569 0.02676534 -0.2274891 0.9734669 0.02472043 -0.2275487 0.9733997 0.02673453 -0.2276428 0.9733496 0.02774196 -0.2278525 0.9733021 0.02768045 -0.2582544 0.9656006 0.0303362 -0.2580354 0.96555 0.03363156 -0.2273955 0.9730309 0.03875887 -0.2579184 0.9652025 0.04315423 -0.2578558 0.9649224 0.04934936 -0.227368 0.9722806 0.05453777 -0.2273985 0.9720058 0.05911564 -0.2273347 0.9717196 0.06387591 -0.2575765 0.9638063 0.06878876 -0.2574592 0.9634579 0.07391726 -0.2272456 0.9713941 0.06894272 -0.2269403 0.970112 0.08591139 -0.226819 0.969566 0.09216809 -0.2569405 0.9615049 0.09741699 -0.2567864 0.9608587 0.103978 -0.226696 0.9689518 0.09869885 -0.2265123 0.9682774 0.1055043 -0.2259637 0.9659309 0.1261661 -0.2258123 0.9652037 0.1318739 -0.2557476 0.9568865 0.1377008 -0.2555672 0.9561644 0.1429516 -0.2256861 0.9645452 0.1368156 -0.2553265 0.9547123 0.1527503 -0.2552344 0.9540085 0.1572363 -0.2253526 0.9627842 0.1492075 -0.2255645 0.9627772 0.1489318 -0.2550165 0.9536872 0.1595226 -0.2553241 0.9537268 0.1587917 -0.2253555 0.9634679 0.1447231 -0.2255064 0.9641934 0.1395643 -0.2554761 0.9542738 0.1552205 -0.2549271 0.9550381 0.1513754 -0.2258417 0.9647409 0.1351693 -0.3316859 0.9224212 0.1977968 -0.2908475 0.9440795 0.155312 -0.3312559 0.9243668 0.1892498 -0.2265735 0.9679427 0.1084037 -0.2270897 0.9686334 0.1008948 -0.2264831 0.9694123 0.09457904 -0.2266367 0.968013 0.1076418 -0.2262082 0.9662985 0.1228702 -0.2255941 0.9634445 0.144506 -0.2245629 0.9589551 0.1731374 -0.2129355 0.3349836 0.9178478 -0.2447021 0.3087006 0.9191436 -0.2554432 0.2217503 0.9410502 -0.2166865 0.9266248 0.3072676 -0.1919664 0.8298504 0.5239248 -0.258314 0.9660222 -0.008667409 -0.2584948 0.9659833 -0.007538139 -0.2584689 0.9660007 -0.006042838 -0.2939578 0.9557902 -0.007355034 -0.2939891 0.9557927 -0.005554437 -0.2585569 0.9659872 -0.004150569 -0.2584923 0.9660044 0.004181027 -0.2581884 0.9660705 0.006836175 -0.2939019 0.9558069 0.007416188 -0.2939329 0.9557778 0.009613573 -0.2581632 0.9660596 0.008972644 -0.2581577 0.9660392 0.01107823 -0.2581583 0.9660111 0.01330614 -0.2581574 0.9659771 0.01559501 -0.2581622 0.9659339 0.01800632 -0.2581297 0.9658959 0.02035617 -0.2580048 0.9658854 0.02233964 -0.2584354 0.9655925 0.02902358 -0.2582831 0.9655939 0.03030544 -0.2937786 0.9553145 0.03268611 -0.2937752 0.9552731 0.03390651 -0.2581896 0.965617 0.03036624 -0.2579473 0.9657156 0.02926778 -0.2579779 0.9654107 0.03781312 -0.2577925 0.9646392 0.05490332 -0.2934138 0.954068 0.06051999 -0.2933221 0.9537928 0.06512838 -0.2577297 0.9643883 0.05941969 -0.2576402 0.9641213 0.06396752 -0.2573656 0.9630532 0.07931852 -0.2572436 0.9625961 0.08505612 -0.2927134 0.9518448 0.09116196 -0.2925585 0.9512881 0.09726512 -0.2571212 0.9620757 0.09109872 -0.2565773 0.9601429 0.1108772 -0.2563634 0.9593484 0.1180187 -0.2561438 0.9585021 0.1251573 -0.2913972 0.9474986 0.1316598 -0.2911234 0.9466165 0.1384354 -0.2559359 0.9576692 0.1317829 -0.2553233 0.9555245 0.1475906 -0.2902078 0.9436254 0.159219 -0.2896227 0.943059 0.1635803 -0.2555363 0.9571394 0.1363287 -0.2900541 0.9431947 0.1620262 -0.2903591 0.9439268 0.1571431 -0.2561452 0.9578057 0.1303768 -0.2565442 0.9585769 0.1237552 -0.3303739 0.9200722 0.2105237 -0.3768174 0.8789457 0.2923409 -0.2560832 0.9589312 0.1219531 -0.400532 0.4652019 0.7894058 -0.4183558 0.5427212 0.7283078 -0.4409123 0.4211357 0.7926166 -0.2550202 0.9536398 0.1597996 -0.2538296 0.9493965 0.1849778 -0.2521827 0.9429309 0.2174515 -0.2494916 0.9334497 0.2577317 -0.240488 0.9003348 0.3627158 -0.2331352 0.8737 0.4269618 -0.2094829 0.7863543 0.5811746 -0.1960261 0.6951711 0.6916003 -0.2939629 0.9557762 -0.008820056 -0.2939921 0.9558024 -0.003265559 -0.293689 0.9559009 -5.18831e-4 -0.3376073 0.9412842 -0.002319455 -0.3377261 0.9412445 3.66231e-4 -0.2935314 0.9559456 0.002716183 -0.2936844 0.9558858 0.00564599 -0.2939256 0.9557542 0.01190227 -0.3378182 0.9411237 0.01284861 -0.3377881 0.9410946 0.01550382 -0.2939614 0.9557102 0.01431351 -0.2939879 0.9556666 0.01651066 -0.2941105 0.9555769 0.01928788 -0.293964 0.9555661 0.02188247 -0.2939288 0.9555202 0.02423208 -0.2939026 0.9554734 0.02630776 -0.2939611 0.9554041 0.02810817 -0.3376042 0.9408178 0.02975624 -0.3376048 0.9407277 0.03247255 -0.2937164 0.9554024 0.03061068 -0.2938975 0.955243 0.03369289 -0.2935304 0.9553623 0.03350967 -0.2938097 0.9551945 0.03576862 -0.2938058 0.9550902 0.03848433 -0.3374814 0.9403579 0.04281842 -0.3374168 0.9401952 0.04672437 -0.2938423 0.9548958 0.04278838 -0.2938089 0.9546425 0.04831194 -0.2935345 0.9543688 0.05493468 -0.3369261 0.9397308 0.05819904 -0.3369897 0.9393412 0.06384551 -0.293224 0.9534971 0.06973528 -0.2931388 0.9531512 0.0746504 -0.2930113 0.9527674 0.07986778 -0.3364742 0.9376416 0.0872544 -0.3363237 0.9371591 0.09283995 -0.2928581 0.952338 0.08536094 -0.2923734 0.9506713 0.103643 -0.2921286 0.9499978 0.1102959 -0.3354053 0.9346486 0.118048 -0.3350969 0.9338461 0.1250662 -0.2919146 0.9492337 0.1172236 -0.2916739 0.9483903 0.1244276 -0.2908813 0.9457687 0.1446014 -0.2906645 0.9449649 0.1501848 -0.3335094 0.9292362 0.1590334 -0.3332352 0.9283831 0.1644966 -0.2904521 0.9442362 0.155099 -0.2900871 0.9422566 0.167338 -0.3324115 0.9262171 0.1778334 -0.331956 0.9253691 0.1830229 -0.2901483 0.9415245 0.1713055 -0.2899038 0.9413098 0.1728923 -0.3318314 0.9243853 0.1881486 -0.3318332 0.9236884 0.1915373 -0.2898436 0.9414959 0.1719774 -0.2895084 0.9422606 0.1683153 -0.3319606 0.9233371 0.1930053 -0.332561 0.9232178 0.1925417 -0.3827686 0.8925265 0.2385055 -0.3321413 0.924124 0.1888839 -0.2904813 0.9446596 0.1524432 -0.2900851 0.9425861 0.1654752 -0.2879471 0.9357745 0.2035009 -0.2859991 0.9295657 0.2326203 -0.2831235 0.920571 0.2690543 -0.2790695 0.9076778 0.3134344 -0.2988439 0.5673822 0.7673134 -0.2681102 0.510035 0.8173013 -0.2558114 0.8334776 0.4897711 -0.1931287 0.4179674 0.8876963 -0.3375409 0.9412693 -0.008850514 -0.3376634 0.9412397 -0.007171988 -0.3376311 0.9412652 -0.005005061 -0.3375169 0.9413179 0.001739561 -0.3375145 0.9413111 0.004181146 -0.3377841 0.9412053 0.00589013 -0.3378155 0.9411774 0.008118033 -0.3939651 0.9190689 0.01019322 -0.337818 0.941154 0.01040703 -0.3377513 0.9410464 0.01886057 -0.3376658 0.9410024 0.02227908 -0.3376359 0.9409433 0.02505636 -0.3939443 0.9186336 0.03033626 -0.3376067 0.9408856 0.02749806 -0.337574 0.9406353 0.03534132 -0.3377862 0.9404789 0.03741645 -0.3376906 0.9404676 0.03854525 -0.3378113 0.9403722 0.03979635 -0.3932066 0.9176449 0.05758929 -0.3373272 0.9399567 0.05188238 -0.3369005 0.9391039 0.06769138 -0.3927135 0.9160466 0.08145415 -0.3368732 0.9387772 0.07220894 -0.3367524 0.9384446 0.0769397 -0.3366259 0.9380662 0.0819438 -0.336109 0.9366372 0.09869939 -0.391407 0.9130388 0.1147211 -0.3358901 0.9360424 0.1048932 -0.3356506 0.9353841 0.1113342 -0.3347896 0.9329551 0.1323288 -0.3344548 0.9320116 0.1396232 -0.3341263 0.9310551 0.1466152 -0.3891471 0.9076945 0.15702 -0.3338175 0.9301295 0.1530531 -0.3329613 0.9275919 0.169441 -0.3327157 0.9268552 0.173896 -0.3871322 0.9027185 0.1876912 -0.3853907 0.899479 0.2059405 -0.3846963 0.8960479 0.2216009 -0.3842927 0.8939872 0.2304474 -0.3796875 0.8854491 0.2679877 -0.4359369 0.8191366 0.3727926 -0.3910171 0.7379333 0.5500547 -0.4066364 0.7659987 0.4978885 -0.440392 0.5989697 0.6687976 -0.3233501 0.9006804 0.2902063 -0.3185642 0.8883054 0.3308027 -0.3123941 0.8709862 0.3792005 -0.3039368 0.8479042 0.4343742 -0.2929821 0.8183661 0.4944072 -0.2794026 0.7807707 0.5588662 -0.2621949 0.7337551 0.6267834 -0.2407695 0.6753389 0.6970994 -0.2135122 0.6074234 0.7651466 -0.411952 0.9111591 -0.009216845 -0.3938126 0.9191302 -0.01055943 -0.4702615 0.8824461 -0.01196324 -0.3938442 0.9191325 -0.009064018 -0.3938137 0.9191633 -0.007049798 -0.3937311 0.9192146 -0.004516839 -0.3939999 0.9191095 -0.001403868 -0.3940259 0.9190987 0.001098632 -0.4702092 0.8825541 0.001312315 -0.3939725 0.9191166 0.003234982 -0.3939688 0.919108 0.005401849 -0.3939738 0.9190893 0.007721364 -0.3939386 0.9190478 0.0127874 -0.3939344 0.9190073 0.01553398 -0.3937856 0.9190163 0.01849442 -0.393845 0.9189208 0.02169883 -0.3938784 0.9188359 0.02450674 -0.3939682 0.9187099 0.02758902 -0.4699679 0.8821931 0.02942067 -0.3939094 0.9185625 0.03283846 -0.3937262 0.9185622 0.03497481 -0.4698778 0.8818908 0.03851556 -0.3935105 0.9185572 0.03744661 -0.3935377 0.9184886 0.03881967 -0.3936079 0.9183574 0.04114001 -0.3935413 0.9182835 0.04336732 -0.3940052 0.9180231 0.04464983 -0.3936371 0.9181101 0.04608404 -0.3933875 0.918067 0.04898267 -0.3933638 0.9178692 0.05273741 -0.3929348 0.9173769 0.06341892 -0.3929072 0.9167122 0.07254469 -0.3929984 0.9169556 0.06888228 -0.4685292 0.8793469 0.0850262 -0.3928483 0.9163817 0.07690936 -0.3925424 0.9156781 0.08627873 -0.3923524 0.9152652 0.09137392 -0.3919299 0.9142692 0.1024841 -0.3921723 0.9147838 0.096807 -0.4670655 0.8766328 0.1156066 -0.3916837 0.9136845 0.1084653 -0.3910976 0.9123272 0.1212509 -0.3907401 0.911554 0.1280289 -0.3899731 0.909744 0.1424326 -0.39037 0.9106904 0.1351081 -0.4644367 0.8717725 0.1559211 -0.389547 0.9087395 0.1498187 -0.3887259 0.9066711 0.1638283 -0.3878998 0.9046519 0.1764623 -0.3883217 0.9056465 0.1703256 -0.4615386 0.8660067 0.1923916 -0.3875039 0.9036774 0.1822309 -0.3867737 0.9017904 0.1928222 -0.3857965 0.9000799 0.2025271 -0.3862849 0.9009957 0.1974609 -0.4582748 0.8596315 0.2258718 -0.3849984 0.8985433 0.2107039 -0.3851237 0.8973301 0.2155887 -0.3841413 0.8950886 0.2263891 -0.4525114 0.8503932 0.2684488 -0.3831418 0.8938551 0.2328637 -0.4479576 0.8408285 0.3038775 -0.4414019 0.8289982 0.3434042 -0.5246894 0.6888533 0.5001823 -0.3816176 0.8898307 0.2501389 -0.4644427 0.6352898 0.6170088 -0.498037 0.5455549 0.6740393 -0.4541224 0.5726886 0.6824959 -0.3727289 0.8697922 0.3233186 -0.3671473 0.8571957 0.361135 -0.3596387 0.8401641 0.4059364 -0.3498104 0.8176079 0.4573293 -0.3372063 0.7887679 0.5139428 -0.3216436 0.7536148 0.5732453 -0.3032414 0.7112256 0.6341946 -0.2813254 0.6606478 0.695989 -0.2553805 0.6008827 0.7574436 -0.2251682 0.5309673 0.8169291 -0.4702939 0.8824496 -0.01031529 -0.4702436 0.8825002 -0.008026599 -0.4703601 0.8824592 -0.005218744 -0.4701237 0.8825958 -0.002899348 -0.591154 0.8065575 -0.001403868 -0.4699687 0.882683 -3.05194e-4 -0.4702666 0.8825168 0.003662228 -0.4702612 0.8825066 0.006042659 -0.4702411 0.8824955 0.008667469 -0.4702406 0.8824641 0.01144468 -0.4702355 0.882424 0.01437437 -0.4702013 0.8823866 0.01745665 -0.4701738 0.8823313 0.02069175 -0.4701408 0.8822655 0.02398771 -0.5907183 0.8062713 0.03128153 -0.4700635 0.8822313 0.02661311 -0.4699591 0.8820852 0.0326246 -0.4699364 0.8819778 0.03570759 -0.5903065 0.8058956 0.04550439 -0.4698429 0.8817909 0.04113984 -0.4698449 0.8816725 0.04358154 -0.5899366 0.8055244 0.05572807 -0.4696838 0.8816565 0.04559499 -0.4696319 0.8815211 0.04864782 -0.4696261 0.8813577 0.05157703 -0.4695398 0.881276 0.05371397 -0.4698774 0.8809438 0.05615574 -0.4695125 0.8809158 0.0595436 -0.4692853 0.8807378 0.06381446 -0.4691166 0.8804292 0.06909632 -0.4689299 0.8800257 0.07523018 -0.5884663 0.8022516 0.1004989 -0.4687169 0.8796607 0.0806322 -0.4683451 0.8790091 0.08942073 -0.4681283 0.8786371 0.0940895 -0.4678885 0.8782179 0.099065 -0.4676501 0.8777403 0.1042851 -0.5865746 0.7993224 0.130438 -0.4673703 0.8772119 0.1098384 -0.4667049 0.8760024 0.1216814 -0.4663354 0.8752943 0.1280285 -0.4659085 0.8745322 0.1346209 -0.5834075 0.7957915 0.1623322 -0.465446 0.8736993 0.1414558 -0.4649556 0.8727798 0.148566 -0.4638573 0.8707053 0.1634289 -0.4633167 0.8695621 0.1708788 -0.4627384 0.8684052 0.1781735 -0.5794671 0.7879128 0.2083542 -0.4621574 0.8672127 0.1853451 -0.4608983 0.8647871 0.1992892 -0.4602681 0.8635254 0.2060998 -0.4596126 0.8622466 0.2128073 -0.5728486 0.7795869 0.2531582 -0.4589478 0.8609469 0.2194026 -0.4575727 0.8582883 0.2323113 -0.4568397 0.8569446 0.2386285 -0.5657033 0.7707005 0.2932586 -0.4558997 0.8557657 0.2445829 -0.4540602 0.8532475 0.2565114 -0.5591115 0.7624914 0.3255786 -0.4536651 0.8512972 0.2635927 -0.4551386 0.8541517 0.2515425 -0.452082 0.8483749 0.275467 -0.5511765 0.7524811 0.3605231 -0.4508877 0.8474515 0.2802254 -0.4495446 0.8437583 0.2932264 -0.5474886 0.7293541 0.4102426 -0.4504366 0.845389 0.2870965 -0.5950307 0.5989983 0.5358542 -0.580566 0.5919802 0.5590195 -0.5391232 0.6989527 0.4699054 -0.4453333 0.8360681 0.320419 -0.5315595 0.5586914 0.6366384 -0.4978258 0.5690571 0.6544798 -0.4899855 0.6541177 0.5762327 -0.4285839 0.8058952 0.4084715 -0.4189096 0.7884998 0.4503141 -0.3723374 0.7034736 0.6053841 -0.350699 0.663554 0.6608377 -0.3262203 0.6186252 0.7147609 -0.2338975 0.4458213 0.8640229 -0.5907251 0.8067383 -0.01474064 -0.6630509 0.7484119 -0.01559507 -0.5909674 0.8065832 -0.01345878 -0.5910891 0.8065216 -0.0116887 -0.6630244 0.748508 -0.01159715 -0.591157 0.8065004 -0.009521961 -0.5911552 0.8065286 -0.006866753 -0.5910063 0.8066557 -0.004272699 -0.591154 0.8065574 0.00149542 -0.591095 0.8065908 0.004242122 -0.5911197 0.8065523 0.007141411 -0.5910649 0.8065608 0.01010179 -0.6630921 0.7484239 0.01306223 -0.5910377 0.8065348 0.01327586 -0.5909819 0.8065115 0.0167247 -0.590951 0.8064498 0.02038705 -0.5909104 0.8063751 0.02417111 -0.6631481 0.7479909 0.02728396 -0.6627823 0.7482661 0.02859634 -0.5908759 0.8062781 0.02795523 -0.5906763 0.8061753 0.03439557 -0.6622966 0.7481776 0.03991907 -0.5904912 0.806142 0.03814935 -0.5903321 0.8060721 0.04190278 -0.590177 0.805794 0.04886096 -0.6619243 0.7475908 0.05444568 -0.6617223 0.7476955 0.05545377 -0.5900973 0.8056575 0.05197495 -0.661205 0.7474836 0.06384676 -0.5901215 0.8051606 0.05893278 -0.5893267 0.8055557 0.06143522 -0.5899424 0.8049219 0.06378579 -0.6612278 0.7464983 0.07428359 -0.6609295 0.7466892 0.07501679 -0.5893038 0.8052302 0.06576979 -0.5897585 0.8047377 0.06769216 -0.5891733 0.8050051 0.06958377 -0.5899558 0.8042578 0.07156616 -0.5893562 0.8043944 0.07489407 -0.5895662 0.8038402 0.07907474 -0.5890436 0.8038044 0.08322477 -0.6607109 0.7443641 0.09686803 -0.5891702 0.8032308 0.08774226 -0.5888043 0.8027734 0.09415131 -0.5885668 0.8016228 0.1048341 -0.5880113 0.8014313 0.1093193 -0.6587896 0.7418021 0.1254038 -0.6587261 0.7410058 0.1303474 -0.5873737 0.8011916 0.1143862 -0.587374 0.800429 0.119605 -0.5868602 0.8000087 0.1248249 -0.5860275 0.7987456 0.1362982 -0.6564916 0.7383127 0.1546391 -0.5856731 0.7979071 0.142588 -0.5849584 0.7973403 0.1485666 -0.5843785 0.7964859 0.1552808 -0.5830088 0.7945681 0.1695953 -0.5824836 0.7934302 0.1765823 -0.6520075 0.7327607 0.1948026 -0.5814471 0.7924551 0.1842124 -0.5807772 0.7910534 0.1921783 -0.5803227 0.7894098 0.2001449 -0.5780268 0.7867147 0.2167143 -0.6463591 0.7245789 0.2391763 -0.5772363 0.7847959 0.2255964 -0.576203 0.7829402 0.2345097 -0.5746507 0.7813589 0.2434231 -0.5717717 0.7772249 0.2626762 -0.6369097 0.7132082 0.2927117 -0.6344681 0.7112549 0.3026 -0.5700302 0.775086 0.2725939 -0.5678442 0.7731788 0.2823961 -0.5640779 0.7678821 0.3036004 -0.5617105 0.7652752 0.3143808 -0.6246022 0.7015101 0.3431558 -0.6214886 0.6987016 0.3543559 -0.5568228 0.7594704 0.3363826 -0.6124912 0.6903153 0.3851226 -0.608983 0.6864717 0.3973619 -0.5539523 0.7563244 0.3480093 -0.6051993 0.6762789 0.4199771 -0.5497757 0.7470223 0.3737705 -0.5483106 0.739667 0.3901899 -0.5912506 0.6156966 0.5209036 -0.5440698 0.7149785 0.4390829 -0.5991234 0.6338543 0.4891625 -0.5097033 0.6708759 0.5386356 -0.5566664 0.5785485 0.5961579 -0.5367419 0.5641787 0.627384 -0.4177539 0.5443497 0.7274374 -0.2439706 0.447137 0.8605504 -0.1198771 0.4933333 0.8615404 -0.6632155 0.7482729 -0.01525962 -0.6633718 0.7481549 -0.01422208 -0.6630864 0.7484176 -0.01370298 -0.6633093 0.7482449 -0.01226878 -0.6637628 0.7478737 -0.0101934 -0.6628172 0.7487289 -0.008850574 -0.6636487 0.7480049 -0.007690906 -0.6628815 0.7487021 -0.00576812 -0.663387 0.7482598 -0.005005061 -0.6630522 0.7485659 -0.003326535 -0.6634577 0.7482096 -0.002533078 -0.6637515 0.7479526 -9.15561e-4 -0.6626344 0.748943 3.35712e-4 -0.6632663 0.7483833 7.01934e-4 -0.6633611 0.7482955 0.002471983 -0.6631639 0.7484666 0.003387689 -0.6635159 0.7481454 0.005035638 -0.6631401 0.7484703 0.006134212 -0.6636352 0.7480202 0.007355034 -0.6627498 0.7487828 0.009338796 -0.6632135 0.7483621 0.01010185 -0.6631488 0.7483885 0.0121771 -0.6633312 0.7481741 0.01507639 -0.6628789 0.7485466 0.01641935 -0.6634376 0.7480077 0.01831179 -0.6628494 0.7484867 0.01995962 -0.6633636 0.7479931 0.02133285 -0.6626935 0.7485134 0.02377444 -0.6628854 0.7483097 0.0248124 -0.6632534 0.7477624 0.0307638 -0.6627768 0.7481074 0.03259402 -0.66264 0.7481253 0.03488379 -0.6627848 0.7479333 0.03622621 -0.6623595 0.7481797 0.0388205 -0.662485 0.7478783 0.04233038 -0.6619391 0.7482789 0.04376506 -0.6624542 0.7476949 0.04590117 -0.6618328 0.7481402 0.04757893 -0.6623966 0.7475463 0.0490449 -0.6617402 0.7479864 0.05114954 -0.6618015 0.7478647 0.05212616 -0.6620734 0.7472513 0.0572226 -0.6611346 0.7479614 0.05877971 -0.6617196 0.7473567 0.05987882 -0.6621696 0.7467987 0.06183135 -0.660858 0.7478371 0.06329637 -0.6615324 0.7470163 0.06589072 -0.6612088 0.7472132 0.06689912 -0.6616571 0.7466837 0.06836307 -0.6610834 0.7470874 0.06949293 -0.6614037 0.7467038 0.0705595 -0.6609492 0.7469516 0.07217735 -0.6610791 0.7467774 0.07278859 -0.661167 0.746346 0.07632839 -0.6607412 0.7466223 0.07730519 -0.6612324 0.7460761 0.07837367 -0.6608624 0.746255 0.07977712 -0.6612862 0.7458239 0.0802955 -0.6615597 0.7453953 0.08200442 -0.660959 0.7458029 0.08313488 -0.661408 0.7451215 0.08563631 -0.6610726 0.7452136 0.08740645 -0.6620603 0.7440968 0.08942222 -0.6611093 0.7446712 0.09164947 -0.6605238 0.7448785 0.09415125 -0.6611286 0.7434989 0.1005899 -0.6602589 0.7440044 0.1025455 -0.6608944 0.7429301 0.1061764 -0.659729 0.7434426 0.1097768 -0.6597393 0.7427521 0.1142954 -0.6598959 0.7421464 0.117287 -0.6596937 0.7417587 0.1208238 -0.6583863 0.7401467 0.1367861 -0.65723 0.7397843 0.1441114 -0.6564974 0.739418 0.1492386 -0.6558631 0.7373195 0.1618752 -0.6546673 0.7364282 0.1705412 -0.6540177 0.7354418 0.1771615 -0.6532649 0.7345378 0.1835734 -0.6528398 0.7336551 0.1885486 -0.6512342 0.7315627 0.2017672 -0.650983 0.7297541 0.2089982 -0.6505188 0.7280684 0.2161987 -0.649091 0.7271296 0.2235255 -0.6468188 0.726809 0.2310285 -0.645722 0.7223554 0.2474789 -0.6443013 0.7206311 0.2560603 -0.642062 0.7193975 0.2649978 -0.639153 0.7181964 0.2750955 -0.6383442 0.7157414 0.2832507 -0.6315336 0.7093881 0.3129438 -0.6285734 0.7068856 0.324358 -0.627224 0.7042232 0.3326558 -0.6173114 0.6963256 0.3661386 -0.6158817 0.6932179 0.3743511 -0.6051588 0.6819747 0.410723 -0.603362 0.6687033 0.4345 -0.5982951 0.6603098 0.4539096 -0.6029096 0.6466438 0.4672816 -0.5694182 0.5801302 0.5824191 -0.4672255 0.5014686 0.7281687 -0.199321 -0.3029337 0.9319348 -0.2037433 -0.06927758 0.9765702 -0.2294393 -0.07843291 0.9701577 -0.6891007 -0.7147066 0.1197281 -0.9275999 -0.3282338 0.1783846 -0.9275934 -0.3285672 0.1778035 -0.9283353 -0.3272582 0.1763404 -0.9284707 -0.3285034 0.1732852 -0.9280225 -0.3302463 0.1723714 -0.6891861 -0.7145476 0.1201848 -0.688835 -0.7154777 0.1166115 -0.9295495 -0.3285682 0.167275 -0.6891218 -0.7147273 0.1194823 -0.9283432 -0.3322051 0.1667892 -0.9297506 -0.329307 0.164684 -0.9291734 -0.3279848 0.1704776 -0.9306551 -0.3281129 0.1619353 -0.6893664 -0.7148804 0.1171324 -0.9305489 -0.3297557 0.1591861 -0.9305574 -0.330186 0.1582414 -0.9315345 -0.3286602 0.1556474 -0.9316005 -0.3301268 0.152108 -0.6898241 -0.7150634 0.1132565 -0.9313123 -0.3313733 0.1511597 -0.9325396 -0.3290867 0.1485666 -0.9328227 -0.3300358 0.144631 -0.6900469 -0.7156832 0.107856 -0.9328496 -0.3310722 0.1420668 -0.6923948 -0.7175123 0.07593238 -0.9378934 -0.3322042 0.09998172 -0.6928883 -0.7178229 0.06808936 -0.9338539 -0.3305523 0.136573 -0.9324789 -0.3346108 0.1360844 -0.6904952 -0.7161923 0.101415 -0.9359592 -0.3319255 0.1174984 -0.6910434 -0.716771 0.09326624 -0.9354142 -0.3312556 0.1235723 -0.9349243 -0.3315908 0.1263493 -0.9344966 -0.3305835 0.1320258 -0.6916911 -0.7172358 0.0844776 -0.9359492 -0.3327766 0.1151472 -0.9369922 -0.332046 0.1085863 -0.9366712 -0.3336687 0.1063601 -0.9371927 -0.3347989 0.09787601 -0.9386973 -0.3326549 0.09048825 -0.6934536 -0.7179604 0.06045818 -0.9390609 -0.3326845 0.08652055 -0.9394338 -0.3332362 0.08011215 -0.6938235 -0.7181779 0.05319494 -0.9400145 -0.3329008 0.07449674 -0.6942118 -0.7182607 0.04660224 -0.9398651 -0.3340616 0.07110941 -0.940596 -0.3331455 0.06552428 -0.9399926 -0.3351623 0.06387674 -0.6945912 -0.7182742 0.0403161 -0.9410359 -0.3332416 0.0583226 -0.6946768 -0.7184817 0.0347613 -0.9416364 -0.3325667 0.0521571 -0.9410329 -0.3338204 0.05496525 -0.9413143 -0.3339448 0.04907542 -0.6949494 -0.7184491 0.02960348 -0.9397693 -0.3369595 0.05737555 -0.9419451 -0.33269 0.04535156 -0.9412128 -0.3343991 0.04791516 -0.6951699 -0.7186697 0.01590055 -0.6952551 -0.7184801 0.02017307 -0.9422487 -0.3336355 0.02923732 -0.941694 -0.3338167 0.0421772 -0.9412539 -0.3351659 0.04129296 -0.6949869 -0.7186089 0.02438497 -0.9421228 -0.3330237 0.03872865 -0.9420254 -0.3336626 0.03546285 -0.9422035 -0.333458 0.03253394 -0.9412999 -0.3357709 0.03482222 -0.2408235 -0.9705578 0.004669368 -0.2404875 -0.9706479 0.002929747 -0.9422982 -0.3340587 0.02188193 -0.6953158 -0.7186018 0.01214653 -0.9413356 -0.336261 0.028566 -0.9427757 -0.332906 0.01864737 -0.9424951 -0.3338194 0.01635831 -0.9426485 -0.3329041 0.02426278 -0.9423429 -0.333606 0.02639913 -0.9422869 -0.3341571 0.02084475 -0.6952655 -0.7187045 0.008362352 -0.6953738 -0.7186293 0.005218684 -0.9426135 -0.333696 0.01126152 -0.942275 -0.3346717 0.01062059 -0.9427744 -0.3331496 0.01370316 -0.9427763 -0.3333029 0.009064257 -0.9426876 -0.3336091 0.006714284 -0.9420774 -0.3353379 0.006225764 -0.6953199 -0.7186976 0.002044737 -0.9427771 -0.3333947 0.004394769 -0.9425604 -0.3340346 9.46101e-4 -0.6952902 -0.718729 -4.88308e-4 -0.9427428 -0.3335155 0.001861631 -0.9428856 -0.3331153 -0.00100708 -0.9426766 -0.3336967 -0.002716183 -0.695225 -0.7187857 -0.003051877 -0.9427039 -0.3335735 -0.006164848 -0.6952962 -0.7187047 -0.005188286 -0.9428649 -0.3331493 -0.004181146 -0.9423678 -0.3344585 -0.008972585 -0.6951943 -0.7187856 -0.007233023 -0.9427636 -0.3333594 -0.008270621 -0.06085437 -0.9981464 8.54525e-4 -0.07162868 -0.9974309 0.00100708 -0.05917638 -0.9982467 0.001342833 -0.9427285 -0.3333883 -0.0107426 -0.2406391 -0.9706135 -0.001586914 -0.2404884 -0.9706516 -9.15565e-4 -0.6950784 -0.7188835 -0.008514881 -0.9425291 -0.3339122 -0.01190251 -0.942722 -0.3332945 -0.01379442 -0.078799 -0.9968898 0.001159667 -0.07141393 -0.9974452 0.001861631 -0.08847439 -0.9960772 0.001556456 -0.6953172 -0.7186338 -0.009979724 -0.1539374 -0.9880806 1.22076e-4 -0.2392669 -0.9709538 3.96744e-4 -0.1529302 -0.9882327 0.002929806 -0.9427076 -0.3332697 -0.01529008 -0.6951684 -0.7187598 -0.01120054 -0.9424998 -0.3338211 -0.01605319 -0.1154242 -0.9933139 0.002197384 -0.113469 -0.993541 0.001068115 -0.9427566 -0.3330213 -0.01751774 -0.09134459 -0.9958179 0.001739561 -0.1008964 -0.9948953 0.001861631 -0.6896309 -0.724117 0.007995843 -0.2517855 -0.9677415 0.008972704 -0.208935 -0.9779292 -8.85059e-4 -0.1730117 -0.9849065 0.005127131 -0.9425943 -0.3334559 -0.01797592 -0.128758 -0.9916718 0.002929747 -0.3955634 -0.9184238 -0.005218803 -0.3520995 -0.9359614 -0.00149542 -0.9522311 -0.3049483 0.01620572 -0.2718985 -0.9621284 0.01950198 -0.3084893 -0.9511955 0.007843434 -0.5309394 -0.8380523 0.1255857 -0.9422237 -0.334614 0.01574796 -0.5341195 -0.7851108 0.313556 -0.9990003 -0.04461836 0.002777159 -0.6739515 -0.6591803 0.3335729 -0.5720867 -0.7328631 0.368278 -0.8676037 -0.4309635 0.2480611 -0.7771295 -0.5572419 0.2924917 -0.9433798 -0.2250487 0.243696 -0.9216877 0.3879328 2.13636e-4 -0.9705896 0.1595523 0.1802746 -0.9250168 0.3714228 0.07993066 -0.9514123 -0.07709205 0.2981137 -0.8573189 0.5144035 0.01983755 -0.7936859 0.6082504 -0.009705126 -0.7613546 0.6480686 -0.01861649 -0.02571475 -0.9996692 -4.62255e-4 -0.9278652 -0.3272843 0.178749 -0.927919 -0.3274452 0.1781736 -0.9251882 -0.3335438 0.1810396 -0.6856715 -0.7189983 0.1135613 -0.9219843 -0.3384271 0.1881812 -0.9235477 -0.3366901 0.1835742 -0.9215255 -0.339556 0.1883946 -0.9252698 -0.3310987 0.1850661 -0.9184921 -0.3425424 0.1975783 -0.6829347 -0.7212976 0.1154552 -0.9113948 -0.3546941 0.2086902 -0.680853 -0.7198565 0.135078 -0.9154905 -0.3426413 0.2108891 -0.8917779 -0.3763961 0.2511139 -0.9081734 -0.3449026 0.2371987 -0.9161345 -0.3324185 0.2240437 -0.1135596 -0.992922 -0.03479117 -0.1136533 -0.9933063 -0.02063089 -0.1541205 -0.9880191 -0.008087456 -0.9041795 -0.3393381 0.2594401 -0.6744785 -0.7176329 0.1734417 -0.8983509 -0.3327463 0.286785 -0.8880481 -0.3401976 0.3092512 -0.8840119 -0.3578346 0.3007948 -0.6613303 -0.7138851 0.2302402 -0.880827 -0.3244541 0.3447802 -0.8628271 -0.3390942 0.3748928 -0.6427403 -0.7037488 0.3026922 -0.8630185 -0.3466051 0.3675107 -0.8591745 -0.3113867 0.4060265 -0.8122198 -0.2928972 0.50449 -0.8248378 -0.3248445 0.4627295 -0.6152698 -0.687326 0.3860391 -0.8419997 -0.318714 0.4352676 -0.8151319 -0.3589339 0.454672 -0.7883063 -0.3146511 0.528742 -0.7549982 -0.3670003 0.5434046 -0.5784049 -0.6644087 0.4732958 -0.7749999 -0.3071433 0.5523027 -0.6857163 -0.3731337 0.6249516 -0.7264733 -0.3100421 0.6132785 -0.7554548 -0.2787061 0.5929678 -0.5289279 -0.6359892 0.5619192 -0.7104604 -0.3036983 0.6348334 -0.6853315 -0.2712211 0.6758401 -0.03515774 -0.9992807 0.01422178 -0.03647011 -0.9992514 0.01290947 -0.04043805 -0.9990187 0.01806741 -0.6518604 -0.3037885 0.6948315 -0.6327487 -0.3039989 0.7121895 -0.4705197 -0.5932693 0.6531791 -0.6072834 -0.3695645 0.7032987 -0.03818112 -0.9992688 -0.002015531 -0.5714804 -0.2712281 0.774497 -0.6112984 -0.2451297 0.7524799 -0.4800089 -0.4083799 0.7764132 -0.5265138 -0.3335116 0.7820188 -0.4096903 -0.5283185 0.7436622 -0.5439719 -0.2526979 0.800149 -0.4325186 -0.2902684 0.8536229 -0.4688399 -0.2279803 0.8533546 -0.5099127 -0.1845793 0.8401902 -0.4406987 -0.2375622 0.8656494 -0.3908604 -0.3718469 0.8419964 -0.07582247 -0.9971199 -0.001712262 -0.06870907 -0.9976347 0.002068519 -0.3368095 -0.4603511 0.8213624 -0.4165803 -0.1405692 0.8981655 -0.04217177 -0.9991093 -0.001454234 -0.3538384 -0.215892 0.9100489 -0.3813362 -0.162972 0.9099577 -0.3347643 -0.2271843 0.9145054 -0.2650879 -0.3927183 0.8806253 -0.2888681 -0.3771003 0.879972 -0.3145898 -0.1111196 0.9427013 -0.2890153 -0.134711 0.9477992 -0.2031694 -0.4078955 0.8901368 -0.2354277 -0.2986642 0.9248641 -0.2642374 -0.203351 0.9427762 -0.2311251 -0.2959489 0.9268201 -0.3227725 -0.2914901 0.900473 -0.1805836 -0.1824453 0.9664902 -0.04791498 -0.9987078 0.01693809 -0.07159733 -0.9969304 0.03167861 -0.07138341 -0.9938445 0.08472013 -0.08826076 -0.9917129 0.09335738 -0.04324585 -0.9990189 -0.009552538 -0.04690819 -0.9988364 -0.01120054 -0.03076303 -0.9995236 0.002502501 -0.04680162 -0.9986811 0.02111488 -0.03820967 -0.9990987 0.01849442 -0.03650051 -0.9991263 0.02035605 -0.03039723 -0.9993861 0.01742649 -0.02466201 -0.9996946 -0.00162059 -0.03039669 -0.9994911 0.009674429 -0.0215429 -0.9997671 -0.001317739 -0.03125667 -0.999511 -0.001010358 -0.02553004 -0.99964 0.008266508 -0.0231471 -0.9997129 0.006201982 -0.05971372 -0.9982143 -0.001583576 -0.04429411 -0.9990168 -0.001943826 -0.02429515 -0.9996957 -0.004268407 -0.02408552 -0.9997075 -0.002198398 -0.02762132 -0.9996137 -0.003108441 -0.02946984 -0.9995643 0.00171256 -0.02955228 -0.9995627 0.001126825 -0.03147584 -0.9995026 0.001956224 -0.03215098 -0.9994813 0.001872658 -0.03099054 -0.9995189 0.001293599 -0.02923882 -0.9995694 -0.002502858 -0.002227902 -0.9999948 0.002349972 -0.01052892 -0.9999436 -0.001434326 -0.01178032 -0.9999276 0.002441525 -0.02616733 -0.9996547 0.00243026 -0.0286898 -0.9995876 0.001311123 -0.02985888 -0.9995542 3.29178e-4 -0.02896404 -0.9995803 5.83863e-4 -0.03006535 -0.9995475 -0.001014292 -0.02108269 -0.9997778 -1.4194e-4 -0.01013219 -0.9999437 0.00314337 -0.01388615 -0.9998981 0.003326535 -0.01300096 -0.9998572 -0.01080363 -8.85062e-4 -0.9999986 -0.00149542 -0.01040703 -0.999933 -0.005066156 -0.01934319 -0.9998114 0.001814424 -0.02120345 -0.9997751 3.62982e-4 -0.02120423 -0.999775 -7.03364e-4 -0.0217688 -0.9997611 -0.002001583 -0.01934075 -0.999811 -0.002013921 -0.02107745 -0.9997759 -0.002005338 -0.004547357 -0.9999662 -0.006866812 -0.01461851 -0.9998881 -0.003204464 -0.01071208 -0.9999218 -0.006469964 -0.009674429 -0.9999478 -0.003296017 2.44153e-4 -0.9999893 -0.00463885 -0.00967437 -0.9999429 -0.004547238 0.005141377 -0.9999806 -0.003553688 -0.003784358 -0.9999561 -0.008575797 9.46097e-4 -0.9999938 -0.003418147 -0.003875851 -0.9999466 -0.009582877 -0.024661 -0.9996922 -0.002752542 -0.0246607 -0.9996935 0.002200424 -0.0251398 -0.9996519 0.008012712 -0.01755291 -0.9998021 0.009364426 -0.02738142 -0.9994901 0.01642745 -0.009552419 -0.9999524 -0.002014219 -0.0169683 -0.9998503 -0.00338751 -0.01684629 -0.9998553 -0.00238043 -0.02332478 -0.9997266 -0.001633942 -0.03201073 -0.9994869 -0.001227796 -0.02178019 -0.9997593 -0.002675771 -0.02414041 -0.9996452 0.01126146 -0.02249264 -0.9996884 0.01083433 -0.02383565 -0.9996023 0.01507657 -0.02465784 -0.9995105 0.01926082 -0.02478992 -0.9995135 0.01893323 -0.02542209 -0.9995817 0.01379448 -0.02945107 -0.9995358 0.007812917 -0.02948129 -0.999466 0.01409971 -0.02951204 -0.9995642 -8.24018e-4 -0.03381472 -0.9994282 -2.4415e-4 -0.0339986 -0.9993591 -0.0112006 -0.03070193 -0.9994614 -0.01159715 -0.03817868 -0.9979875 -0.05063027 -0.04348951 -0.9978176 -0.04968488 -0.03817915 -0.9985178 -0.03878951 -0.03384554 -0.9991304 -0.0243541 -0.03821009 -0.9989869 -0.0237745 -0.05929857 -0.9970897 -0.04791498 -0.05035692 -0.9975562 -0.04843419 -0.05035644 -0.9974855 -0.04986816 -0.04351985 -0.9983322 -0.03793489 -0.05932921 -0.9975798 -0.03625673 -0.05939078 -0.998169 -0.01147526 -0.07162892 -0.9974036 -0.007446706 -0.05038744 -0.9979833 -0.038607 -0.1250383 -0.4935002 0.8607107 -0.1529318 -0.3416628 0.9272963 -0.05938982 -0.9978777 0.02670407 6.10372e-4 -0.9990257 -0.04412984 -0.009613513 -0.9997197 -0.02163815 -0.009613513 -0.9989565 -0.04464966 -0.009613573 -0.9984421 -0.05496543 6.10374e-4 -0.9985116 -0.05453693 -0.01907449 -0.9982226 -0.05646049 -0.01461845 -0.9984837 -0.05307215 -0.004211664 -0.9989925 -0.04468041 -0.01165819 -0.9983022 -0.05707025 -0.003357112 -0.9984742 -0.05511808 -0.001800596 -0.9987065 -0.05081427 -0.01007121 -0.998699 -0.04998987 -0.01217693 -0.9984492 -0.05432325 -0.002685606 -0.9989964 -0.04470974 -0.01705992 -0.9983274 -0.05523878 -0.01705986 -0.9988434 -0.04495388 -0.01263493 -0.9982215 -0.05826109 -0.01199394 -0.9982789 -0.05740636 -0.0137946 -0.9983695 -0.05539202 -0.01635807 -0.9992787 -0.03427267 -0.005493402 -0.9997408 -0.02209573 -0.02069211 -0.99902 -0.03912574 -0.01709043 -0.9996106 -0.02206504 -0.01712089 -0.9997579 0.01382488 6.10385e-4 -0.9997795 -0.02099722 -0.009582817 -0.9998512 0.01434373 -0.01846379 -0.9998219 -0.003906369 -0.01342844 -0.9999024 0.003875911 -0.006591975 -0.999881 0.01394695 -0.01706033 -0.9978625 0.06308358 -0.01944029 -0.9997277 -0.01290935 -0.021272 -0.9978008 0.06277835 -0.02056944 -0.9996954 0.01364177 -0.02041709 -0.9978131 0.06286877 -0.02035605 -0.9918933 0.1254324 -0.009582996 -0.9979177 0.06378513 6.40907e-4 -0.9978926 0.06488418 -0.009521961 -0.9919052 0.1266242 -0.01675474 -0.9801378 0.1976084 -0.01696836 -0.9919185 0.125737 -0.0205391 -0.9801704 0.19709 -0.02008163 -0.9801546 0.197215 6.40907e-4 -0.9797034 0.2004514 -0.009186208 -0.9624471 0.2713139 -0.009369492 -0.9800131 0.1987127 -0.01635813 -0.962781 0.2697874 -0.01980721 -0.9628939 0.2691525 -0.01712131 -0.9404843 0.3394057 7.01935e-4 -0.9618341 0.2736325 -0.009125113 -0.9397356 0.3417803 -0.019746 -0.9407297 0.3385821 -0.008850395 -0.9108631 0.4126137 7.32462e-4 -0.9385278 0.3452032 -0.003723323 -0.8763676 0.4816283 8.5453e-4 -0.9085789 0.4177125 -0.01846414 -0.881856 0.4711574 -0.01791483 -0.8508797 0.5250551 -0.01910495 -0.8814525 0.4718862 -0.01916593 -0.9127631 0.4080394 -0.01977616 -0.9124511 0.4087077 -0.02023404 -0.9405341 0.3390964 -0.02359104 -0.910835 0.412096 -0.04471051 -0.8099169 0.5848382 -0.06186217 -0.7737501 0.6304631 -0.04730486 -0.8560048 0.5147992 -0.03106796 -0.8331294 0.552205 -0.03631806 -0.8676666 0.4958182 -0.09094786 -0.7975335 0.5963799 -0.08124089 -0.7266516 0.6821858 -0.1022688 -0.6656782 0.7391982 -0.1322679 -0.5591021 0.8184804 -0.1601334 -0.6636671 0.7306869 -0.116645 -0.7537677 0.6467057 -0.02282798 -0.8283096 0.5598056 -0.2406753 -0.9706057 -2.13635e-4 -0.2404885 -0.9706519 6.40896e-4 -0.2407683 -0.9705812 0.001678526 -0.2406414 -0.9705922 0.006531 -0.2406157 -0.9705812 0.008728563 -0.2406091 -0.9705546 0.01144444 -0.2405844 -0.9705169 0.0147103 -0.2405834 -0.9704518 0.01852518 -0.2405541 -0.9703652 0.02292007 -0.2405234 -0.9702424 0.02789473 -0.153784 -0.9880451 0.01083415 -0.153786 -0.9879966 0.01458811 -0.2404608 -0.9700835 0.03341847 -0.2404318 -0.9698759 0.03915637 -0.2403404 -0.9696934 0.04394793 -0.2402473 -0.9695954 0.04654175 -0.2404291 -0.969621 0.04504609 -0.2404874 -0.9697931 0.040834 -0.2405521 -0.9700213 0.03454768 -0.2406436 -0.9702653 0.02600228 -0.2407044 -0.9704781 0.01529008 -0.2407676 -0.9705782 0.002990901 -0.2412213 -0.9704701 -9.15567e-5 -0.2409454 -0.9705264 -0.004882991 -0.241372 -0.9702186 0.02038645 -0.2411606 -0.9688237 0.05676519 -0.2401269 -0.9645974 0.1090459 -0.2375914 -0.9551573 0.1767057 -0.2328282 -0.937661 0.2580368 -0.1822618 -0.7468708 0.6395035 -0.2009702 -0.8163632 0.5414445 -0.2254462 -0.9096284 0.3489274 -0.1008968 -0.6109661 0.7852008 -0.08124125 -0.6985468 0.7109375 -0.2151605 -0.869798 0.4440242 -0.07318639 -0.8240032 0.5618385 -0.1538481 -0.9880946 -9.15581e-5 -0.08844417 -0.9960808 7.93495e-4 -0.1134992 -0.9935382 9.15563e-5 -0.1134691 -0.9935415 4.88302e-4 -0.1538778 -0.9880899 0 -0.1540315 -0.988066 1.22078e-4 -0.1538778 -0.9880897 4.88307e-4 -0.153818 -0.988098 0.001556456 -0.1537831 -0.9881001 0.003021299 -0.1537865 -0.9880912 0.005066156 -0.1537839 -0.9880748 0.00766015 -0.1537544 -0.9879286 0.01889121 -0.1537569 -0.9878228 0.02377462 -0.1537252 -0.9876927 0.0288406 -0.1537241 -0.987564 0.03296047 -0.1533561 -0.9875829 0.03408926 -0.1537224 -0.987614 0.03143417 -0.1537564 -0.9877585 0.02630764 -0.1537841 -0.9879233 0.01892161 -0.1538162 -0.988056 0.00927776 -0.1538177 -0.9880958 -0.00262463 -0.1538165 -0.9879661 -0.01623618 -0.153877 -0.9877486 -0.02597165 -0.1539983 -0.9877747 -0.02420145 -0.1541829 -0.9877842 0.02258419 -0.1539072 -0.9857324 0.06814885 -0.1529906 -0.9798357 0.1285145 -0.1476513 -0.9464271 0.2871845 -0.1429213 -0.9160333 0.3747755 -0.1509789 -0.9674917 0.2028921 -0.1363596 -0.8750759 0.4643796 -0.1134089 -0.9935485 -3.3571e-4 -0.08841395 -0.9960837 -5.49345e-4 -0.1134992 -0.9935377 -9.766e-4 -0.1134992 -0.9935378 -8.85044e-4 -0.1134088 -0.9935483 6.10381e-4 -0.1134387 -0.9935427 0.002166807 -0.1134714 -0.9935311 0.004516839 -0.1134694 -0.993514 0.007385551 -0.1134693 -0.9934825 0.01083421 -0.1134704 -0.9934306 0.01483231 -0.1134383 -0.9933554 0.01940989 -0.1134402 -0.99325 0.02420175 -0.1134395 -0.9931525 0.02792495 -0.1133475 -0.9931491 0.02841317 -0.1134404 -0.9932218 0.02533102 -0.1294618 -0.9914114 0.01852506 -0.1330309 -0.9909109 0.01995921 -0.13282 -0.9910228 0.01525962 -0.1191173 -0.9928577 0.006683707 -0.113624 -0.9934706 -0.01028501 -0.1134689 -0.9932348 -0.02468967 -0.113471 -0.992917 -0.03521931 -0.113744 -0.9934822 0.007446587 -0.1119743 -0.9777688 0.177285 -0.1099005 -0.9599283 0.2577978 -0.1136536 -0.9922713 0.04980731 -0.1131349 -0.9878475 0.1065732 -0.1275081 -0.8206238 0.5570623 -0.1069696 -0.9340389 0.3407769 -0.1029729 -0.8994111 0.4248016 -0.08847451 -0.9960784 1.22076e-4 -0.08856528 -0.9960697 -0.001220703 -0.08829259 -0.9960922 -0.002197384 -0.08853495 -0.9960719 -0.001556456 -0.08844423 -0.9960811 4.27267e-4 -0.08844393 -0.9960778 0.002594053 -0.08844298 -0.9960673 0.005279719 -0.08844369 -0.9960446 0.008545279 -0.0884428 -0.9960042 0.01239049 -0.08844518 -0.9959391 0.01681613 -0.08841246 -0.9958536 0.02142405 -0.09012281 -0.9956239 0.02472043 -0.06656247 -0.9976437 0.01663297 -0.09814906 -0.9948579 0.02499502 -0.111395 -0.9934604 0.02505624 -0.1392891 -0.9901309 0.01547312 -0.1342552 -0.9908153 0.01614481 -0.09839463 -0.9951474 4.88311e-4 -0.07956182 -0.9967663 -0.01126134 -0.08829057 -0.995978 -0.01525932 -0.08841258 -0.9956412 -0.02969461 -0.08841323 -0.9952516 -0.04071217 -0.08847522 -0.9952322 -0.04104834 -0.08853507 -0.9956765 -0.02810782 -0.08746761 -0.9829577 0.1616899 -0.08862578 -0.9960638 -0.001556396 -0.08856588 -0.9953136 0.03882002 -0.09753906 -0.853528 0.5118361 -0.08606296 -0.9670187 0.2397251 -0.08401811 -0.9438229 0.3195924 -0.02285873 -0.8789798 0.4763111 -0.02127158 -0.8468965 0.5313322 -0.08127152 -0.9130609 0.3996434 -0.06643992 -0.9977895 0.00137335 -0.07178056 -0.9974204 1.52595e-4 -0.07141399 -0.9974462 -0.001068115 -0.07159817 -0.9974305 -0.00250256 -0.07147455 -0.9974398 -0.002288877 -0.07150512 -0.99744 -6.40891e-4 -0.07150506 -0.9974395 0.001342773 -0.06772148 -0.9976941 0.004486262 -0.06045871 -0.9981649 0.003418147 -0.06448745 -0.9978924 0.007233083 -0.06213736 -0.9980128 0.01046812 -0.06180018 -0.9979898 0.01403856 -0.08294957 -0.9963409 0.02060002 -0.1055344 -0.9942148 0.01998984 -0.133551 -0.9907984 0.0219736 -0.1695032 -0.9853713 0.01767057 -0.06802666 -0.9976027 -0.01269584 -0.07159721 -0.997265 -0.01834183 -0.07147508 -0.9968976 -0.03296029 -0.07147651 -0.9964601 -0.04425317 -0.07150632 -0.9964197 -0.0451073 -0.05923753 -0.9951361 0.0787087 -0.07156622 -0.9968922 -0.03292959 -0.07760983 -0.8725996 0.4822309 -0.07083493 -0.985921 0.1514665 -0.06976646 -0.9712069 0.2277939 -0.06827044 -0.9497438 0.3054928 -0.06622666 -0.9214661 0.3827717 -0.05627781 -0.998413 0.002105832 -0.05920672 -0.9982442 0.001800596 -0.06149661 -0.9981073 0 -0.05920642 -0.9982391 -0.003662228 -0.06494486 -0.997887 -0.001922667 -0.07168936 -0.9974253 -0.001861631 -0.07745712 -0.9969937 -0.002014219 -0.08127206 -0.9966895 -0.002227842 -0.0842626 -0.9964413 -0.00213629 -0.08642917 -0.996255 -0.002441465 -0.0853914 -0.9963449 -0.00225836 -0.08264625 -0.9965772 -0.001892149 -0.0777933 -0.9969693 -8.24017e-4 -0.07123184 -0.9974597 5.18827e-4 -0.05435353 -0.9985061 0.005584895 -0.04791456 -0.998821 0.007812798 -0.04574751 -0.998877 0.01232951 -0.05661267 -0.998306 -0.01342833 -0.05914622 -0.9980393 -0.02047836 -0.05929929 -0.9976199 -0.03518891 -0.05926793 -0.997148 -0.04672461 -0.05044847 -0.9986237 -0.01434409 -0.06354022 -0.8846197 0.461964 -0.05881005 -0.9877769 0.1443547 -0.05981796 -0.8416024 0.5367749 -0.05798673 -0.9739027 0.219434 -0.05679541 -0.9536205 0.295605 -0.05520999 -0.9270647 0.3708137 -0.05292069 -0.998596 0.00238049 -0.07107859 -0.997451 -0.006286859 -0.08346855 -0.9964955 -0.005462825 -0.0934484 -0.9956133 -0.00463885 -0.1010167 -0.9948775 -0.003814816 -0.1061156 -0.9943495 -0.002929806 -0.1086793 -0.9940754 -0.001739561 -0.1053822 -0.9944314 -8.24013e-4 -0.09863644 -0.9951235 3.05187e-4 -0.08884048 -0.9960451 0.001281738 -0.07422226 -0.99724 0.001922667 -0.05581378 -0.9984232 0.00599122 -0.05050837 -0.9984799 -0.02206498 -0.05035585 -0.9980541 -0.03677505 -0.0504477 -0.998456 0.02325534 -0.05032545 -0.9959506 0.07449638 -0.05316364 -0.8927041 0.4474965 -0.04996025 -0.9889819 0.1393517 -0.04931813 -0.9756823 0.2135697 -0.04834216 -0.956223 0.2886187 -0.04672509 -0.9309628 0.3621122 -0.05383539 -0.9985489 0.001403868 -0.05417174 -0.998531 0.001129209 -0.04352033 -0.9977329 -0.05133324 -0.01913553 -0.9998099 0.00375384 -0.04355019 -0.9982376 -0.04031521 -0.04351973 -0.9987883 -0.02298063 -0.043581 -0.998915 -0.01641917 -0.04358154 -0.9988356 0.02069205 -0.04348921 -0.9964984 0.07141387 -0.04501616 -0.8985233 0.4366113 -0.04321444 -0.9898132 0.1356557 -0.0423603 -0.9769729 0.2091159 -0.04156726 -0.958154 0.2832192 -0.03851515 -0.9343743 0.3542053 -0.03399825 -0.9993789 0.00927776 -0.03820925 -0.9992697 3.05186e-4 -0.03817868 -0.9978961 -0.05240035 -0.03820943 -0.9992139 -0.01055943 -0.03820997 -0.9984036 -0.0415976 -0.03824055 -0.9991069 -0.0179758 -0.03823995 -0.9990918 0.01879954 -0.03817939 -0.9968771 0.06912583 -0.03720349 -0.9034134 0.4271536 -0.03796571 -0.9904047 0.13288 -0.03546321 -0.9781391 0.2049056 -0.03482246 -0.9599232 0.2780917 -0.04583966 -0.9987679 0.01901334 -0.03613495 -0.9990525 0.0242629 -0.04576534 -0.9988191 0.01631623 -0.06356823 -0.997765 0.02059948 -0.03626227 -0.999142 0.02001166 -0.06301599 -0.9978693 0.0169093 -0.03588277 -0.9991546 0.02006691 -0.03384566 -0.999256 0.01849454 -0.03381532 -0.9993222 0.01455765 -0.02948141 -0.9992551 -0.02490353 -0.0338146 -0.9993935 0.008331537 -0.0338152 -0.9986488 -0.03946125 -0.03378504 -0.9981084 -0.05136424 -0.03583669 -0.9978395 -0.05506652 -0.03393715 -0.9980041 -0.05325573 -0.03384554 -0.9985213 -0.04254347 -0.03384518 -0.9992428 -0.01919621 -0.0338453 -0.9992774 0.01730412 -0.03583461 -0.9978396 -0.05506622 -0.03378498 -0.997161 0.06729531 -0.03347927 -0.990859 0.1306822 -0.03091591 -0.9372752 0.347217 -0.02772808 -0.9996129 -0.002287864 -0.0329445 -0.9994548 -0.002230703 -0.04043442 -0.9991729 -0.004313588 -0.03218358 -0.9994819 -2.92329e-4 -0.04118138 -0.9991462 -0.003335475 -0.03070211 -0.9995282 9.1557e-4 -0.03048855 -0.9995306 0.003051877 -0.03698897 -0.9993131 0.002288877 -0.0321837 -0.9994793 -0.002335548 -0.03218322 -0.999482 -2.92091e-4 -0.03393763 -0.999407 0.005824089 -0.05216443 -0.9986316 0.003721833 -0.0308243 -0.9993487 0.01876926 -0.03588575 -0.999206 0.01731115 -0.03236466 -0.9992776 0.01992136 -0.03195881 -0.9992953 0.01968783 -0.02954226 -0.9994015 0.01800608 -0.02942019 -0.9987624 -0.04010182 -0.02945059 -0.9982079 -0.05209553 -0.0321325 -0.9979161 -0.05595529 -0.03064066 -0.9980797 -0.05383473 -0.02948158 -0.9986215 -0.04342889 -0.02945125 -0.9993596 -0.02032595 -0.02948141 -0.9994389 0.01590043 -0.03172397 -0.9979394 -0.05577212 -0.02969479 -0.9078134 0.4183217 -0.02941995 -0.9974113 0.06561511 -0.02929836 -0.991231 0.1288518 -0.0285663 -0.874782 0.4836739 -0.02923685 -0.9790993 0.2012705 -0.02865749 -0.9613545 0.2738181 -0.0245071 -0.9621865 0.2712873 -0.0257889 -0.939023 0.3428862 -0.03233855 -0.9994767 -7.57114e-4 -0.02684795 -0.9996334 -0.003529429 -0.02939629 -0.9995657 0.002093493 -0.02892512 -0.9995797 0.002005696 -0.03184807 -0.9994917 0.001508295 -0.02524983 -0.9996804 -0.001287698 -0.02387714 -0.9997099 -0.003195047 -0.02846133 -0.9995949 -2.29355e-4 -0.0296247 -0.9995494 -0.004852831 -0.02902269 -0.9995765 -0.00212419 -0.03480058 -0.9993823 -0.004910051 -0.02876788 -0.9995814 -0.003088355 -0.02924227 -0.9995639 -0.004123866 -0.02961349 -0.9995502 -0.004736185 -0.02924215 -0.9995723 -4.7534e-4 -0.02856773 -0.999589 0.002432465 -0.03610384 -0.999342 -0.00350964 -0.05368316 -0.9985559 -0.002075254 -0.04974627 -0.9987412 -0.006439507 -0.02924203 -0.9995646 -0.003957092 -0.03218293 -0.9994794 0.00232774 -0.02924221 -0.9995692 -0.00250405 -0.03218179 -0.9994748 0.003821313 -0.02924335 -0.9995722 -4.75882e-4 -0.02786439 -0.9994646 0.01715141 -0.02923852 -0.9994146 0.01776653 -0.03178942 -0.9992994 0.0197547 -0.0292375 -0.9993795 0.01964098 -0.0292378 -0.9993919 0.01900202 -0.02710092 -0.9995604 -0.01202446 -0.02697873 -0.9981523 -0.05444574 -0.02889496 -0.9980182 -0.05590057 -0.02537769 -0.9996754 -0.002290129 -0.02495443 -0.9996843 -0.002953708 -0.02722084 -0.9996275 0.002018928 -0.0272029 -0.999629 0.001468896 -0.02668768 -0.9996424 0.001745343 -0.02658587 -0.9996459 0.001149833 -0.0264821 -0.9996493 3.36877e-4 -0.02777034 -0.9996144 4.29533e-5 -0.02730494 -0.9996269 7.66895e-4 -0.02691948 -0.9996368 -0.001285851 -0.02946138 -0.9995632 -0.002347767 -0.02740579 -0.9996244 -1.49879e-4 -0.0297479 -0.9995511 -0.003579556 -0.02748936 -0.9996211 -0.001430869 -0.02691912 -0.999625 -0.005036652 -0.02924287 -0.9995592 -0.005137741 -0.02994698 -0.9995399 -0.004841625 -0.02691942 -0.9996348 -0.002389013 -0.02895456 -0.9995691 -0.004848897 -0.02717673 -0.9996231 -0.003912925 -0.02924209 -0.9995646 -0.003957152 -0.02924185 -0.9995602 -0.004935979 -0.02691912 -0.999625 -0.005040824 -0.02924221 -0.9995692 -0.002503931 -0.02691972 -0.9996293 -0.004074037 -0.02924335 -0.9995701 0.002130627 -0.02691876 -0.9996342 -0.002632141 -0.02978897 -0.9995467 0.004395246 -0.02691954 -0.9996351 0.00225383 -0.02923744 -0.9993795 0.01964104 -0.02691489 -0.9994484 0.01945883 -0.02691429 -0.9994487 0.01944303 -0.02539181 -0.9996501 0.007416069 -0.02691447 -0.9994487 0.01944291 -0.02542221 -0.999676 -0.001312255 -0.02735996 -0.9994422 0.01915222 -0.02710634 -0.9994945 0.01661354 -0.02545303 -0.9993527 -0.02542251 -0.02545267 -0.9988504 -0.0406205 -0.02707421 -0.9980086 -0.05697131 -0.02542209 -0.9986956 -0.04428267 -0.02548366 -0.9994483 -0.02130252 -0.02533107 -0.9982903 -0.05267649 -0.02548354 -0.9995666 0.01474076 -0.02545303 -0.9976136 0.06418198 -0.02530062 -0.9915773 0.127022 -0.02499514 -0.9796652 0.1990765 -0.02240127 -0.9400308 0.3403533 -0.02670717 -0.999641 0.002137243 -0.02442526 -0.9996993 0.002177298 -0.02498257 -0.9996858 0.002061784 -0.02466118 -0.9996945 0.001658499 -0.02466118 -0.9996955 7.8023e-4 -0.02528721 -0.9996792 0.001487374 -0.02466142 -0.9996958 -1.52615e-4 -0.02466148 -0.9996956 7.80151e-4 -0.02377402 -0.999717 -9.29292e-4 -0.02762401 -0.999615 -0.002624452 -0.02464306 -0.9996963 -1.45343e-4 -0.02666133 -0.9996379 -0.003655791 -0.02508324 -0.9996846 -0.001301407 -0.02630567 -0.9996422 -0.004848957 -0.02371513 -0.9997162 -0.002318978 -0.02466189 -0.9996922 -0.002753317 -0.02466183 -0.9996913 -0.003045678 -0.0243991 -0.999695 -0.003846704 -0.0269193 -0.9996294 -0.004074037 -0.02691966 -0.999625 -0.00503683 -0.02512872 -0.9996715 -0.005070805 -0.02691882 -0.9996375 -6.1549e-4 -0.0269196 -0.9996342 -0.002632379 -0.02466118 -0.9996836 -0.004969 -0.02466094 -0.9996872 -0.004183709 -0.02664273 -0.9996424 0.00232768 -0.02691972 -0.9996374 -6.15744e-4 -0.02466201 -0.9996956 -7.46435e-4 -0.02530646 -0.999669 0.004642605 -0.02600246 -0.9995399 0.01562589 -0.02572751 -0.9995892 0.01263487 -0.02691531 -0.9994871 0.01736098 -0.02500706 -0.9995591 0.01601141 -0.02465897 -0.9995478 0.01721495 -0.02495378 -0.9995068 0.01906323 -0.02395707 -0.9996367 -0.01236003 -0.0238046 -0.9982063 -0.05493366 -0.02502095 -0.9980962 -0.05637431 -0.01455783 -0.8486893 0.5286912 -0.02282595 -0.9997382 -0.001623749 -0.02255338 -0.9997442 0.001679956 -0.02466195 -0.9996923 -0.002675712 -0.02466171 -0.999688 -0.003977775 -0.02521121 -0.9996692 -0.005100429 -0.02512872 -0.9996712 -0.005111932 -0.02466118 -0.9996871 -0.004183828 -0.02372586 -0.9997051 -0.005195498 -0.02530932 -0.999678 0.001877307 -0.02466088 -0.9996957 -7.45291e-4 -0.02346181 -0.9996885 0.008515775 -0.02508974 -0.9995419 0.01692318 -0.0234676 -0.9997122 0.004997253 -0.02333992 -0.9996901 0.008660972 -0.02255362 -0.9996547 0.01348942 -0.02255374 -0.9997201 0.00714147 -0.0228281 -0.9997383 -0.001525938 -0.02371609 -0.999583 0.01647895 -0.02279776 -0.9994091 -0.02572757 -0.022798 -0.9989008 -0.04095703 -0.02368122 -0.9980821 -0.0571959 -0.02279776 -0.9987372 -0.04477149 -0.02249258 -0.9983422 -0.05298119 -0.02282828 -0.9995006 -0.02185165 -0.02282798 -0.999641 0.01403856 -0.02279776 -0.9977324 0.06332725 -0.02264493 -0.9917703 0.1260122 -0.02237051 -0.9799698 0.1978861 -0.02197355 -0.9626265 0.2699395 -0.02385461 -0.9997099 -0.003359138 -0.02315104 -0.9997301 0.001986861 -0.02272355 -0.9997405 0.001633644 -0.02295267 -0.9997363 7.88357e-4 -0.02300721 -0.9997354 -2.31634e-5 -0.0227589 -0.9997405 -0.001041889 -0.02254164 -0.9997455 9.58639e-4 -0.02297723 -0.999736 -7.3601e-6 -0.0227195 -0.9997411 -0.001320362 -0.02292066 -0.9997256 -0.004852414 -0.02223438 -0.9997498 -0.002461016 -0.02372586 -0.9997053 -0.005168914 -0.02292078 -0.9997298 -0.0038836 -0.02271944 -0.9997328 -0.004273056 -0.02271938 -0.9997379 -0.002851366 -0.02238374 -0.999736 -0.005194783 -0.02271991 -0.9997416 -8.51123e-4 -0.02271974 -0.9997405 0.001726388 -0.02271932 -0.9997284 -0.005209207 -0.02262967 -0.9997342 0.004412412 -0.02271914 -0.9997329 -0.004272937 -0.02271997 -0.9997379 -0.002851843 -0.02271974 -0.9997416 -8.5075e-4 -0.02271664 -0.9995961 0.01707768 -0.02263104 -0.9997423 0.001812815 -0.02271544 -0.9995621 0.01896446 -0.02253925 -0.9996237 0.01563674 -0.02194309 -0.9996466 0.01501524 -0.02271604 -0.9995962 0.01707834 -0.02242892 -0.9995661 0.01909822 -0.02265906 -0.9995654 0.01886254 -0.02197366 -0.9996799 -0.01254326 -0.02188187 -0.9982351 -0.05520826 -0.02268433 -0.9981288 -0.05678319 -0.02279961 -0.9997379 0.002130746 -0.02133727 -0.9997721 -7.77716e-4 -0.02173644 -0.9997614 0.002195596 -0.02181243 -0.9997611 0.00143671 -0.02098792 -0.9997798 -7.40143e-6 -0.02271944 -0.9997392 -0.002333164 -0.02342939 -0.9997208 -0.003069043 -0.02291828 -0.9997299 -0.003881931 -0.02170246 -0.9997528 -0.004860818 -0.0223838 -0.9997371 -0.004989326 -0.02102768 -0.9997777 -0.001617491 -0.0210582 -0.9994416 -0.02594125 -0.02105778 -0.9989328 -0.04110842 -0.0210886 -0.9987637 -0.04501545 -0.02111917 -0.9995308 -0.02218735 -0.02111917 -0.9996835 0.01367253 -0.02108883 -0.9977989 0.06286978 -0.0209667 -0.9918766 0.1254647 -0.02072209 -0.9801359 0.1972418 -0.02032566 -0.962876 0.269178 -0.02140247 -0.9997684 0.002283453 -0.02107882 -0.9997757 0.002054452 -0.02122479 -0.9997733 0.00170964 -0.0211001 -0.9997771 8.57749e-4 -0.02092033 -0.9997811 1.47105e-5 -0.02032786 -0.9997931 -7.2019e-4 -0.02140307 -0.9997708 5.37467e-4 -0.0216155 -0.9997662 -7.15256e-4 -0.0214436 -0.9997685 -0.001763045 -0.02106064 -0.9997752 -0.00243026 -0.02152818 -0.99976 -0.004060387 -0.02133721 -0.999763 -0.004332005 -0.02133762 -0.999763 -0.004336118 -0.02133715 -0.9997681 -0.002916216 -0.02133715 -0.9997588 -0.005227148 -0.02133727 -0.999772 -9.19945e-4 -0.02133834 -0.9997714 0.001345217 -0.02133709 -0.9997586 -0.005260705 -0.02133709 -0.999763 -0.004331946 -0.02142506 -0.999734 0.008545219 -0.02133733 -0.9997681 -0.002916276 -0.02096682 -0.9997238 0.01062071 -0.02133834 -0.9997719 -9.20964e-4 -0.0213139 -0.9996286 0.01699078 -0.02105706 -0.9995976 0.01900899 -0.02142238 -0.9997571 0.005179882 -0.02133333 -0.9996035 0.01838093 -0.02142167 -0.999734 0.008549392 -0.02084428 -0.9996715 0.01492363 -0.02084475 -0.9996939 0.01333695 -0.02105772 -0.9996287 0.01729512 -0.02087467 -0.9997578 0.006988704 -0.02133327 -0.9995995 0.0185967 -0.02075278 -0.9997048 -0.01263475 -0.02138185 -0.9996383 0.01631695 -0.02136605 -0.9981242 -0.05737322 -0.02078354 -0.9982517 -0.05533123 -0.02081394 -0.9983689 -0.05316412 -0.02127307 -0.9981313 -0.05728489 -0.01660221 -0.9122681 0.4092572 -0.0152288 -0.8806794 0.4734678 -0.02253013 -0.9997462 -1.32124e-4 -0.0216307 -0.999766 4.01534e-4 -0.02071142 -0.9997844 0.001507401 -0.02103132 -0.999778 -0.001333057 -0.0211057 -0.9997743 -0.002476871 -0.02106058 -0.9997723 -0.003436803 -0.02178508 -0.9997513 -0.004793822 -0.02133756 -0.9997587 -0.005227327 -0.02133715 -0.9997586 -0.005260527 -0.003326594 -0.8406896 0.5415071 -0.02052772 -0.9997867 0.002247929 -0.02075964 -0.9997826 0.001987874 -0.02055835 -0.9997863 0.002151191 -0.02073097 -0.9997851 -5.97696e-5 -0.02049642 -0.9997895 9.58662e-4 -0.02037298 -0.9997925 3.64312e-4 -0.02053815 -0.9997891 -2.21969e-4 -0.02035027 -0.9997927 -7.37686e-4 -0.02051562 -0.9997887 -0.001323759 -0.02051585 -0.9997875 -0.001996099 -0.0205149 -0.9997836 -0.00348103 -0.02051544 -0.999776 -0.005228996 -0.0205155 -0.9997758 -0.005250871 -0.02050501 -0.9997803 -0.00434637 -0.02050471 -0.9997855 -0.002951145 -0.0206018 -0.9997738 -0.005285918 -0.02046489 -0.9997903 -8.86004e-4 -0.02051544 -0.9997801 -0.004364252 -0.02054673 -0.9997875 0.001641929 -0.02050507 -0.9997855 -0.0029518 -0.0205152 -0.9997789 0.004635512 -0.02050489 -0.9997893 -9.58832e-4 -0.02046197 -0.9997538 0.008590579 -0.02047473 -0.9997886 0.001921474 -0.02055352 -0.9997786 0.004515588 -0.02051466 -0.9997534 0.008502721 -0.02051168 -0.9996089 0.01901161 -0.02069157 -0.9997289 0.0106815 -0.02069461 -0.9996151 0.01847535 -0.02051192 -0.9996111 0.01889383 -0.02069699 -0.9996634 0.0156418 -0.02017337 -0.9629207 0.2690294 -0.02045559 -0.9997881 0.002294957 -0.02038931 -0.9997906 -0.001772642 -0.02051579 -0.9997857 -0.002759635 -0.02051484 -0.9997801 -0.004354894 -0.02060174 -0.9997735 -0.005349993 -0.02051562 -0.9997801 -0.004356324 -0.02063095 -0.9987705 -0.04507678 -0.02057003 -0.9995402 -0.02227914 -0.02069211 -0.9996938 0.01358109 -0.02063071 -0.9978144 0.06277728 -0.0207833 -0.9918923 0.1253713 -0.02029472 -0.9997919 0.002114534 -0.02044731 -0.9997898 0.001528441 -0.02044731 -0.9997906 9.17981e-4 -0.02040708 -0.9997906 0.001569747 -0.02065515 -0.9997867 4.92604e-5 -0.02039057 -0.9997782 -0.005292356 -0.02084416 -0.9997579 0.007049739 -0.02084463 -0.9994462 -0.02594137 -0.02084422 -0.998936 -0.04113912 -0.02078336 -0.9983663 -0.05322504 -0.02039796 -0.9981434 -0.05739068 -0.009796738 -0.8523805 0.5228304 -0.020545 -0.9997864 0.002247512 -0.02049589 -0.9997873 0.00228548 -0.02040708 -0.9997898 0.002012312 -0.02048259 -0.9997903 -1.89401e-4 -0.02039062 -0.9997783 -0.005254209 -0.02050298 -0.9997837 -0.003495216 -0.02075278 -0.9996742 0.01486265 -0.02050024 -0.9996462 0.0169472 -0.02047908 -0.9996176 0.0185849 -0.02044981 -0.9996452 0.0170685 -0.02045387 -0.9996646 0.01588511 -0.0204997 -0.9996094 0.01899743 -0.02072262 -0.9997839 -0.001678526 -0.02048003 -0.9996652 0.01581567 -0.02069175 -0.9997062 -0.01263475 -0.02069157 -0.9996961 0.01339763 -0.02046281 -0.9981321 -0.05756431 -0.02099704 -0.9982457 -0.05536144 -0.0204696 -0.9997878 0.002326905 -0.02048254 -0.9997901 -6.5886e-4 -0.02050298 -0.9997861 -0.002744495 -0.0208888 -0.9997817 5.06933e-4 -0.02067542 -0.9997837 0.00224775 -0.02069938 -0.9997837 0.002034962 -0.02072322 -0.9997833 0.002021431 -0.02068245 -0.999785 0.001528561 -0.02068245 -0.9997859 8.0355e-4 -0.02069938 -0.9997847 0.001518547 -0.02057272 -0.9997884 3.63949e-4 -0.02068662 -0.9997857 7.98289e-4 -0.02057194 -0.9997875 -0.001323282 -0.0205717 -0.9997864 -0.001995682 -0.02057164 -0.9997849 -0.002649247 -0.02057158 -0.9997789 -0.004355132 -0.02067834 -0.9997721 -0.005309224 -0.02067834 -0.9997732 -0.005109667 -0.02066248 -0.9997774 -0.004282355 -0.0206626 -0.9997822 -0.002945661 -0.02078151 -0.9997692 -0.005467414 -0.02067852 -0.9997768 -0.00431782 -0.0206626 -0.9997822 -0.002945542 -0.02067899 -0.9997765 0.004407227 -0.0206626 -0.9997864 -6.25011e-4 -0.02067834 -0.9997472 0.008844316 -0.02056837 -0.9996097 0.01891016 -0.02056843 -0.9996135 0.01870346 -0.02118015 -0.9995282 -0.02224832 6.40898e-4 -0.9917744 0.1279965 -0.05432432 -0.8745914 0.481808 -0.04709184 -0.8684682 0.4935033 -0.01935976 -0.9998101 0.002233564 -0.02120381 -0.9997745 0.001204252 -0.0205717 -0.9997875 -0.001322984 -0.02057182 -0.9997881 -7.82079e-4 -0.0205717 -0.9997864 -0.001995503 -0.02057158 -0.999782 -0.003588974 -0.0206784 -0.9997759 -0.00455594 -0.02078151 -0.9997704 -0.005223989 -0.02088874 -0.9997792 0.002320408 -0.02119421 -0.9997743 -0.001495361 -0.02106595 -0.9997756 0.002256989 -0.02106666 -0.999776 0.002031624 -0.021066 -0.9997761 0.002032041 -0.02110904 -0.9997761 0.001503884 -0.02106666 -0.9997769 0.001526296 -0.02106177 -0.9997779 8.10589e-4 -0.02107459 -0.9997777 7.97099e-4 -0.02105927 -0.9997782 -9.26062e-5 -0.02108275 -0.9997776 -5.11859e-4 -0.02120429 -0.9997744 -0.001319646 -0.02120387 -0.9997733 -0.001990497 -0.02120441 -0.9997708 -0.00297445 -0.02120471 -0.999769 -0.003503739 -0.01794499 -0.9997937 0.009521842 -0.02104938 -0.9996345 0.01696342 -0.02108699 -0.9997427 0.008367478 -0.02105146 -0.9995948 0.01916289 -0.02639865 -0.9995785 0.01208537 -0.02114939 -0.9996064 0.01843297 -0.02105408 -0.9996346 0.01695322 -0.0210523 -0.9996519 0.0159024 -0.02114915 -0.9995959 0.01899546 -0.07663345 -0.9969978 0.01107841 -0.02105337 -0.9996045 0.01864326 -0.02105665 -0.999652 0.01589316 -0.08496481 -0.9963837 -7.62975e-4 -0.07840359 -0.9968763 -0.009521961 -0.02130204 -0.998755 -0.04510664 -0.02130228 -0.9996814 0.0135504 -0.007446706 -0.9979534 0.06351083 -0.0249949 -0.9990639 0.03531026 -0.01617485 -0.9987525 0.04724282 -0.01848506 -0.999829 7.01856e-4 -0.02148258 -0.9997638 -0.003320932 -0.02172589 -0.9997624 0.001836538 -0.02169853 -0.9997646 3.47696e-4 -0.02120393 -0.9997743 -0.001319169 -0.02120447 -0.9997732 -0.001991391 -0.02108281 -0.9997741 -0.002720355 -0.02120459 -0.9997661 -0.004271686 -0.02108275 -0.9997723 -0.003313601 -0.02127605 -0.99976 -0.005235433 -0.02132463 -0.9997683 -0.002927362 -0.02132302 -0.9997721 -0.001144945 -0.02132993 -0.9997631 -0.004351198 -0.02123343 -0.9997732 0.001667678 -0.0213322 -0.9997681 -0.002941727 -0.02123409 -0.9997623 0.004950106 -0.0212534 -0.9997738 -9.58193e-4 -0.02125477 -0.9997729 0.001610755 -0.01019322 -0.9407086 0.3390628 -0.03680634 -0.953792 0.298205 -0.01922696 -0.9474622 0.3192897 -0.02119415 -0.9997727 0.00230062 -0.01799911 -0.9998371 -0.001415848 -0.02167475 -0.9997501 -0.005483865 -0.02156519 -0.9997651 0.002203881 -0.02147948 -0.9997674 0.002010643 -0.02155596 -0.9997652 0.002212107 -0.02146846 -0.9997676 0.002028822 -0.02147948 -0.999768 0.001631557 -0.02173358 -0.9997636 -7.15446e-4 -0.02137571 -0.9997617 -0.004448175 -0.0214163 -0.9997568 -0.005259633 -0.02137219 -0.9997625 -0.004272758 -0.02134859 -0.9997569 -0.005516409 -0.02137261 -0.9997583 -0.005180895 -0.02136945 -0.9997606 0.004713237 -0.08386731 -0.9964584 0.006073355 -0.06192284 -0.9978765 -0.02020347 -0.0212593 -0.9981402 -0.05713385 -0.03280752 -0.9989361 -0.0324108 -0.02121078 -0.9983425 -0.05350005 -0.01538145 -0.999002 -0.04193282 -0.00827074 -0.9919435 0.1264116 -0.02304196 -0.9967271 0.07748824 -0.01001036 -0.912347 0.4092957 -0.0269792 -0.934904 0.3538737 -0.02337759 -0.90657 0.4214078 -0.009491384 -0.8824889 0.4702376 -0.02148264 -0.9997668 0.00224775 -0.01753944 -0.999841 -0.003230631 -0.02160048 -0.9997358 -0.0078547 -0.02116841 -0.9997743 0.001770496 -0.02107846 -0.9997771 0.001189291 -0.02107727 -0.9997777 -7.16809e-4 -0.02137219 -0.9997588 -0.005059659 -0.01060938 -0.99993 -0.005251049 0.003843367 -0.9999754 -0.005874276 0.02050501 -0.9997719 -0.005979359 0.03806 -0.9992603 -0.005520701 0.05456089 -0.9985005 -0.004447579 0.06728303 -0.9977304 -0.002667546 0.07089626 -0.9974838 -7.8635e-5 0.0624687 -0.9980413 0.003379583 -0.02137064 -0.9997335 0.00873661 -0.001441538 -0.9998281 0.0184881 -0.02269482 -0.9996601 0.01283597 -0.04361021 -0.9988995 0.01726323 -0.06926935 -0.9974089 0.01941978 -0.09622102 -0.9951766 0.01910799 -0.1208291 -0.9925385 0.01636493 -0.1395756 -0.9901469 0.01130509 -0.1490262 -0.9888288 0.002960324 -0.1451802 -0.9894048 -9.76617e-4 -0.1244269 -0.9922108 -0.005981743 -0.0822488 -0.9965382 -0.01211601 -0.02159476 -0.9981122 -0.05749666 -0.02633804 -0.9989538 -0.03738594 -0.02395731 -0.9898198 0.1402954 -0.0100103 -0.9803398 0.1970629 -0.01013249 -0.9629248 0.2695799 -0.03048843 -0.9746543 0.2216289 -0.01708847 -0.9998396 -0.005383312 -0.02132511 -0.9997196 -0.01030653 -0.02166306 -0.9997647 0.001187384 -0.02151715 -0.9997673 0.001618146 -0.01934009 -0.9998129 3.49938e-4 -0.0216487 -0.9997649 0.001202642 -0.0215432 -0.9997676 8.09346e-4 -0.02168464 -0.9997649 3.6224e-4 -0.0215435 -0.999768 -1.41749e-4 -0.021721 -0.9997638 -7.0219e-4 -0.02154237 -0.9997627 -0.00323832 -0.02175563 -0.9997614 -0.001987695 -0.02155786 -0.9997584 -0.004303574 -0.01994806 -0.9998001 -0.001419067 -0.007787883 -0.999969 -0.001179218 0.007714033 -0.9999698 -9.3992e-4 0.02545416 -0.9996758 -6.98868e-4 0.04364293 -0.9990471 -4.60065e-4 0.06003814 -0.9981961 -2.54447e-4 0.0724762 -0.9973702 1.59393e-4 0.05605715 -0.9984275 4.92523e-4 -0.01266765 -0.9999195 7.35413e-4 -0.03067815 -0.9995288 9.74546e-4 -0.05534297 -0.9984667 0.001214444 -0.08331412 -0.9965223 0.001452565 -0.1106479 -0.9938583 0.001691162 -0.1211305 -0.9926047 0.007965445 -0.1398378 -0.9901566 0.005951166 -0.02111917 -0.9983084 -0.05417126 -0.02047836 -0.9985275 -0.05023461 -0.02041691 -0.9982627 -0.05526912 -0.02146923 -0.9981314 -0.05720949 -0.02047842 -0.998775 -0.0450465 -0.02044743 -0.9995447 -0.02218699 -0.02145516 -0.9994205 0.02642983 -0.02859622 -0.9569528 0.2888315 -0.03409016 -0.8745346 0.4837636 -0.02737557 -0.8683288 0.4952331 -0.01663261 -0.9998315 -0.007771432 -0.02092504 -0.9996994 -0.01278388 -0.02168637 -0.9997624 0.002240002 -0.0193392 -0.9998123 0.001194834 -0.01934134 -0.9998127 -7.19915e-4 -0.02179104 -0.9997565 -0.003496825 -0.02154248 -0.9997643 -0.002716183 -0.02154225 -0.9997586 -0.004325032 -0.02273261 -0.9997293 -0.004964053 -0.03299111 -0.9956237 0.08743709 -0.01870799 -0.9944546 0.1034892 -0.04651153 -0.9335572 0.3553981 -0.02630764 -0.9248269 0.3794772 -0.03723335 -0.880447 0.4726806 -0.01617968 -0.9998168 -0.01023077 -0.0193268 -0.9997059 -0.01464998 -0.0213378 -0.9997699 0.002242326 -0.01705992 -0.9998535 0.001403808 -0.01709043 -0.9998518 0.002075254 -0.009460866 -0.9999538 0.001739561 -0.02122044 -0.9997724 0.002207815 -0.02107846 -0.9997763 0.001806437 -0.01696842 -0.9998561 -3.05188e-5 -0.0170294 -0.9998548 7.62968e-4 -0.009643971 -0.9999533 7.93493e-4 -0.02107763 -0.9997771 0.001189708 -0.02107763 -0.9997779 3.48257e-4 -0.01709043 -0.9998531 -0.001312255 -0.009369313 -0.999956 -4.88304e-4 -0.02107727 -0.9997778 3.48545e-4 -0.02107751 -0.9997776 -7.16747e-4 -0.02107846 -0.9997726 -0.003243327 -0.02107721 -0.9997759 -0.002005279 -0.01736509 -0.9985086 -0.0517596 -0.02090805 -0.998129 -0.05745792 -0.02014231 -0.9982969 -0.0547505 -0.01309245 -0.998599 -0.0512712 -0.04379528 -0.9877291 0.1499111 -0.02530026 -0.9853985 0.1683735 -0.06164807 -0.9141008 0.4007736 -0.03436475 -0.8995273 0.4355111 -0.01572525 -0.9997953 -0.01272767 -0.01706016 -0.9998357 -0.006134331 -0.02094292 -0.999778 0.00233227 -0.01934313 -0.9998105 0.002216935 3.35713e-4 -0.9999985 0.001770079 -0.01933914 -0.9998113 0.001815259 5.79869e-4 -0.9999995 7.93505e-4 -0.01934009 -0.9998123 0.001194536 -0.01934128 -0.999813 3.49646e-4 5.1883e-4 -0.9999998 -4.88311e-4 -0.01934081 -0.9998127 -7.19748e-4 4.8831e-4 -0.9999977 -0.002075314 -0.02107709 -0.9997726 -0.003242731 -0.01842963 -0.9998287 -0.001779079 -0.02107828 -0.9997632 -0.005414724 -0.01959264 -0.9998036 -0.002992272 -0.01923912 -0.9998062 -0.004171907 -0.01931101 -0.9981745 -0.05722606 -0.01690745 -0.9983637 -0.05462872 -0.01945751 -0.9981667 -0.05731189 -0.02838307 -0.9995114 -0.01309281 -0.03711086 -0.9990031 0.0248118 -0.05304199 -0.9960486 0.0712313 -0.05099749 -0.9746909 0.2176628 -0.03027534 -0.9711012 0.2367401 -0.06113058 -0.959259 0.2758354 -0.07443678 -0.9418284 0.3277477 -0.05942094 -0.8929017 0.4463135 -0.01593095 -0.9997759 -0.01394718 -0.009765982 -0.9999486 0.002716124 -0.01932597 -0.9998108 0.00222069 -0.002258419 -0.9999969 0.001068174 -0.001403868 -0.9999967 0.002166867 -0.008789479 -0.9999597 0.001861631 -0.0109561 -0.9999397 8.85037e-4 -0.01043736 -0.9999448 0.00125122 -0.01126164 -0.9999364 7.01945e-4 -0.003418147 -0.9999942 1.52596e-4 -0.004547297 -0.9999895 -5.49344e-4 -0.01464909 -0.9998925 -7.01936e-4 -0.004669368 -0.9999881 -0.001464903 -0.01565641 -0.9998748 -0.002288937 -0.004577815 -0.9999858 -0.002716183 -0.01547336 -0.9998783 -0.002044796 -0.01909041 -0.9998126 -0.00325942 -0.01968616 -0.9997987 -0.003878593 -0.01168876 -0.9985833 -0.0519129 -0.01010179 -0.9984905 -0.05398809 -0.0257889 -0.9987487 -0.04284924 -0.06906539 -0.9890116 0.1307145 -0.08307278 -0.9228036 0.376208 -0.008850514 -0.9999582 0.002319395 -0.009399831 -0.9999546 0.001617491 -0.01278734 -0.9999182 2.4415e-4 -0.01352006 -0.9999087 -1.22078e-4 -0.01571744 -0.9998756 -0.00137335 -0.01577848 -0.999874 -0.001739561 -0.01632755 -0.9998596 -0.003784298 -0.005462884 -0.9987652 -0.0493797 -2.13632e-4 -0.9986706 -0.05154645 -0.01214635 -0.9996973 -0.02139347 6.40893e-4 -0.9998844 0.01519829 -0.01327556 -0.9787628 0.2045663 -0.01245182 -0.9620563 0.2725669 -0.01336735 -0.8784625 0.4776243 -0.03616523 -0.8600613 0.5089075 -0.01428639 -0.9998585 -0.00889033 0.006191968 -0.9999782 0.002340674 0.00495541 -0.9999861 0.001823544 0.005474269 -0.9999848 7.94292e-4 -0.0152288 -0.9998835 -0.001068115 0.005443811 -0.9999853 -1.06627e-4 0.005331754 -0.9999854 -8.82387e-4 0.006570816 -0.9999777 -0.001315891 -0.01568692 -0.9998735 -0.00262463 0.005114376 -0.9999847 -0.002132654 2.44155e-4 -0.9990217 -0.04422259 0.005759 -0.9983906 -0.05642038 -0.01184123 -0.9982966 -0.05713093 0.005760073 -0.9983906 -0.05641955 -0.0122382 -0.998744 -0.04858672 -0.01232963 -0.9995592 -0.0270093 -0.01232975 -0.9998396 0.01300114 -0.01187181 -0.9980909 0.06061053 -0.01223814 -0.9929398 0.1179869 -0.01434409 -0.9822682 0.1869316 -0.0165413 -0.9666904 0.2554138 -0.01187199 -0.9413991 0.3370859 -0.01318413 -0.9151986 0.4027875 -0.0144658 -0.8847362 0.4658675 -0.02905458 -0.8550667 0.5177034 0.00593084 -0.9999808 0.001828968 0.00577712 -0.9999808 0.002278983 0.006542265 -0.9999778 0.001312732 0.006553828 -0.9999785 3.18965e-4 0.006652176 -0.9999735 -0.002971827 -0.01672416 -0.8522635 0.5228454 -9.17682e-5 0 1 7.9255e-4 0 0.9999997 3.36445e-4 0 1 -2.77313e-4 0 1 1.85811e-4 0 1 -1.76379e-4 0 1 1.09504e-4 0 1 8.82019e-5 0 1 6.00101e-5 0 1 1.6896e-4 0 1 3.31509e-5 0 1 -7.92648e-4 0 0.9999997 -5.44329e-4 0 0.9999999 -7.56377e-5 0 1 -3.80899e-5 0 1 1.09516e-4 0 1 -8.95671e-5 0 1 -2.21307e-5 0 1 0 -2.02376e-7 1 0 0 1 0 -6.39451e-7 1 6.48141e-5 -5.35436e-6 1 0 -9.55651e-7 1 -8.56879e-6 5.18291e-7 1 5.45655e-7 0 1 1.28687e-6 0 1 1.2297e-6 2.15397e-6 1 0 -4.82323e-6 1 0 -2.13676e-6 1 -6.48042e-6 -4.84139e-6 1 0 -1.44615e-5 1 4.70432e-6 2.08664e-6 1 0 -1.45231e-5 1 0 -4.67844e-6 1 0 -1.7737e-6 1 3.06609e-6 -1.32495e-6 1 0 -2.41306e-6 1 0 -3.38981e-6 1 0 4.72081e-6 1 -4.4847e-6 -4.88877e-6 1 -5.86302e-5 -5.07814e-6 1 0 -5.22511e-6 1 -1.21344e-4 0 1 0 -5.69963e-6 1 2.05107e-5 0 1 -1.7616e-5 0 1 -4.08224e-5 0 1 1.11955e-4 0 1 -4.10648e-6 0 1 -4.45264e-5 0 1 5.79055e-5 0 1 2.27565e-5 0 1 -1.13149e-4 0 1 -1.66031e-6 0 1 1.43547e-6 0 1 0 1.10151e-6 1 0 -1.3565e-5 1 0 7.65782e-7 1 0 1.40447e-7 1 4.765e-6 3.20691e-7 1 -0.9933521 -0.1151164 0 -0.8204988 -0.5716483 0 -0.9039391 -0.4276612 0 -0.9614156 -0.2751 0 -0.5896569 -0.8076539 0 -0.4482876 -0.8938895 0 -0.8204889 -0.5716626 0 -0.7150426 -0.6990809 0 -0.1345902 -0.9909014 0 0.03027522 -0.9995416 0 -0.2960325 -0.9551779 0 -0.4482997 -0.8938833 0 0.5016474 -0.8650723 0 0.3537175 -0.9353524 0 0.1945605 -0.9808905 0 0.8529958 -0.5219178 0 0.7560938 -0.6544634 0 0.5016341 -0.8650799 0 0.6383725 -0.7697276 0 0.9765248 -0.2154049 0 0.9765313 -0.2153758 0 0.9273507 -0.3741936 0 0.9273612 -0.3741673 0 0.9039217 0.427698 0 0.9613383 0.27537 0 0.9614156 0.2751 0 0.9936974 0.1120961 0 0.9936766 0.1122803 0 0.9986326 -0.05227851 0 0.7150426 0.6990809 -6.10391e-5 0.5897603 0.8075785 -3.05196e-5 0.715103 0.6990192 -6.1039e-5 0.9029091 0.4298317 -3.05191e-5 0.8190828 0.5736754 -9.15585e-5 0.8204889 0.5716626 -3.05196e-5 0.2963368 0.9550836 3.05187e-5 0.2957925 0.9552522 0 0.4485681 0.8937487 0 0.5906767 0.8069083 0 0.4494218 0.8933197 3.05189e-5 -0.03109848 0.9995164 0 -0.194314 0.9809394 0 -0.3535371 0.9354205 0 -0.5015524 0.8651274 3.05192e-5 -0.3530759 0.9355947 0 -0.5033852 0.8640622 0 -0.6366536 0.7711501 0 -0.6380898 0.769962 -3.05189e-5 -0.756291 0.6542355 -3.0519e-5 -0.8543236 0.5197417 -3.05192e-5 -0.7562347 0.6543006 -3.05192e-5 -0.8542528 0.519858 0 -0.9274016 0.3740674 0 -0.9273253 0.3742567 0 -0.9758875 0.2182745 0 -0.9758404 0.2184845 0 -0.07668346 0.004018425 0.9970474 -0.0766828 0.004018425 0.9970476 0.8239421 -0.0431773 0.5650268 0.8239431 -0.04317718 0.5650252 0.900626 -0.0471962 -0.4320247 0.9006248 -0.0471968 -0.4320272 0.07668274 -0.004018425 -0.9970475 0.0766828 -0.004018843 -0.9970475 -0.8239425 0.04317724 -0.5650262 -0.8239431 0.04317718 -0.5650253 -0.9006249 0.0471965 0.432027 -0.9006261 0.0471965 0.4320246 0.05233156 0.9986298 0 0.05233204 0.9986298 0 0.05233138 0.9986298 0 0.05233073 0.9986298 0 0.05233079 0.9986299 4.8081e-7 0.05233371 0.9986297 0 0.05233097 0.9986299 -5.58181e-7 0.05232834 0.9986301 2.09754e-6 0.05233061 0.9986299 0 0.05233108 0.9986298 -1.76603e-6 0.05232977 0.9986299 4.61409e-7 0.05233067 0.9986299 0 0.05233085 0.9986298 -2.35173e-7 0.05233091 0.9986298 0 0.05233073 0.9986298 0 0.05233246 0.9986298 0 0.05233103 0.9986299 5.43428e-7 0.05233174 0.9986298 0 0.05233043 0.9986299 0 0.05233138 0.9986298 0 0.05233049 0.9986299 5.25027e-7 0.05232977 0.9986299 0 0.05232971 0.9986299 8.92421e-7 0.05233085 0.9986299 -1.31341e-6 0.05232888 0.99863 -5.64096e-7 0.05232948 0.99863 -1.01132e-6 0.0523312 0.9986299 -7.39922e-7 0.0523318 0.9986298 9.54895e-7 0.05233061 0.9986299 6.81142e-7 0.05232959 0.9986299 1.61831e-6 0.05233234 0.9986298 -4.28855e-7 0.05233037 0.9986299 -4.34043e-7 0.05233281 0.9986297 1.12845e-6 0.05233103 0.9986298 0 0.05233091 0.9986298 4.702e-7 0.05233192 0.9986298 -1.85492e-6 0.05233103 0.9986298 4.98916e-7 0.05233103 0.9986299 0 0.0523312 0.9986299 0 0.05233305 0.9986298 0 0.05233073 0.9986298 0 0.05233037 0.9986299 -9.7931e-7 -0.05233144 -0.9986298 9.55998e-7 -0.05233037 -0.9986299 0 -0.05233097 -0.9986298 0 -0.05233079 -0.9986299 4.80513e-7 -0.0523315 -0.9986298 1.01455e-6 -0.05233013 -0.9986299 1.05076e-6 -0.05233144 -0.9986298 -3.93305e-7 -0.05233132 -0.9986298 9.78742e-7 -0.05233168 -0.9986298 1.00917e-6 -0.05233055 -0.9986299 0 -0.05233162 -0.9986298 0 -0.05233019 -0.9986299 0 -0.05233007 -0.9986299 0 -0.05232954 -0.99863 0 -0.05233168 -0.9986298 5.98568e-7 -0.0523315 -0.9986298 0 -0.05233097 -0.9986298 -6.51899e-7 -0.05232948 -0.99863 8.46151e-7 -0.05233097 -0.9986299 1.49806e-6 -0.05233114 -0.9986298 5.25034e-7 -0.05233108 -0.9986298 0 -0.05233228 -0.9986298 0 -0.05232989 -0.9986299 0 -0.05233108 -0.9986299 1.05072e-6 -0.05233073 -0.9986298 0 -0.05233132 -0.9986298 5.39935e-7 -0.05233031 -0.9986299 5.45733e-7 -0.05233138 -0.9986298 0 -0.05233156 -0.9986298 0 -0.0523315 -0.9986298 9.77301e-7 -0.05233055 -0.9986299 0 -0.05233108 -0.9986298 2.62223e-7 -0.05233156 -0.9986298 9.96716e-7 -0.0523324 -0.9986298 0 -0.05233001 -0.9986299 6.4327e-7 -0.05233091 -0.9986299 5.6458e-7 -0.05233156 -0.9986298 5.66592e-7 -0.05233144 -0.9986298 -1.22871e-7 -0.05232995 -0.9986299 0 -0.05233097 -0.9986299 4.70199e-7 -0.05233132 -0.9986298 0 -0.05232959 -0.9986299 -9.27419e-7 -0.05233114 -0.9986299 2.71714e-7 -0.05233222 -0.9986298 0 -0.9878116 0.05176037 -0.1467968 -0.9984691 0.05231004 0.01797586 0.1003786 -0.005249321 0.9949355 -0.06451719 0.003357052 0.997911 -0.06454759 0.003357052 0.9979091 -0.9502033 0.04977613 -0.3076297 -0.886678 0.04645037 -0.4600483 -0.7989661 0.04184198 -0.5999189 -0.6894578 0.03610414 -0.7234256 -0.5611544 0.02938985 -0.8271893 -0.4175313 0.02185159 -0.9083998 -0.262496 0.01373362 -0.9648354 -0.2625244 0.0137335 -0.9648277 -0.1003453 0.005249202 -0.9949389 -0.1003151 0.005249202 -0.9949418 0.06454759 -0.003357052 -0.9979091 -0.9818972 0.05145549 0.1822917 -0.9818987 0.05142503 0.182292 -0.9385347 0.04916685 0.3416655 -0.9385383 0.04916542 0.3416556 -0.8695768 0.04556477 0.491691 -0.7769034 0.04068243 0.6283041 -0.6630325 0.03473097 0.7477847 -0.5310636 0.02780294 0.8468757 -0.3846262 0.02014225 0.9228527 -0.2276756 0.01190257 0.9736644 -0.2276756 0.01193308 0.973664 0.5609362 -0.02945065 0.8273351 0.4176552 -0.02185171 0.9083428 0.4173448 -0.02191251 0.9084841 0.2624313 -0.01376396 0.9648526 0.2626174 -0.01373362 0.9648023 0.7991356 -0.04181075 0.5996951 0.798754 -0.04193365 0.6001946 0.8865171 -0.04654151 0.4603492 0.5613014 -0.02938956 0.8270895 0.6892208 -0.03619605 0.7236467 0.6896452 -0.03610432 0.7232469 0.9877537 -0.05182158 0.1471635 0.9984719 -0.0523712 -0.01764017 0.9878664 -0.05166846 0.1464602 0.9500889 -0.0498681 0.3079679 0.9503043 -0.04971563 0.3073275 0.886824 -0.0464195 0.4597702 0.8697097 -0.04559588 -0.4914529 0.9384302 -0.04907459 -0.3419659 0.9386443 -0.04922723 -0.3413558 0.9818341 -0.05136382 -0.1826575 0.9984678 -0.05221843 -0.0183115 0.9819509 -0.05151617 -0.1819851 0.6628412 -0.034639 -0.7479585 0.7767145 -0.04059052 -0.6285436 0.6631607 -0.03476178 -0.7476695 0.869427 -0.04544287 -0.4919672 0.7770513 -0.04074323 -0.6281173 0.531192 -0.02783375 -0.8467943 0.5309138 -0.02774202 -0.8469717 0.3847259 -0.02014267 -0.9228112 0.3845745 -0.02011221 -0.9228749 0.2277045 -0.01193302 -0.9736572 0.2277334 -0.0119329 -0.9736505 -0.05233108 -0.9986298 0 -0.05233037 -0.9986299 0 -0.0523324 -0.9986298 1.75034e-7 -0.05233108 -0.9986298 0 0.9929358 -0.05203944 0.1066326 0.9929354 -0.05203908 0.1066361 0.5886836 -0.03085058 -0.8077747 0.5886914 -0.03085017 -0.807769 -0.4042367 0.02118867 -0.914409 -0.404249 0.02118027 -0.9144038 -0.9929367 0.05202245 -0.1066322 -0.992936 0.05203866 -0.1066311 -0.5886821 0.03085058 0.8077758 -0.5886879 0.03085047 0.8077715 0.4042431 -0.02117186 0.9144066 0.4042418 -0.02118873 0.9144067 -0.05232894 -0.99863 -1.77334e-7 -0.05233174 -0.9986298 -1.432e-7 -0.05233466 -0.9986296 -2.50988e-7 -0.05233037 -0.9986299 0 -0.05232965 -0.9986299 -2.04831e-7 -0.0523346 -0.9986296 0 -0.05232715 -0.9986301 1.45668e-7 -0.05233061 -0.9986299 -1.33959e-7 -0.05233168 -0.9986298 0 -0.05233043 -0.9986299 -1.03942e-6 -0.05233657 -0.9986296 9.0875e-7 -0.05233061 -0.9986299 0 -0.05232757 -0.99863 3.47896e-7 -0.0523324 -0.9986298 7.78891e-7 -0.05233126 -0.9986298 0 -0.05232971 -0.9986299 -1.39902e-7 -0.05232983 -0.9986299 -1.24928e-7 -0.05233091 -0.9986299 0 -0.05233031 -0.9986299 -2.97616e-7 -0.05233067 -0.9986299 2.29735e-7 -0.0523346 -0.9986297 -1.08308e-6 -0.05232942 -0.99863 -1.28666e-7 -0.0523315 -0.9986298 -2.82449e-7 -0.05233204 -0.9986298 -2.71147e-7 -0.0523315 -0.9986298 4.68815e-7 -0.05233192 -0.9986298 0 -0.05233073 -0.9986298 0 -0.05233311 -0.9986297 5.45318e-7 -0.05233019 -0.9986299 3.51021e-7 -0.05232936 -0.9986299 2.09399e-7 -0.05233198 -0.9986298 2.71928e-7 -0.05233496 -0.9986296 -2.1254e-7 -0.05232918 -0.9986299 2.46401e-7 -0.05233091 -0.9986298 0 -0.05233383 -0.9986297 2.17503e-7 -0.0523315 -0.9986298 1.11917e-6 -0.05233132 -0.9986298 -5.94581e-7 -0.05232816 -0.99863 0 -0.05232906 -0.9986299 -4.02086e-7 -0.0523284 -0.9986301 2.13101e-7 -0.05232876 -0.9986299 2.1272e-7 -0.05233007 -0.9986299 -7.28483e-7 -0.05233108 -0.9986299 0 -0.05233329 -0.9986298 1.81365e-7 0.8997626 -0.0471214 -0.4338282 0.8161692 -0.04275709 -0.5762289 0.8161836 -0.0427578 -0.5762085 0.5063803 -0.02652144 0.8619024 0.3577787 -0.01873886 0.9336184 0.7103157 -0.03720349 -0.7028993 0.7103005 -0.03720271 -0.7029148 0.5850574 -0.03064149 -0.8104128 0.4438425 -0.0232557 -0.8958032 0.443867 -0.0232554 -0.8957909 0.2905414 -0.01519846 -0.9567418 0.2905134 -0.01519858 -0.9567503 0.1292475 -0.006744623 -0.9915894 -0.03552383 0.001861631 -0.9993671 -0.03549331 0.001861631 -0.9993682 -0.1993206 0.01043754 -0.9798787 -0.1993499 0.01043748 -0.9798728 -0.3577787 0.01873886 -0.9336184 -0.3577419 0.01873856 -0.9336325 -0.5063669 0.02652078 -0.8619102 0.8997613 -0.04715186 -0.4338276 0.9587962 -0.05023485 -0.2796183 0.9916812 -0.05194312 -0.1177724 0.997516 -0.05224865 0.04724353 0.9975175 -0.05224871 0.04721307 0.9761579 -0.0511502 0.210949 0.9761517 -0.0511499 0.2109781 0.928189 -0.04861748 0.3689195 0.9281786 -0.04861694 0.3689458 0.8549075 -0.04477185 0.5168449 0.7583725 -0.03973603 0.6506091 0.6411698 -0.03360116 0.7666632 0.6411524 -0.03357136 0.7666789 0.1994438 -0.0104376 0.9798537 -0.2902923 0.01519823 0.9568173 -0.1290636 0.006744623 0.9916135 -0.2903009 0.01519864 0.9568148 0.03567618 -0.001861631 0.9993618 -0.5848301 0.03064078 0.810577 -0.7100879 0.03720277 0.7031295 -0.4436227 0.02322483 0.8959127 -0.58481 0.03064131 0.8105914 -0.4435982 0.02322518 0.8959249 -0.9586988 0.05023455 0.2799524 -0.8996143 0.04712158 0.4341355 -0.8996024 0.04712098 0.4341603 -0.8159686 0.04275774 0.5765129 -0.8159799 0.04272621 0.5764992 -0.9762173 0.05115014 -0.2106739 -0.997532 0.05224788 -0.04690712 -0.9762111 0.05114978 -0.2107031 -0.991641 0.05194425 0.1181106 -0.9916374 0.05194407 0.1181407 -0.8549985 0.0448023 -0.5166919 -0.9282748 0.04861718 -0.3687036 -0.9282644 0.04861664 -0.36873 -0.7584286 0.03973573 -0.6505438 -0.8549996 0.04477185 -0.5166926 -0.7584006 0.03973591 -0.6505765 -0.6411524 0.03357136 -0.7666789 -0.6411194 0.03357124 -0.7667065 0.05232805 0.9986301 -3.4535e-7 0.05232644 0.9986301 0 0.05232739 0.99863 6.907e-7 0.05233013 0.9986299 1.3814e-6 0.05232894 0.9986299 -1.92101e-6 0.05233609 0.9986295 3.4538e-7 0.05233246 0.9986298 1.29512e-6 0.05233192 0.9986298 0 0.05233132 0.9986298 -1.10511e-6 0.05232828 0.99863 -6.90638e-7 0.05232781 0.99863 1.10513e-6 0.05232727 0.9986301 -5.52535e-7 0.05233281 0.9986298 5.52594e-7 0.0523349 0.9986296 -6.90653e-7 0.05232852 0.99863 3.45334e-7 0.05232918 0.99863 0 0.05233049 0.9986299 -2.76375e-7 0.0523262 0.9986301 6.90684e-7 0.05232763 0.9986301 3.45365e-7 0.05233407 0.9986297 -2.07259e-7 0.05233156 0.9986299 0 0.05233126 0.9986298 6.90669e-7 0.0523312 0.9986298 -6.91005e-7 0.05232965 0.9986299 0 0.05233281 0.9986298 -5.52594e-7 0.05233126 0.9986298 -5.52437e-7 0.05233055 0.9986299 -2.76268e-7 0.05233216 0.9986298 4.48839e-7 0.05232834 0.9986301 -6.90493e-7 0.05233049 0.9986299 0 0.05232912 0.99863 0 0.05233103 0.9986298 -1.65725e-6 0.05232912 0.99863 -5.52555e-7 0.05232506 0.9986302 -6.90669e-7 0.05233204 0.9986298 -5.52574e-7 0.05232822 0.99863 -3.45273e-7 0.05233192 0.9986298 1.72644e-7 0.05232816 0.99863 -6.90856e-7 0.05233538 0.9986296 0 0.05233448 0.9986297 -1.72682e-7 0.05233049 0.9986299 -1.65771e-6 0.0523315 0.9986298 0 0.05232834 0.9986301 -5.52535e-7 0.05232912 0.99863 -1.10511e-6 0.05233317 0.9986297 -5.52574e-7 0.05233556 0.9986296 -5.52594e-7 0.05233317 0.9986297 -8.28861e-7 0.05232959 0.9986299 1.13964e-6 0.0523315 0.9986298 -4.14431e-7 0.05233126 0.9986298 0 0.05233246 0.9986298 -6.9073e-7 0.05233013 0.9986299 0 0.05233013 0.9986299 -1.3814e-6 0.0523315 0.9986298 6.90699e-7 0.05232775 0.99863 -3.45243e-7 0.05233168 0.9986298 1.65733e-6 0.0523284 0.99863 -5.61019e-7 0.05233103 0.9986298 -1.6573e-6 0.05233097 0.9986298 -1.72637e-7 0.05233263 0.9986297 0 0.05233198 0.9986298 -5.52457e-7 0.05232852 0.99863 0 0.05233311 0.9986298 -5.52515e-7 0.05233275 0.9986297 1.10507e-6 0.05233317 0.9986297 2.76287e-7 0.05232912 0.99863 -2.76277e-7 0.05233156 0.9986298 2.76316e-7 0.05233299 0.9986298 -3.79949e-7 0.0523312 0.9986299 -5.52711e-7 0.0523321 0.9986298 0 0.05232632 0.9986301 1.38174e-6 0.05233043 0.9986299 4.1493e-7 0.0523355 0.9986296 -5.52809e-7 0.05232912 0.99863 0 0.05232983 0.9986299 6.91572e-7 0.5063442 -0.02652114 0.8619236 -0.9586905 0.05023407 0.2799805 -0.9916415 0.05194264 0.118107 -0.9282734 0.04864764 -0.368703 -0.6411374 0.03357058 -0.7666915 -0.5063442 0.02652114 -0.8619236 -0.5063803 0.02652144 -0.8619024 -0.2903288 0.01519852 0.9568063 0.1994731 -0.01043754 0.9798477 0.3577419 -0.01873856 0.9336325 0.9281744 -0.04870831 0.3689442 0.8549985 -0.0448023 0.5166919 0.8549052 -0.04483276 0.5168435 0.7584156 -0.03973668 0.6505588 0.6411518 -0.03360182 0.7666782 0.9975304 -0.05227828 0.046907 0.9975127 -0.05234003 0.04721283 0.991675 -0.05206489 -0.1177717 0.9282734 -0.04864764 0.368703 0.9761548 -0.05121111 0.2109483 0.9762173 -0.05115014 0.2106739 0.8997573 -0.04724317 -0.4338257 0.8161557 -0.04284954 -0.576241 0.8996143 -0.04712158 -0.4341355 0.9587918 -0.05032616 -0.2796171 0.9586988 -0.05023455 -0.2799524 0.9916393 -0.05197465 -0.1181104 0.4438052 -0.02331638 -0.89582 0.5848445 -0.03064149 -0.8105665 0.5850218 -0.03070223 -0.8104363 0.7101032 -0.03720355 -0.7031141 0.8159931 -0.04275745 -0.5764781 0.7102981 -0.03729414 -0.7029125 0.1290636 -0.006744623 -0.9916135 0.2903009 -0.01519864 -0.9568148 0.1292175 -0.006805717 -0.991593 0.4436227 -0.02322483 -0.8959127 0.2904852 -0.01525974 -0.9567579 -0.03549331 0.001800596 -0.9993683 -0.03567618 0.001861631 -0.9993618 -0.1993207 0.01040703 -0.9798791 -0.199473 0.01046806 -0.9798475 0.0523352 0.9986296 0 0.05233055 0.9986299 0 0.05232506 0.9986302 6.90669e-7 0.05233287 0.9986298 0 0.05233383 0.9986297 6.9073e-7 0.05233722 0.9986295 -2.76274e-6 0.05232852 0.99863 -8.63336e-7 0.05233317 0.9986298 0 0.05233383 0.9986297 -6.9073e-7 0.05232971 0.9986299 0 0.05233126 0.9986298 6.90715e-7 0.05232942 0.9986299 -6.90699e-7 0.05232888 0.99863 -1.72667e-7 0.05233162 0.9986298 0 0.05232501 0.9986302 -2.76194e-6 0.05233198 0.9986298 -2.76304e-6 0.05233144 0.9986298 0 0.05232596 0.9986301 2.76243e-6 0.05232638 0.9986301 1.72633e-6 0.05233228 0.9986298 -2.76277e-6 0.0523321 0.9986298 3.45354e-7 0.05233085 0.9986298 0 0.05233108 0.9986299 -2.76329e-6 0.05233305 0.9986298 0 0.05233079 0.9986298 -1.3814e-6 0.05232185 0.9986304 0 0.05233055 0.9986299 1.38134e-6 0.05233198 0.9986298 0 0.05233287 0.9986298 -2.0721e-6 0.05232363 0.9986303 0 0.05233001 0.9986299 1.03606e-6 0.05232876 0.9986299 6.90699e-7 0.05233234 0.9986298 -1.38109e-6 0.05233108 0.9986299 -1.38146e-6 0.05233484 0.9986296 0 0.05233329 0.9986296 0 0.05233174 0.9986298 0 0.05233073 0.9986299 1.38141e-6 0.05233156 0.9986298 -1.38144e-6 0.05232852 0.9986299 1.38143e-6 0.05233246 0.9986298 -1.38146e-6 0.05233246 0.9986298 0 0.05233383 0.9986297 1.38146e-6 0.05233281 0.9986298 0 0.05232888 0.99863 0 0.05233561 0.9986295 -1.38122e-6 0.05233097 0.9986298 0 0.05232775 0.99863 2.76194e-6 0.05232971 0.9986299 2.76292e-6 0.0523352 0.9986296 -2.76292e-6 0.05233287 0.9986298 2.7628e-6 0.05233287 0.9986298 -2.7628e-6 0.052329 0.99863 1.38137e-6 0.05233126 0.9986298 1.38143e-6 0.05233407 0.9986297 0 0.05233162 0.9986298 6.90738e-7 0.05233234 0.9986298 -6.90738e-7 0.05233383 0.9986297 0 0.05233252 0.9986297 0 0.05232959 0.9986299 0 0.05232834 0.99863 -2.59001e-7 0.05233013 0.9986299 6.90699e-7 0.05233174 0.9986298 0 0.05233901 0.9986294 3.45399e-7 0.05235803 0.9986284 9.49892e-6 0.05232584 0.9986302 -4.27308e-7 0.05231046 0.998631 0 0.05232268 0.9986303 8.5126e-6 0.05234044 0.9986293 -8.99653e-7 0.05235213 0.9986287 3.95628e-6 0.05231535 0.9986307 -2.64199e-6 0.05233609 0.9986295 1.65393e-6 0.05233335 0.9986298 2.04825e-6 0.0523315 0.9986298 0 0.05232036 0.9986304 -1.38085e-6 0.05233347 0.9986297 4.27355e-7 0.05233472 0.9986296 0 0.05233764 0.9986295 1.38207e-6 0.0523231 0.9986302 0 0.05233228 0.9986298 0 0.05232673 0.9986301 0 0.05233287 0.9986298 -3.96634e-6 0.05233347 0.9986298 1.38151e-6 0.05233776 0.9986295 6.32749e-6 0.05232715 0.9986301 -2.15907e-6 0.05231583 0.9986307 -5.27684e-6 0.05234843 0.9986289 0 0.05234235 0.9986292 3.07399e-6 0.05233043 0.9986299 1.80014e-6 0.0523281 0.99863 2.37101e-6 0.05231308 0.9986308 -1.65433e-6 0.05233424 0.9986297 0 0.05233407 0.9986297 -1.04199e-6 0.05233103 0.9986298 -1.40056e-6 0.05233341 0.9986297 1.44041e-6 0.05232268 0.9986303 -3.45304e-7 0.05232656 0.9986301 -7.50847e-7 0.052338 0.9986295 0 0.05232977 0.9986299 0 0.0523315 0.9986299 3.97321e-7 -0.8159543 0.04275697 0.5765332 -0.7100728 0.03720355 0.7031448 -0.5848445 0.03064149 0.8105665 -0.443537 0.02322518 0.8959552 -0.2902085 0.01519858 0.9568428 -0.1290975 0.006744801 0.991609 -0.1290335 0.006744623 0.9916174 0.03561526 -0.001861631 0.9993639 0.3578053 -0.01873868 0.9336082 -0.9587084 0.05020451 0.2799246 -0.7583725 0.03973603 -0.6506091 -0.7584437 0.03973656 -0.6505262 -0.6410865 0.03357112 -0.7667341 0.1288835 -0.006744742 -0.9916369 -0.03555428 0.001831114 -0.9993662 -0.03576874 0.001861631 -0.9993584 -0.1994438 0.0104376 -0.9798537 -0.3578053 0.01873868 -0.9336082 0.4433172 -0.02319431 -0.8960648 0.5845285 -0.03061044 -0.8107956 0.1292475 -0.00677514 -0.9915893 0.2899961 -0.01516813 -0.9569077 0.2905693 -0.01519834 -0.9567334 0.8157404 -0.04272645 -0.5768382 0.8994363 -0.04712188 -0.4345042 0.8161938 -0.04275673 -0.5761942 0.7097849 -0.03717237 -0.703437 0.7103308 -0.03720271 -0.7028841 0.585092 -0.03064167 -0.8103879 0.9975448 -0.05224853 0.04663306 0.9916796 -0.05197358 -0.1177722 0.9916047 -0.05194395 -0.1184151 0.958788 -0.05023443 -0.2796465 0.8997732 -0.04715245 -0.4338029 0.9586108 -0.05020421 -0.2802586 0.9283459 -0.04861772 0.3685244 0.9975159 -0.05227917 0.04721295 0.9762641 -0.05114936 0.2104572 0.855077 -0.04480165 0.5165619 0.8549281 -0.04480183 0.5168083 0.7584717 -0.03973644 0.6504935 0.6411194 -0.03357124 0.7667065 0.6411704 -0.0335707 0.7666639 + + + + + + + + + + + + + + +

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

+
+ + + +

304 119 306 120 305 119 307 121 309 120 308 122 310 123 312 124 311 125 313 126 315 127 314 128 316 129 318 130 317 129 319 130 321 131 320 131 322 132 324 132 323 133 325 134 327 133 326 134 328 135 330 136 329 136 331 137 333 137 332 135 334 138 336 139 335 140 337 139 339 141 338 141 340 142 342 142 341 143 343 144 345 145 344 144 346 146 348 147 347 148 349 149 351 150 350 146 352 151 354 152 353 151 355 152 357 153 356 154 358 155 360 155 359 156 361 157 363 156 362 157 364 158 360 155 358 155 364 158 366 158 365 159 366 158 364 158 358 155 367 159 368 160 365 159 365 159 366 158 367 159 369 161 368 160 370 160 367 159 370 160 368 160 369 161 372 161 371 162 372 161 369 161 370 160 373 163 374 164 371 162 371 162 372 161 373 163 375 165 374 164 376 164 373 163 376 164 374 164 375 165 378 166 377 167 378 166 375 165 376 164 379 167 308 122 377 167 377 167 378 166 379 167 359 156 363 156 361 157 379 167 307 121 308 122 360 155 363 156 359 156 352 151 353 151 362 157 362 157 353 151 361 157 356 154 354 152 355 152 355 152 354 152 352 151 348 147 357 153 347 148 348 147 356 154 357 153 346 146 350 146 351 150 346 146 347 148 350 146 349 149 342 142 340 142 351 150 349 149 340 142 345 145 343 144 341 143 342 142 345 145 341 143 334 138 335 140 344 144 344 144 335 140 343 144 338 141 336 139 337 139 337 139 336 139 334 138 330 136 338 141 339 141 328 135 329 136 332 135 330 136 339 141 329 136 333 137 331 137 322 132 328 135 332 135 333 137 324 132 327 133 323 133 331 137 324 132 322 132 326 134 317 129 325 134 327 133 325 134 323 133 319 130 318 130 316 129 316 129 317 129 326 134 312 124 320 131 321 131 320 131 318 130 319 130 310 123 311 125 313 126 312 124 321 131 311 125 314 128 315 127 305 119 310 123 313 126 314 128 304 119 309 120 306 120 315 127 304 119 305 119 307 121 306 120 309 120 380 60 382 60 381 60 383 60 385 60 384 60 386 168 388 168 387 168 380 169 389 169 388 169 390 60 391 60 381 60 392 60 393 60 386 60 392 60 394 60 393 60 395 170 396 170 394 170 397 60 391 60 398 60 399 60 400 60 395 60 397 60 402 60 401 60 403 60 405 60 404 60 406 171 403 171 401 171 407 60 409 60 408 60 410 60 412 60 411 60 413 60 415 60 414 60 416 172 418 172 417 172 419 173 421 173 420 173 422 174 424 174 423 174 425 175 427 175 426 175 428 176 430 176 429 176 431 60 427 60 432 60 432 60 434 60 433 60 429 60 436 60 435 60 434 60 437 60 436 60 438 60 440 60 439 60 441 60 443 60 442 60 444 60 445 60 424 60 444 60 430 60 446 60 422 60 383 60 384 60 447 60 449 60 448 60 450 60 385 60 416 60 425 177 426 177 443 177 414 178 415 178 451 178 418 179 453 179 452 179 454 180 408 180 455 180 456 60 412 60 453 60 410 60 458 60 457 60 455 60 404 60 454 60 457 60 459 60 399 60 413 60 448 60 415 60 448 181 413 181 447 181 451 182 409 182 407 182 451 60 407 60 414 60 409 60 455 60 408 60 404 60 405 60 454 60 403 183 406 183 405 183 401 184 402 184 406 184 397 60 398 60 402 60 391 185 390 185 398 185 381 186 382 186 390 186 381 60 389 60 380 60 389 60 387 60 388 60 387 60 392 60 386 60 394 187 396 187 393 187 395 188 400 188 396 188 399 60 459 60 400 60 457 60 458 60 459 60 410 60 411 60 458 60 412 60 456 60 411 60 412 189 452 189 453 189 452 190 417 190 418 190 417 191 450 191 416 191 450 60 384 60 385 60 422 192 423 192 383 192 424 193 445 193 423 193 444 194 446 194 445 194 430 195 428 195 446 195 429 196 435 196 428 196 436 197 437 197 435 197 436 198 433 198 434 198 433 60 431 60 432 60 431 60 426 60 427 60 442 199 440 199 441 199 443 60 441 60 425 60 439 60 421 60 438 60 442 200 439 200 440 200 419 201 420 201 449 201 438 202 421 202 419 202 448 203 449 203 420 203 460 204 462 205 461 206 463 207 465 208 464 209 466 210 468 211 467 212 469 213 471 214 470 215 472 216 474 217 473 218 472 216 476 219 475 220 477 221 479 222 478 223 478 223 481 224 480 225 482 226 484 227 483 228 485 229 487 230 486 231 488 232 490 233 489 234 491 235 484 227 492 236 493 237 495 238 494 239 496 240 498 241 497 242 499 243 501 244 500 245 502 246 503 247 500 245 504 248 506 249 505 250 507 251 509 252 508 253 510 254 512 255 511 256 513 257 515 258 514 259 516 260 518 261 517 262 519 263 516 260 520 264 521 265 518 261 516 260 522 266 521 265 523 267 521 265 522 266 518 261 523 267 525 268 524 269 524 269 522 266 523 267 526 270 527 271 525 268 524 269 525 268 527 271 528 272 526 270 529 273 526 270 528 272 527 271 529 273 531 274 530 275 530 275 528 272 529 273 532 276 533 277 531 274 530 275 531 274 533 277 534 278 532 276 535 279 532 276 534 278 533 277 535 279 537 280 536 281 536 281 534 278 535 279 463 207 538 282 537 280 536 281 537 280 538 282 516 260 517 262 520 264 463 207 464 209 538 282 510 254 519 263 520 264 511 256 512 255 513 257 519 263 510 254 511 256 515 258 505 250 514 259 512 255 515 258 513 257 504 248 508 253 506 249 505 250 506 249 514 259 501 244 509 252 507 251 507 251 508 253 504 248 503 247 499 243 500 245 499 243 509 252 501 244 493 237 494 239 503 247 493 237 503 247 502 246 498 241 496 240 495 238 496 240 494 239 495 238 490 233 497 242 489 234 497 242 498 241 489 234 490 233 488 232 492 236 483 228 484 227 491 235 491 235 492 236 488 232 482 226 486 231 487 230 483 228 486 231 482 226 485 229 479 222 477 221 485 229 477 221 487 230 481 224 478 223 539 283 539 283 478 223 479 222 474 217 480 225 473 218 480 225 481 224 473 218 476 219 468 211 475 220 474 217 472 216 475 220 469 213 466 210 467 212 467 212 468 211 476 219 461 206 470 215 471 214 470 215 466 210 469 213 462 205 460 204 465 208 461 206 471 214 460 204 465 208 463 207 462 205 540 284 542 284 541 285 543 286 545 286 544 287 542 284 547 288 546 288 547 288 542 284 540 284 548 289 546 288 549 289 547 288 549 289 546 288 550 290 551 290 548 289 548 289 549 289 550 290 551 290 553 291 552 291 553 291 551 290 550 290 554 292 552 291 555 292 553 291 555 292 552 291 556 293 557 294 554 292 554 292 555 292 556 293 557 294 559 295 558 295 559 295 557 294 556 293 560 296 558 295 561 296 559 295 561 296 558 295 562 297 563 297 560 296 560 296 561 296 562 297 564 145 563 297 562 297 564 145 565 145 563 297 540 284 541 285 566 285 567 298 566 285 568 298 541 285 568 298 566 285 569 299 570 300 567 298 567 298 568 298 569 299 570 300 572 301 571 301 572 301 570 300 569 299 573 302 571 301 574 302 572 301 574 302 571 301 575 303 576 303 573 302 573 302 574 302 575 303 576 303 578 304 577 304 578 304 576 303 575 303 579 305 577 304 580 306 578 304 580 306 577 304 581 307 582 307 579 305 579 305 580 306 581 307 582 307 584 308 583 309 584 308 582 307 581 307 584 308 545 286 583 309 585 310 587 311 586 310 583 309 545 286 543 286 588 312 590 313 589 314 591 315 593 315 592 316 594 317 596 318 595 318 597 319 599 317 598 320 600 321 602 321 601 322 603 322 605 323 604 323 606 324 608 325 607 324 609 326 611 326 610 325 612 327 614 328 613 329 615 330 614 328 616 331 617 332 618 329 613 329 612 327 613 329 618 329 617 332 620 333 619 332 619 332 618 329 617 332 621 333 620 333 622 334 620 333 621 333 619 332 565 145 623 335 622 334 621 333 622 334 623 335 564 145 623 335 565 145 615 330 616 331 606 324 616 331 614 328 612 327 608 325 610 325 607 324 606 324 607 324 615 330 609 326 602 321 611 326 608 325 609 326 610 325 600 321 601 322 603 322 611 326 602 321 600 321 604 323 605 323 595 318 603 322 601 322 605 323 599 317 596 318 594 317 596 318 604 323 595 318 588 312 597 319 598 320 598 320 599 317 594 317 590 313 592 316 589 314 588 312 589 314 597 319 591 315 585 310 593 315 590 313 591 315 592 316 586 310 587 311 544 287 593 315 585 310 586 310 543 286 544 287 587 311 624 333 626 336 625 337 627 143 629 334 628 145 630 338 632 339 631 327 633 340 635 341 634 342 636 325 638 343 637 344 639 324 641 331 640 345 642 346 644 322 643 347 645 348 647 321 646 326 648 349 650 350 649 317 651 323 653 351 652 318 654 313 656 352 655 353 657 314 659 320 658 354 660 287 662 311 661 355 663 356 665 310 664 315 666 308 668 357 667 358 669 121 671 121 670 359 672 360 674 361 673 362 675 363 677 364 676 365 678 366 680 367 679 368 681 369 683 370 682 371 684 372 686 373 685 374 687 375 689 376 688 377 686 373 690 378 685 374 691 379 690 378 692 380 686 373 692 380 690 378 691 379 694 381 693 382 694 381 691 379 692 380 695 383 696 384 693 382 693 382 694 381 695 383 697 385 696 384 698 386 695 383 698 386 696 384 697 385 700 387 699 388 700 387 697 385 698 386 701 389 702 390 699 388 699 388 700 387 701 389 703 391 702 390 704 392 701 389 704 392 702 390 703 391 706 393 705 394 706 393 703 391 704 392 707 395 628 145 705 394 705 394 706 393 707 395 684 372 688 377 689 376 707 395 627 143 628 145 684 372 685 374 688 377 687 375 680 367 678 366 689 376 687 375 678 366 683 370 681 369 679 368 680 367 683 370 679 368 672 360 673 362 682 371 682 371 673 362 681 369 676 365 674 361 675 363 675 363 674 361 672 360 668 357 677 364 667 358 668 357 676 365 677 364 666 308 670 359 671 121 666 308 667 358 670 359 669 121 662 311 660 287 671 121 669 121 660 287 665 310 663 356 661 355 662 311 665 310 661 355 654 313 655 353 664 315 664 315 655 353 663 356 657 314 656 352 654 313 650 350 658 354 659 320 658 354 656 352 657 314 648 349 649 317 652 318 650 350 659 320 649 317 653 351 651 323 642 346 648 349 652 318 653 351 644 322 647 321 643 347 651 323 644 322 642 346 646 326 637 344 645 348 647 321 645 348 643 347 639 324 638 343 636 325 636 325 637 344 646 326 632 339 640 345 641 331 640 345 638 343 639 324 630 338 631 327 633 340 632 339 641 331 631 327 634 342 635 341 625 337 630 338 633 340 634 342 624 333 629 334 626 336 635 341 624 333 625 337 627 143 626 336 629 334 708 396 710 397 709 398 711 399 713 400 712 401 708 396 715 402 714 403 714 403 710 397 708 396 716 404 715 402 717 405 715 402 716 404 714 403 717 405 719 406 718 407 716 404 717 405 718 407 719 406 721 408 720 409 721 408 719 406 717 405 722 410 720 409 723 411 721 408 723 411 720 409 724 412 725 413 722 410 722 410 723 411 724 412 725 413 727 414 726 415 727 414 725 413 724 412 728 416 726 415 729 417 727 414 729 417 726 415 730 418 731 419 728 416 728 416 729 417 730 418 732 420 731 419 730 418 732 420 733 421 731 419 709 398 735 422 734 423 735 422 709 398 710 397 736 424 734 423 737 425 735 422 737 425 734 423 738 426 739 427 736 424 736 424 737 425 738 426 739 427 741 428 740 429 741 428 739 427 738 426 742 430 740 429 743 431 741 428 743 431 740 429 744 432 745 433 742 430 742 430 743 431 744 432 745 433 747 434 746 435 747 434 745 433 744 432 748 436 746 435 749 437 747 434 749 437 746 435 750 438 751 439 748 436 748 436 749 437 750 438 751 439 753 440 752 441 753 440 751 439 750 438 752 441 754 442 713 400 753 440 754 442 752 441 755 443 757 444 756 445 752 441 713 400 711 399 758 446 760 447 759 448 761 449 763 450 762 451 764 452 766 453 765 454 767 455 769 456 768 457 770 458 772 459 771 460 773 461 774 462 765 454 775 463 777 464 776 465 778 466 780 467 779 468 781 469 783 470 782 471 784 472 786 473 785 474 787 475 782 471 788 476 783 470 788 476 782 471 789 477 790 478 787 475 787 475 788 476 789 477 790 478 792 479 791 480 792 479 790 478 789 477 793 481 791 480 794 482 792 479 794 482 791 480 795 483 732 420 793 481 793 481 794 482 795 483 733 421 732 420 795 483 781 469 785 474 786 473 786 473 783 470 781 469 777 464 775 463 784 472 777 464 784 472 785 474 776 465 778 466 779 468 777 464 778 466 776 465 772 459 780 467 771 460 779 468 780 467 772 459 773 461 770 458 774 462 770 458 771 460 774 462 766 453 764 452 769 456 766 453 773 461 765 454 758 446 767 455 768 457 768 457 769 456 764 452 760 447 762 451 759 448 758 446 759 448 767 455 761 449 755 443 763 450 760 447 761 449 762 451 756 445 757 444 712 401 763 450 755 443 756 445 711 399 712 401 757 444 796 484 798 484 797 484 799 79 801 79 800 79 802 79 798 79 796 79 797 79 804 79 803 79 805 79 806 79 802 79 807 79 808 79 804 79 809 485 807 485 810 485 811 486 812 486 810 486 813 79 814 79 805 79 815 487 811 487 816 487 817 488 818 488 813 488 819 489 821 489 820 489 815 490 822 490 820 490 823 491 825 491 824 491 826 492 825 492 821 492 827 493 829 493 828 493 827 494 823 494 830 494 831 495 832 495 828 495 831 496 828 496 829 496 831 497 833 497 832 497 834 79 832 79 833 79 835 79 836 79 817 79 831 498 837 498 833 498 838 79 840 79 839 79 841 79 843 79 842 79 844 499 846 499 845 499 847 500 849 500 848 500 850 79 852 79 851 79 853 79 855 79 854 79 856 501 858 501 857 501 859 79 858 79 851 79 860 79 862 79 861 79 856 502 863 502 860 502 864 503 799 503 865 503 865 79 861 79 866 79 867 504 800 504 868 504 869 505 871 505 870 505 867 79 870 79 871 79 872 506 842 506 873 506 874 79 869 79 872 79 875 79 841 79 876 79 877 507 879 507 878 507 840 79 838 79 844 79 835 79 881 79 880 79 881 79 877 79 882 79 883 79 879 79 876 79 833 79 847 79 834 79 853 79 852 79 855 79 827 508 830 508 829 508 823 79 824 79 830 79 825 79 826 79 824 79 821 79 819 79 826 79 820 509 822 509 819 509 815 510 816 510 822 510 815 511 812 511 811 511 812 79 809 79 810 79 809 79 808 79 807 79 808 512 803 512 804 512 803 79 796 79 797 79 802 79 806 79 798 79 805 513 814 513 806 513 813 514 818 514 814 514 817 79 836 79 818 79 835 79 880 79 836 79 881 79 882 79 880 79 877 515 878 515 882 515 879 79 883 79 878 79 879 516 875 516 876 516 875 79 843 79 841 79 843 517 873 517 842 517 873 79 874 79 872 79 874 518 871 518 869 518 867 519 868 519 870 519 800 79 801 79 868 79 799 520 864 520 801 520 865 521 866 521 864 521 861 522 862 522 866 522 860 523 863 523 862 523 856 524 857 524 863 524 858 79 859 79 857 79 858 79 850 79 851 79 850 79 855 79 852 79 854 79 846 79 853 79 845 79 840 79 844 79 854 525 845 525 846 525 848 79 838 79 839 79 847 79 848 79 884 79 839 526 884 526 848 526 834 527 847 527 884 527 885 121 887 528 886 121 888 529 887 528 889 530 887 528 888 529 886 121 890 531 891 532 889 530 888 529 889 530 891 532 890 531 893 533 892 534 892 534 891 532 890 531 894 535 893 533 895 536 893 533 894 535 892 534 896 537 897 538 895 536 894 535 895 536 897 538 896 537 899 539 898 540 898 540 897 538 896 537 900 541 899 539 901 542 899 539 900 541 898 540 902 543 903 544 901 542 900 541 901 542 903 544 902 543 905 545 904 546 904 546 903 544 902 543 906 547 905 545 907 548 905 545 906 547 904 546 908 549 909 550 907 548 906 547 907 548 909 550 908 549 911 551 910 552 910 552 909 550 908 549 912 553 911 551 913 554 911 551 912 553 910 552 914 555 915 556 913 554 912 553 913 554 915 556 914 555 917 557 916 558 916 558 915 556 914 555 918 559 917 557 919 560 917 557 918 559 916 558 920 561 921 562 919 560 918 559 919 560 921 562 920 561 923 563 922 564 922 564 921 562 920 561 924 565 923 563 925 566 923 563 924 565 922 564 926 567 927 568 925 566 924 565 925 566 927 568 926 567 929 569 928 570 928 570 927 568 926 567 929 569 930 569 928 570 931 571 885 121 886 121 932 572 933 573 931 571 885 121 931 571 933 573 932 572 935 574 934 575 934 575 933 573 932 572 936 576 935 574 937 577 935 574 936 576 934 575 938 578 939 579 937 577 936 576 937 577 939 579 938 578 941 580 940 581 940 581 939 579 938 578 942 582 941 580 943 583 941 580 942 582 940 581 944 584 945 585 943 583 942 582 943 583 945 585 944 584 947 586 946 587 946 587 945 585 944 584 948 588 947 586 949 589 947 586 948 588 946 587 950 590 951 591 949 589 948 588 949 589 951 591 950 590 953 592 952 593 952 593 951 591 950 590 954 594 953 592 955 595 953 592 954 594 952 593 956 596 957 597 955 595 954 594 955 595 957 597 956 596 959 598 958 599 958 599 957 597 956 596 960 600 959 598 961 601 959 598 960 600 958 599 962 602 963 603 961 601 960 600 961 601 963 603 962 602 965 604 964 605 964 605 963 603 962 602 966 606 965 604 967 607 965 604 966 606 964 605 968 608 969 609 967 607 966 606 967 607 969 609 968 608 971 610 970 611 970 611 969 609 968 608 972 612 971 610 973 613 971 610 972 612 970 611 972 612 973 613 974 614 975 60 977 60 976 60 978 615 975 615 979 615 976 616 979 616 975 616 980 617 982 121 981 121 983 618 985 619 984 620 986 621 988 622 987 623 989 624 991 625 990 626 992 627 994 628 993 628 995 629 997 630 996 631 998 632 1000 625 999 632 1001 633 1003 634 1002 635 1004 636 1006 637 1005 638 1007 639 1009 640 1008 639 1010 641 1012 642 1011 642 1013 643 1015 643 1014 145 1016 644 1018 645 1017 646 1019 647 1021 648 1020 649 1022 650 1024 650 1023 145 1025 651 1027 652 1026 653 1028 647 1030 654 1029 654 1031 655 1033 655 1032 656 1034 657 1036 658 1035 659 1037 660 1039 660 1038 661 1039 660 1037 660 1040 662 1041 661 1042 663 1038 661 1038 661 1039 660 1041 661 1043 664 1042 663 1044 663 1041 661 1044 663 1042 663 1043 664 1046 665 1045 666 1046 665 1043 664 1044 663 1047 667 1048 668 1045 666 1045 666 1046 665 1047 667 1049 669 1048 668 1050 670 1047 667 1050 670 1048 668 1049 669 1052 671 1051 672 1052 671 1049 669 1050 670 1053 672 1054 673 1051 672 1051 672 1052 671 1053 672 982 121 1054 673 1055 674 1053 672 1055 674 1054 673 981 121 982 121 1055 674 1040 662 1032 656 1033 655 1037 660 1032 656 1040 662 1034 657 1035 659 1031 655 1031 655 1035 659 1033 655 1025 651 1036 658 1027 652 1027 652 1036 658 1034 657 1030 654 1026 653 1029 654 1030 654 1025 651 1026 653 1028 647 1019 647 1020 649 1028 647 1029 654 1019 647 1021 648 1024 650 1022 650 1020 649 1021 648 1022 650 1014 145 1015 643 1023 145 1024 650 1014 145 1023 145 1016 644 1017 646 1013 643 1013 643 1017 646 1015 643 1007 639 1018 645 1009 640 1009 640 1018 645 1016 644 1012 642 1007 639 1008 639 1010 641 1011 642 1001 633 1012 642 1008 639 1011 642 1002 635 1003 634 1004 636 1010 641 1001 633 1002 635 1006 637 996 631 1005 638 1003 634 1006 637 1004 636 995 629 999 632 997 630 996 631 997 630 1005 638 991 625 1000 625 998 632 998 632 999 632 995 629 994 628 989 624 990 626 989 624 1000 625 991 625 992 627 993 628 983 618 994 628 990 626 993 628 984 620 985 619 987 623 992 627 983 618 984 620 986 621 980 617 988 622 985 619 986 621 987 623 981 121 988 622 980 617 1056 675 1058 675 1057 675 1057 676 1059 676 1056 676 1060 677 1062 677 1061 677 1063 678 1065 678 1064 678 1066 679 1062 679 1063 679 1067 680 1060 680 1061 680 1063 681 1060 681 1065 681 1062 682 1060 682 1063 682 1068 683 1070 683 1069 683 1069 683 1071 683 1068 683 1072 684 1074 684 1073 684 1072 685 1075 685 1074 685 1076 686 1077 686 1072 686 1078 687 1079 687 1075 687 1074 688 1075 688 1079 688 1072 689 1077 689 1075 689 1080 690 1082 691 1081 692 1083 693 1085 693 1084 692 1086 694 1088 695 1087 696 1089 694 1091 697 1090 697 1092 698 1094 698 1093 699 1095 699 1097 700 1096 701 1098 702 1100 703 1099 704 1101 705 1103 705 1102 703 1104 706 1106 707 1105 707 1107 708 1109 706 1108 708 1110 709 1112 710 1111 711 1112 710 1110 709 1113 709 1114 712 1111 711 1115 712 1112 710 1115 712 1111 711 1116 713 1117 713 1114 712 1114 712 1115 712 1116 713 1117 713 1119 714 1118 715 1119 714 1117 713 1116 713 1120 716 1118 715 1121 717 1119 714 1121 717 1118 715 1105 707 1113 709 1110 709 1106 707 1113 709 1105 707 1104 706 1108 708 1109 706 1106 707 1104 706 1109 706 1107 708 1098 702 1099 704 1107 708 1108 708 1098 702 1102 703 1100 703 1101 705 1102 703 1099 704 1100 703 1092 698 1103 705 1094 698 1094 698 1103 705 1101 705 1097 700 1095 699 1093 699 1093 699 1095 699 1092 698 1087 696 1088 695 1096 701 1097 700 1087 696 1096 701 1086 694 1091 697 1089 694 1088 695 1086 694 1089 694 1090 697 1082 691 1080 690 1090 697 1091 697 1082 691 1083 693 1084 692 1081 692 1084 692 1080 690 1081 692 1122 718 1124 718 1123 718 1125 719 1127 719 1126 719 1125 720 1129 720 1128 720 1130 721 1132 721 1131 721 1133 722 1125 722 1134 722 1125 723 1128 723 1134 723 1135 724 1125 724 1136 724 1125 725 1133 725 1136 725 1125 726 1137 726 1127 726 1125 727 1135 727 1137 727 1125 728 1139 728 1138 728 1126 729 1139 729 1125 729 1140 730 1124 730 1138 730 1125 731 1138 731 1124 731 1141 732 1124 732 1142 732 1124 733 1140 733 1142 733 1143 734 1124 734 1144 734 1124 735 1141 735 1144 735 1145 736 1124 736 1146 736 1124 737 1143 737 1146 737 1124 738 1145 738 1123 738 1130 739 1124 739 1147 739 1122 740 1147 740 1124 740 1148 741 1130 741 1149 741 1130 742 1147 742 1132 742 1150 743 1130 743 1151 743 1130 744 1131 744 1151 744 1130 745 1152 745 1149 745 1130 746 1150 746 1152 746 1130 747 1154 747 1153 747 1148 732 1154 732 1130 732 1129 748 1130 748 1155 748 1153 749 1155 749 1130 749 1156 750 1129 750 1157 750 1129 751 1155 751 1157 751 1158 752 1129 752 1159 752 1129 753 1156 753 1159 753 1160 754 1129 754 1161 754 1129 755 1158 755 1161 755 1162 756 1129 756 1163 756 1129 757 1160 757 1163 757 1128 758 1129 758 1162 758 1164 759 1166 759 1165 759 1166 760 1164 760 1167 760 1168 761 1170 761 1169 761 1169 762 1172 762 1171 762 1169 763 1173 763 1168 763 1174 764 1176 764 1175 764 1177 765 1169 765 1178 765 1169 766 1170 766 1178 766 1179 767 1169 767 1180 767 1169 768 1177 768 1180 768 1169 769 1179 769 1172 769 1169 770 1182 770 1181 770 1171 771 1182 771 1169 771 1174 772 1169 772 1183 772 1181 773 1183 773 1169 773 1184 774 1174 774 1185 774 1174 775 1183 775 1185 775 1186 776 1174 776 1187 776 1174 777 1184 777 1187 777 1174 778 1188 778 1176 778 1174 779 1186 779 1188 779 1174 780 1190 780 1189 780 1175 781 1190 781 1174 781 1191 782 1193 782 1192 782 1174 783 1189 783 1191 783 1194 784 1191 784 1195 784 1191 785 1189 785 1195 785 1196 786 1191 786 1197 786 1191 787 1194 787 1197 787 1191 788 1198 788 1193 788 1191 789 1196 789 1198 789 1191 790 1200 790 1199 790 1192 774 1200 774 1191 774 1201 791 1173 791 1199 791 1191 792 1199 792 1173 792 1202 793 1173 793 1203 793 1173 794 1201 794 1203 794 1204 795 1173 795 1205 795 1173 796 1202 796 1205 796 1206 797 1173 797 1207 797 1173 798 1204 798 1207 798 1208 799 1173 799 1209 799 1173 800 1206 800 1209 800 1168 761 1173 761 1208 761 1210 801 1212 802 1211 802 1213 803 1215 804 1214 804 1210 801 1217 801 1216 805 1217 801 1210 801 1211 802 1218 805 1219 806 1216 805 1216 805 1217 801 1218 805 1220 807 1219 806 1221 806 1218 805 1221 806 1219 806 1220 807 1223 808 1222 809 1223 808 1220 807 1221 806 1224 810 1225 811 1222 809 1222 809 1223 808 1224 810 1226 812 1225 811 1227 811 1224 810 1227 811 1225 811 1226 812 1229 812 1228 813 1229 812 1226 812 1227 811 1230 813 1231 814 1228 813 1228 813 1229 812 1230 813 1232 815 1231 814 1233 814 1230 813 1233 814 1231 814 1234 815 1232 815 1233 814 1235 816 1211 802 1212 802 1236 817 1235 816 1237 816 1212 802 1237 816 1235 816 1236 817 1239 817 1238 818 1239 817 1236 817 1237 816 1240 818 1241 819 1238 818 1238 818 1239 817 1240 818 1242 820 1241 819 1243 819 1240 818 1243 819 1241 819 1242 820 1245 821 1244 822 1245 821 1242 820 1243 819 1246 822 1247 823 1244 822 1244 822 1245 821 1246 822 1248 824 1247 823 1249 825 1246 822 1249 825 1247 823 1248 824 1251 826 1250 827 1251 826 1248 824 1249 825 1252 827 1215 804 1250 827 1250 827 1251 826 1252 827 1252 827 1214 804 1215 804 1253 828 1255 829 1254 829 1256 830 1258 803 1257 830 1259 831 1261 832 1260 833 1262 828 1264 834 1263 835 1265 836 1267 836 1266 837 1268 838 1270 832 1269 838 1271 839 1273 840 1272 841 1274 842 1276 842 1275 837 1277 843 1279 844 1278 843 1280 839 1282 845 1281 846 1283 847 1279 844 1284 848 1277 843 1284 848 1279 844 1283 847 1286 847 1285 849 1286 847 1283 847 1284 848 1287 850 1288 851 1285 849 1285 849 1286 847 1287 850 1289 852 1288 851 1290 851 1287 850 1290 851 1288 851 1291 853 1289 852 1290 851 1281 846 1282 845 1278 843 1282 845 1277 843 1278 843 1280 839 1271 839 1272 841 1280 839 1281 846 1271 839 1273 840 1276 842 1274 842 1272 841 1273 840 1274 842 1266 837 1267 836 1275 837 1276 842 1266 837 1275 837 1268 838 1269 838 1265 836 1265 836 1269 838 1267 836 1259 831 1270 832 1261 832 1261 832 1270 832 1268 838 1264 834 1260 833 1263 835 1264 834 1259 831 1260 833 1262 828 1253 828 1254 829 1262 828 1263 835 1253 828 1255 829 1256 830 1257 830 1254 829 1255 829 1257 830 1213 803 1214 804 1258 803 1256 830 1213 803 1258 803 1292 854 1294 854 1293 854 1295 79 1297 79 1296 79 1297 79 1299 79 1298 79 1300 79 1302 79 1301 79 1292 855 1303 855 1294 855 1299 79 1297 79 1295 79 1304 79 1305 79 1298 79 1296 856 1306 856 1295 856 1307 79 1305 79 1308 79 1298 857 1299 857 1304 857 1307 858 1310 858 1309 858 1304 79 1308 79 1305 79 1307 859 1308 859 1310 859 1311 860 1309 860 1310 860 1311 79 1312 79 1309 79 1312 79 1311 79 1313 79 1314 861 1312 861 1313 861 1313 79 1315 79 1314 79 1314 862 1315 862 1316 862 1317 863 1316 863 1315 863 1318 79 1316 79 1317 79 1319 79 1321 79 1320 79 1322 79 1323 79 1321 79 1324 79 1316 79 1325 79 1326 79 1328 79 1327 79 1329 864 1331 864 1330 864 1301 79 1332 79 1303 79 1332 865 1333 865 1294 865 1316 79 1318 79 1325 79 1334 79 1335 79 1323 79 1319 79 1320 79 1333 79 1336 866 1337 866 1335 866 1323 79 1322 79 1334 79 1338 867 1340 867 1339 867 1341 79 1342 79 1340 79 1336 868 1335 868 1343 868 1344 79 1341 79 1345 79 1338 869 1337 869 1336 869 1346 79 1345 79 1347 79 1347 870 1295 870 1306 870 1347 871 1306 871 1346 871 1347 79 1345 79 1341 79 1344 79 1342 79 1341 79 1342 872 1339 872 1340 872 1339 79 1337 79 1338 79 1343 79 1335 79 1334 79 1322 79 1321 79 1319 79 1320 873 1294 873 1333 873 1294 79 1303 79 1332 79 1348 79 1350 79 1349 79 1302 874 1350 874 1348 874 1351 79 1353 79 1352 79 1354 79 1353 79 1355 79 1356 875 1358 875 1357 875 1359 79 1361 79 1360 79 1362 79 1364 79 1363 79 1363 876 1365 876 1362 876 1366 877 1368 877 1367 877 1330 79 1363 79 1364 79 1369 878 1371 878 1370 878 1369 79 1331 79 1372 79 1367 79 1368 79 1373 79 1374 879 1376 879 1375 879 1327 880 1375 880 1377 880 1374 79 1379 79 1378 79 1380 79 1374 79 1378 79 1326 79 1373 79 1328 79 1366 79 1367 79 1370 79 1376 881 1374 881 1381 881 1374 882 1380 882 1381 882 1377 79 1326 79 1327 79 1376 883 1377 883 1375 883 1368 884 1328 884 1373 884 1371 885 1369 885 1372 885 1366 79 1370 79 1371 79 1372 79 1331 79 1329 79 1330 886 1331 886 1363 886 1358 79 1365 79 1363 79 1357 887 1361 887 1356 887 1358 888 1356 888 1365 888 1360 889 1361 889 1357 889 1351 890 1352 890 1359 890 1359 79 1360 79 1351 79 1352 79 1353 79 1354 79 1354 891 1355 891 1349 891 1300 892 1350 892 1302 892 1355 79 1348 79 1349 79 1300 893 1301 893 1303 893 1382 894 1384 895 1383 895 1382 894 1386 896 1385 894 1385 894 1384 895 1382 894 1387 896 1386 896 1388 897 1386 896 1387 896 1385 894 1389 898 1390 897 1388 897 1387 896 1388 897 1390 897 1389 898 1392 899 1391 898 1391 898 1390 897 1389 898 1393 899 1392 899 1394 900 1392 899 1393 899 1391 898 1395 901 1396 902 1394 900 1393 899 1394 900 1396 902 1395 901 1398 903 1397 904 1397 904 1396 902 1395 901 1399 905 1398 903 1400 906 1398 903 1399 905 1397 904 1401 907 1402 906 1400 906 1399 905 1400 906 1402 906 1401 907 1403 907 1402 906 1384 895 1404 908 1383 895 1404 908 1405 908 1383 895 1406 909 1405 908 1407 909 1404 908 1407 909 1405 908 1408 910 1409 910 1406 909 1406 909 1407 909 1408 910 1409 910 1411 911 1410 911 1411 911 1409 910 1408 910 1412 912 1410 911 1413 912 1411 911 1413 912 1410 911 1414 913 1415 913 1412 912 1412 912 1413 912 1414 913 1415 913 1417 914 1416 914 1417 914 1415 913 1414 913 1418 915 1416 914 1419 915 1417 914 1419 915 1416 914 1420 916 1421 916 1418 915 1418 915 1419 915 1420 916 1421 916 1423 917 1422 917 1423 917 1421 916 1420 916 1423 917 1424 918 1422 917 1422 917 1424 918 1425 918 1426 60 1428 60 1427 60 1429 919 1431 919 1430 919 1432 60 1434 60 1433 60 1433 60 1434 60 1435 60 1436 920 1437 920 1435 920 1435 921 1434 921 1436 921 1438 60 1440 60 1439 60 1441 60 1437 60 1436 60 1442 60 1443 60 1441 60 1437 60 1441 60 1443 60 1442 922 1445 922 1444 922 1444 923 1443 923 1442 923 1446 60 1448 60 1447 60 1445 60 1431 60 1444 60 1430 60 1431 60 1445 60 1449 924 1429 924 1430 924 1427 60 1449 60 1426 60 1449 925 1427 925 1429 925 1426 60 1450 60 1428 60 1428 60 1450 60 1451 60 1452 60 1450 60 1426 60 1453 60 1455 60 1454 60 1455 926 1456 926 1454 926 1457 60 1459 60 1458 60 1460 60 1462 60 1461 60 1463 927 1465 927 1464 927 1466 928 1461 928 1467 928 1468 60 1470 60 1469 60 1471 60 1473 60 1472 60 1469 60 1472 60 1474 60 1474 929 1468 929 1469 929 1475 60 1476 60 1468 60 1473 60 1471 60 1477 60 1472 930 1473 930 1474 930 1471 931 1478 931 1477 931 1467 932 1477 932 1478 932 1467 60 1478 60 1466 60 1479 60 1480 60 1462 60 1460 933 1461 933 1466 933 1481 934 1483 934 1482 934 1484 60 1480 60 1479 60 1479 60 1486 60 1485 60 1458 60 1482 60 1487 60 1485 60 1484 60 1479 60 1488 60 1490 60 1489 60 1481 60 1492 60 1491 60 1462 60 1460 60 1479 60 1493 60 1455 60 1459 60 1494 60 1492 60 1495 60 1495 60 1497 60 1496 60 1465 60 1498 60 1497 60 1475 60 1463 60 1499 60 1468 935 1476 935 1470 935 1475 936 1499 936 1476 936 1463 937 1464 937 1499 937 1463 60 1498 60 1465 60 1498 60 1496 60 1497 60 1496 60 1494 60 1495 60 1494 60 1491 60 1492 60 1491 60 1483 60 1481 60 1483 60 1487 60 1482 60 1493 938 1459 938 1457 938 1487 60 1457 60 1458 60 1456 60 1451 60 1454 60 1493 60 1456 60 1455 60 1450 60 1454 60 1451 60 1488 60 1489 60 1500 60 1501 939 1490 939 1502 939 1501 940 1504 940 1503 940 1503 941 1505 941 1447 941 1488 60 1502 60 1490 60 1448 942 1507 942 1506 942 1502 943 1504 943 1501 943 1439 60 1508 60 1507 60 1433 944 1440 944 1509 944 1433 945 1509 945 1432 945 1440 946 1438 946 1509 946 1440 60 1508 60 1439 60 1508 947 1506 947 1507 947 1506 60 1447 60 1448 60 1446 948 1447 948 1505 948 1505 949 1503 949 1504 949 1510 950 1500 950 1511 950 1489 60 1511 60 1500 60 1510 60 1511 60 1512 60 1510 60 1512 60 1513 60 1514 60 1510 60 1515 60 1513 60 1515 60 1510 60 1516 951 1518 951 1517 951 1518 952 1516 952 1519 952 1520 953 1522 953 1521 953 1523 954 1525 954 1524 954 1523 955 1527 955 1526 955 1528 956 1523 956 1529 956 1523 957 1526 957 1529 957 1530 958 1523 958 1531 958 1523 959 1528 959 1531 959 1523 960 1532 960 1525 960 1523 961 1530 961 1532 961 1523 962 1534 962 1533 962 1524 963 1534 963 1523 963 1521 964 1523 964 1535 964 1533 965 1535 965 1523 965 1536 966 1521 966 1537 966 1521 967 1535 967 1537 967 1538 968 1521 968 1539 968 1521 969 1536 969 1539 969 1521 970 1540 970 1520 970 1521 971 1538 971 1540 971 1521 972 1542 972 1541 972 1522 973 1542 973 1521 973 1543 974 1521 974 1541 974 1543 975 1545 975 1544 975 1546 976 1543 976 1547 976 1543 977 1541 977 1547 977 1548 978 1543 978 1549 978 1543 979 1546 979 1549 979 1543 980 1550 980 1545 980 1543 981 1548 981 1550 981 1543 982 1552 982 1551 982 1544 983 1552 983 1543 983 1553 984 1527 984 1551 984 1543 985 1551 985 1527 985 1554 729 1527 729 1555 729 1527 986 1553 986 1555 986 1556 987 1527 987 1557 987 1527 988 1554 988 1557 988 1558 989 1527 989 1559 989 1527 990 1556 990 1559 990 1560 991 1527 991 1561 991 1527 992 1558 992 1561 992 1526 993 1527 993 1560 993 1562 994 1564 994 1563 994 1563 995 1566 995 1565 995 1563 996 1567 996 1562 996 1568 997 1570 997 1569 997 1571 998 1563 998 1572 998 1563 999 1564 999 1572 999 1573 1000 1563 1000 1574 1000 1563 1001 1571 1001 1574 1001 1563 1002 1573 1002 1566 1002 1563 1003 1576 1003 1575 1003 1565 1004 1576 1004 1563 1004 1577 1005 1569 1005 1575 1005 1563 1006 1575 1006 1569 1006 1578 1007 1569 1007 1579 1007 1569 1008 1577 1008 1579 1008 1580 1009 1569 1009 1581 1009 1569 1010 1578 1010 1581 1010 1582 1011 1569 1011 1583 1011 1569 1012 1580 1012 1583 1012 1569 1013 1582 1013 1568 1013 1570 1014 1584 1014 1569 1014 1569 1015 1584 1015 1585 1015 1586 1016 1585 1016 1587 1016 1585 1017 1584 1017 1587 1017 1588 1018 1589 1018 1585 1018 1590 1019 1585 1019 1591 1019 1585 1020 1586 1020 1591 1020 1585 1021 1592 1021 1588 1021 1585 1022 1590 1022 1592 1022 1585 1023 1594 1023 1593 1023 1589 1024 1594 1024 1585 1024 1567 1025 1585 1025 1595 1025 1593 1026 1595 1026 1585 1026 1596 1027 1567 1027 1597 1027 1567 1028 1595 1028 1597 1028 1598 1029 1567 1029 1599 1029 1567 1030 1596 1030 1599 1030 1600 1031 1567 1031 1601 1031 1567 1032 1598 1032 1601 1032 1602 1033 1567 1033 1603 1033 1567 1034 1600 1034 1603 1034 1562 761 1567 761 1602 761 1604 622 1606 121 1605 121 1607 1035 1609 619 1608 1036 1610 1037 1612 617 1611 1038 1613 626 1615 1039 1614 1040 1616 1041 1618 628 1617 628 1619 629 1621 1042 1620 638 1622 632 1624 625 1623 1043 1625 1044 1627 634 1626 635 1628 637 1630 1045 1629 1046 1631 1047 1633 1048 1632 1047 1634 641 1636 642 1635 1049 1637 643 1639 643 1638 145 1640 1050 1642 1051 1641 1052 1643 1053 1645 1054 1644 1055 1646 1056 1648 1057 1647 145 1649 1058 1651 1059 1650 1060 1652 1061 1654 1062 1653 1063 1655 1064 1657 1065 1656 1066 1658 1067 1660 1068 1659 1069 1661 1070 1663 1071 1662 1072 1663 1071 1661 1070 1664 1073 1665 1074 1666 1075 1662 1072 1662 1072 1663 1071 1665 1074 1667 1076 1666 1075 1668 1077 1665 1074 1668 1077 1666 1075 1667 1076 1670 1078 1669 1079 1670 1078 1667 1076 1668 1077 1671 1080 1672 1081 1669 1079 1669 1079 1670 1078 1671 1080 1673 1082 1672 1081 1674 1083 1671 1080 1674 1083 1672 1081 1673 1082 1676 1084 1675 672 1676 1084 1673 1082 1674 1083 1677 1085 1678 1086 1675 672 1675 672 1676 1084 1677 1085 1606 121 1678 1086 1679 674 1677 1085 1679 674 1678 1086 1605 121 1606 121 1679 674 1664 1073 1656 1066 1657 1065 1661 1070 1656 1066 1664 1073 1658 1067 1659 1069 1655 1064 1655 1064 1659 1069 1657 1065 1649 1058 1660 1068 1651 1059 1651 1059 1660 1068 1658 1067 1654 1062 1650 1060 1653 1063 1654 1062 1649 1058 1650 1060 1652 1061 1643 1053 1644 1055 1652 1061 1653 1063 1643 1053 1645 1054 1648 1057 1646 1056 1644 1055 1645 1054 1646 1056 1638 145 1639 643 1647 145 1648 1057 1638 145 1647 145 1640 1050 1641 1052 1637 643 1637 643 1641 1052 1639 643 1631 1047 1642 1051 1633 1048 1633 1048 1642 1051 1640 1050 1636 642 1631 1047 1632 1047 1634 641 1635 1049 1625 1044 1636 642 1632 1047 1635 1049 1626 635 1627 634 1628 637 1634 641 1625 1044 1626 635 1630 1045 1620 638 1629 1046 1627 634 1630 1045 1628 637 1619 629 1623 1043 1621 1042 1620 638 1621 1042 1629 1046 1615 1039 1624 625 1622 632 1622 632 1623 1043 1619 629 1618 628 1613 626 1614 1040 1613 626 1624 625 1615 1039 1616 1041 1617 628 1607 1035 1618 628 1614 1040 1617 628 1608 1036 1609 619 1611 1038 1616 1041 1607 1035 1608 1036 1610 1037 1604 622 1612 617 1609 619 1610 1037 1611 1038 1605 121 1612 617 1604 622 8765 8256 8766 8256 8767 8256 8765 8257 8767 8257 8768 8257 8769 8258 8770 8258 8771 8258 8769 8259 8771 8259 8772 8259 8773 8260 8774 8260 8775 8260 8773 8261 8775 8261 8776 8261 8777 8262 8778 8262 8779 8262 8777 8263 8779 8263 8780 8263 8781 8264 8782 8264 8783 8264 8781 8265 8783 8265 8784 8265 8785 8266 8786 8266 8787 8266 8785 8267 8787 8267 8788 8267 8789 8268 8790 8268 8791 8268 8792 8269 8793 8269 8794 8269 8795 8270 8789 8270 8791 8270 8796 8271 8790 8271 8789 8271 8789 8272 8795 8272 8797 8272 8798 8273 8799 8273 8796 8273 8796 8274 8800 8274 8798 8274 8800 8275 8796 8275 8801 8275 8802 8276 8789 8276 8803 8276 8796 8277 8804 8277 8801 8277 8789 8278 8802 8278 8805 8278 8806 8279 8807 8279 8794 8279 8796 8280 8808 8280 8804 8280 8809 8281 8792 8281 8794 8281 8810 8282 8811 8282 8812 8282 8813 8283 8814 8283 8793 8283 8815 8284 8816 8284 8812 8284 8817 8285 8818 8285 8814 8285 8815 8286 8819 8286 8820 8286 8818 8287 8821 8287 8814 8287 8814 8288 8822 8288 8815 8288 8819 1662 8815 1662 8823 1662 8823 8289 8815 8289 8822 8289 8814 8290 8813 8290 8824 8290 8814 8291 8824 8291 8817 8291 8815 8292 8820 8292 8825 8292 8826 8293 8812 8293 8816 8293 8793 8294 8814 8294 8794 8294 8794 8295 8827 8295 8809 8295 8826 8296 8810 8296 8812 8296 8807 722 8828 722 8794 722 8812 8297 8829 8297 8830 8297 8789 8298 8805 8298 8831 8298 8794 8299 8831 8299 8806 8299 8811 8300 8829 8300 8812 8300 8827 8301 8794 8301 8828 8301 8794 8302 8789 8302 8831 8302 8822 8303 8814 8303 8821 8303 8816 8304 8815 8304 8832 8304 8825 8305 8832 8305 8815 8305 8808 8306 8796 8306 8812 8306 8830 8307 8808 8307 8812 8307 8799 8308 8790 8308 8796 8308 8797 8309 8803 8309 8789 8309 8833 8310 8834 8310 8835 8310 8836 8311 8837 8311 8838 8311 8839 8312 8834 8312 8833 8312 8833 8313 8840 8313 8839 8313 8841 8314 8842 8314 8843 8314 8844 8315 8843 8315 8842 8315 8843 8316 8844 8316 8845 8316 8840 8317 8833 8317 8846 8317 8847 8318 8843 8318 8845 8318 8848 8319 8846 8319 8833 8319 8849 8320 8838 8320 8850 8320 8847 8321 8851 8321 8843 8321 8852 8322 8838 8322 8837 8322 8853 8323 8854 8323 8855 8323 8856 8324 8857 8324 8858 8324 8855 8325 8859 8325 8860 8325 8856 8326 8861 8326 8862 8326 8863 8327 8864 8327 8865 8327 8856 8328 8866 8328 8861 8328 8856 8329 8864 8329 8867 8329 8868 8330 8869 8330 8864 8330 8869 8331 8867 8331 8864 8331 8857 8332 8856 8332 8870 8332 8862 8333 8870 8333 8856 8333 8871 8334 8864 8334 8860 8334 8865 8335 8864 8335 8871 8335 8872 8336 8859 8336 8855 8336 8856 8337 8858 8337 8838 8337 8873 8338 8874 8338 8838 8338 8873 8339 8838 8339 8852 8339 8838 8340 8874 8340 8850 8340 8851 8341 8855 8341 8843 8341 8851 8342 8853 8342 8855 8342 8875 8343 8848 8343 8833 8343 8849 8344 8875 8344 8833 8344 8854 8345 8876 8345 8855 8345 8855 8346 8876 8346 8872 8346 8835 8347 8843 8347 8833 8347 8841 8348 8843 8348 8835 8348 8849 8349 8833 8349 8838 8349 8858 8350 8836 8350 8838 8350 8867 8351 8866 8351 8856 8351 8855 8352 8860 8352 8864 8352 8868 8353 8864 8353 8863 8353 8877 8354 8878 8354 8879 8355 8880 8356 8881 8357 8882 8358 8878 8354 8883 8359 8884 8359 8883 8359 8878 8354 8877 8354 8885 8360 8884 8359 8886 8360 8883 8359 8886 8360 8884 8359 8887 8361 8888 8361 8885 8360 8885 8360 8886 8360 8887 8361 8888 8361 8889 8362 8890 8362 8889 8362 8888 8361 8887 8361 8891 8363 8890 8362 8892 8363 8889 8362 8892 8363 8890 8362 8893 8364 8894 8364 8891 8363 8891 8363 8892 8363 8893 8364 8894 8364 8895 8365 8896 8366 8895 8365 8894 8364 8893 8364 8897 8367 8896 8366 8898 8368 8895 8365 8898 8368 8896 8366 8899 8369 8900 8369 8897 8367 8897 8367 8898 8368 8899 8369 8877 8354 8879 8355 8901 8355 8902 8370 8903 8371 8901 8355 8901 8355 8879 8355 8902 8370 8903 8371 8904 8372 8905 8373 8904 8372 8903 8371 8902 8370 8906 8374 8905 8373 8907 8374 8904 8372 8907 8374 8905 8373 8908 8375 8909 8375 8906 8374 8906 8374 8907 8374 8908 8375 8909 8375 8910 8376 8911 8376 8910 8376 8909 8375 8908 8375 8912 8377 8911 8376 8913 8377 8910 8376 8913 8377 8911 8376 8914 8378 8915 8378 8912 8377 8912 8377 8913 8377 8914 8378 8915 8378 8916 8379 8917 8380 8916 8379 8915 8378 8914 8378 8916 8379 8882 8358 8917 8380 8917 8380 8882 8358 8881 8357 8918 8381 8919 8382 8920 8383 8921 8384 8922 8385 8923 8356 8924 8386 8925 8387 8926 8388 8927 8389 8928 8390 8929 8391 8930 8392 8931 8393 8932 8394 8933 8395 8934 8396 8935 8397 8936 8398 8937 8399 8938 8400 8939 8401 8940 8402 8941 8403 8942 8404 8943 8405 8944 8406 8945 8407 8946 8408 8943 8405 8947 8409 8948 8410 8942 8404 8942 8404 8944 8406 8947 8409 8948 8410 8949 8411 8950 8412 8949 8411 8948 8410 8947 8409 8951 8413 8950 8412 8952 8414 8949 8411 8952 8414 8950 8412 8900 8369 8899 8369 8951 8413 8951 8413 8952 8414 8900 8369 8936 8398 8946 8408 8945 8407 8943 8405 8946 8408 8944 8406 8937 8399 8939 8401 8938 8400 8945 8407 8937 8399 8936 8398 8941 8403 8940 8402 8931 8393 8938 8400 8939 8401 8941 8403 8930 8392 8932 8394 8934 8396 8931 8393 8940 8402 8932 8394 8926 8388 8933 8395 8935 8397 8933 8395 8930 8392 8934 8396 8929 8391 8925 8387 8924 8386 8924 8386 8926 8388 8935 8397 8927 8389 8918 8381 8928 8390 8929 8391 8928 8390 8925 8387 8919 8382 8922 8385 8920 8383 8927 8389 8919 8382 8918 8381 8921 8384 8923 8356 8880 8356 8920 8383 8922 8385 8921 8384 8881 8357 8880 8356 8923 8356

+
+ + + +

1680 1087 1682 1087 1681 1087 1681 1088 1683 1088 1680 1088 1684 1089 1686 1089 1685 1089 1685 1090 1687 1090 1684 1090 1688 1091 1690 1091 1689 1091 1689 1092 1691 1092 1688 1092 1692 1093 1694 1093 1693 1093 1693 1094 1695 1094 1692 1094 1696 1095 1698 1095 1697 1095 1697 1096 1699 1096 1696 1096 1700 1097 1702 1097 1701 1097 1701 1098 1703 1098 1700 1098 1704 1099 1706 1099 1705 1099 1707 1100 1709 1100 1708 1100 1710 1101 1712 1101 1711 1101 1713 1102 1715 1102 1714 1102 1716 1103 1717 1103 1710 1103 1718 1104 1720 1104 1719 1104 1721 1105 1710 1105 1722 1105 1710 1106 1717 1106 1722 1106 1710 1107 1721 1107 1712 1107 1710 1108 1724 1108 1723 1108 1711 1109 1724 1109 1710 1109 1725 1110 1706 1110 1723 1110 1710 1111 1723 1111 1706 1111 1706 1112 1726 1112 1705 1112 1706 1113 1725 1113 1726 1113 1706 1114 1728 1114 1727 1114 1704 1115 1728 1115 1706 1115 1720 1116 1706 1116 1729 1116 1727 1117 1729 1117 1706 1117 1730 1118 1720 1118 1731 1118 1720 1119 1729 1119 1731 1119 1720 1120 1730 1120 1719 1120 1720 1121 1733 1121 1732 1121 1718 1122 1733 1122 1720 1122 1715 1123 1720 1123 1732 1123 1734 1124 1715 1124 1735 1124 1715 1125 1732 1125 1735 1125 1715 1126 1734 1126 1714 1126 1715 1127 1737 1127 1736 1127 1713 1128 1737 1128 1715 1128 1738 1129 1708 1129 1736 1129 1715 1130 1736 1130 1708 1130 1709 1131 1739 1131 1708 1131 1708 1132 1738 1132 1707 1132 1708 1133 1741 1133 1740 1133 1739 1134 1741 1134 1708 1134 1716 1135 1708 1135 1742 1135 1740 1136 1742 1136 1708 1136 1743 1137 1716 1137 1744 1137 1716 1138 1742 1138 1744 1138 1745 1139 1716 1139 1746 1139 1716 1140 1743 1140 1746 1140 1717 1141 1716 1141 1747 1141 1716 1142 1745 1142 1747 1142 1748 1143 1750 1143 1749 1143 1751 1144 1752 1144 1749 1144 1753 1145 1755 1145 1754 1145 1756 1146 1758 1146 1757 1146 1759 1147 1761 1147 1760 1147 1762 1148 1764 1148 1763 1148 1765 1149 1766 1149 1749 1149 1749 1150 1766 1150 1751 1150 1749 1151 1750 1151 1765 1151 1749 1152 1768 1152 1767 1152 1748 1153 1749 1153 1767 1153 1769 1154 1768 1154 1755 1154 1749 1155 1755 1155 1768 1155 1755 1156 1753 1156 1770 1156 1755 1157 1770 1157 1769 1157 1755 1158 1772 1158 1771 1158 1754 1159 1755 1159 1771 1159 1760 1160 1773 1160 1755 1160 1772 1161 1755 1161 1773 1161 1774 1162 1775 1162 1760 1162 1760 1163 1775 1163 1773 1163 1760 1164 1761 1164 1774 1164 1760 1165 1777 1165 1776 1165 1759 1166 1760 1166 1776 1166 1778 1167 1777 1167 1762 1167 1760 1168 1762 1168 1777 1168 1762 1169 1763 1169 1779 1169 1762 1170 1779 1170 1778 1170 1762 1171 1781 1171 1780 1171 1764 1172 1762 1172 1780 1172 1782 1173 1781 1173 1756 1173 1762 1174 1756 1174 1781 1174 1758 1175 1756 1175 1783 1175 1756 1176 1757 1176 1782 1176 1756 1177 1785 1177 1784 1177 1783 1178 1756 1178 1784 1178 1752 1179 1786 1179 1756 1179 1785 1180 1756 1180 1786 1180 1787 1181 1788 1181 1752 1181 1752 1182 1788 1182 1786 1182 1789 1183 1790 1183 1752 1183 1752 1184 1790 1184 1787 1184 1751 1185 1791 1185 1752 1185 1752 1186 1791 1186 1789 1186 1792 1187 1794 1188 1793 1189 1795 1190 1797 1191 1796 1191 1798 1192 1800 1187 1799 1193 1801 1194 1803 1195 1802 1194 1804 1190 1806 1196 1805 1197 1807 1198 1809 1199 1808 1200 1810 1201 1812 1195 1811 1201 1813 1202 1815 1203 1814 1204 1816 1205 1818 1206 1817 1207 1819 1208 1821 1209 1820 1210 1822 1202 1824 1211 1823 1212 1825 1213 1827 1214 1826 1215 1828 1216 1830 1217 1829 1218 1831 1219 1833 1220 1832 1221 1834 1222 1836 1223 1835 1224 1837 1225 1839 1226 1838 1227 1840 1228 1842 1229 1841 1230 1843 1231 1845 1232 1844 1233 1846 1234 1848 1235 1847 1236 1849 1237 1851 1238 1850 1239 1851 1238 1849 1237 1852 1240 1853 1241 1854 1242 1850 1239 1850 1239 1851 1238 1853 1241 1855 1243 1854 1242 1856 1244 1853 1241 1856 1244 1854 1242 1855 1243 1858 1245 1857 1246 1858 1245 1855 1243 1856 1244 1859 1247 1860 1248 1857 1246 1857 1246 1858 1245 1859 1247 1861 1249 1860 1248 1862 1250 1859 1247 1862 1250 1860 1248 1861 1249 1864 1251 1863 1252 1864 1251 1861 1249 1862 1250 1865 1253 1866 1254 1863 1252 1863 1252 1864 1251 1865 1253 1794 1188 1866 1254 1867 1254 1865 1253 1867 1254 1866 1254 1793 1189 1794 1188 1867 1254 1852 1240 1844 1233 1845 1232 1849 1237 1844 1233 1852 1240 1846 1234 1847 1236 1843 1231 1843 1231 1847 1236 1845 1232 1837 1225 1848 1235 1839 1226 1839 1226 1848 1235 1846 1234 1842 1229 1838 1227 1841 1230 1842 1229 1837 1225 1838 1227 1840 1228 1831 1219 1832 1221 1840 1228 1841 1230 1831 1219 1833 1220 1836 1223 1834 1222 1832 1221 1833 1220 1834 1222 1826 1215 1827 1214 1835 1224 1836 1223 1826 1215 1835 1224 1828 1216 1829 1218 1825 1213 1825 1213 1829 1218 1827 1214 1819 1208 1830 1217 1821 1209 1821 1209 1830 1217 1828 1216 1824 1211 1819 1208 1820 1210 1822 1202 1823 1212 1813 1202 1824 1211 1820 1210 1823 1212 1814 1204 1815 1203 1816 1205 1822 1202 1813 1202 1814 1204 1818 1206 1808 1200 1817 1207 1815 1203 1818 1206 1816 1205 1807 1198 1811 1201 1809 1199 1808 1200 1809 1199 1817 1207 1803 1195 1812 1195 1810 1201 1810 1201 1811 1201 1807 1198 1806 1196 1801 1194 1802 1194 1801 1194 1812 1195 1803 1195 1804 1190 1805 1197 1795 1190 1806 1196 1802 1194 1805 1197 1796 1191 1797 1191 1799 1193 1804 1190 1795 1190 1796 1191 1798 1192 1792 1187 1800 1187 1797 1191 1798 1192 1799 1193 1793 1189 1800 1187 1792 1187

+
+ + + +

8953 8415 8954 8415 8955 8415 8956 8416 8955 8416 8954 8416 8957 8417 8953 8417 8955 8417 8954 8418 8958 8418 8956 8418 8959 8419 8960 8419 8961 8419 8959 8420 8962 8420 8960 8420 8963 8421 8964 8421 8965 8421 8963 8422 8966 8422 8964 8422 8967 8423 8968 8423 8969 8423 8967 8424 8970 8424 8968 8424 8971 8425 8972 8425 8973 8425 8971 8426 8974 8426 8972 8426 8975 8427 8976 8427 8977 8427 8975 8428 8978 8428 8976 8428 8979 8429 8980 8429 8981 8429 8979 8430 8982 8430 8980 8430 8983 8431 8984 8431 8985 8431 8986 8432 8987 8432 8988 8432 8984 8433 8989 8433 8985 8433 8983 8434 8990 8434 8984 8434 8989 8435 8984 8435 8991 8435 8990 8436 8983 8436 8992 8436 8992 8437 8993 8437 8990 8437 8994 8438 8990 8438 8993 8438 8995 8439 8991 8439 8984 8439 8994 8440 8996 8440 8990 8440 8997 8441 8984 8441 8998 8441 8987 8442 8999 8442 9000 8442 8987 8443 9001 8443 8998 8443 8986 8444 9002 8444 8987 8444 9003 8445 9004 8445 9005 8445 8988 8446 9006 8446 9007 8446 9008 8447 9003 8447 9009 8447 8988 8448 9010 8448 9011 8448 9012 8449 9013 8449 9014 8449 9015 8450 8988 8450 9012 8450 9016 8451 9015 8451 9012 8451 9014 8452 9017 8452 9012 8452 9016 8453 9012 8453 9017 8453 9006 8454 8988 8454 9018 8454 9018 8455 8988 8455 9011 8455 9003 8456 9008 8456 9012 8456 9003 8457 9019 8457 9009 8457 9007 8458 8986 8458 8988 8458 9020 8459 9021 8459 8987 8459 9022 8460 9019 8460 9003 8460 9021 8461 8999 8461 8987 8461 9003 8462 9023 8462 9024 8462 9003 8463 9024 8463 9004 8463 8987 8464 8998 8464 8984 8464 9000 8465 9001 8465 8987 8465 8996 8466 9025 8466 8990 8466 8990 8467 9025 8467 9023 8467 8995 8468 8984 8468 8997 8468 9002 8469 9020 8469 8987 8469 9015 8470 9010 8470 8988 8470 9008 8471 9026 8471 9012 8471 9013 8472 9012 8472 9026 8472 8990 8473 9023 8473 9003 8473 9022 8474 9003 8474 9005 8474 9027 8475 9028 8476 9029 8477 9030 8478 9031 8478 9032 8479 9033 8480 9029 8477 9034 8481 9028 8476 9034 8481 9029 8477 9035 8482 9036 8482 9033 8480 9033 8480 9034 8481 9035 8482 9036 8482 9037 8483 9038 8484 9037 8483 9036 8482 9035 8482 9039 8485 9038 8484 9040 8486 9037 8483 9040 8486 9038 8484 9041 8487 9042 8487 9039 8485 9039 8485 9040 8486 9041 8487 9042 8487 9043 8488 9044 8489 9043 8488 9042 8487 9041 8487 9045 8490 9044 8489 9046 8491 9043 8488 9046 8491 9044 8489 9047 8492 9048 8493 9045 8490 9045 8490 9046 8491 9047 8492 9049 8494 9048 8493 9047 8492 9049 8494 9050 8494 9048 8493 9028 8476 9027 8475 9051 8495 9052 8496 9053 8496 9051 8495 9051 8495 9027 8475 9052 8496 9053 8496 9054 8497 9055 8497 9054 8497 9053 8496 9052 8496 9056 8498 9055 8497 9057 8499 9054 8497 9057 8499 9055 8497 9058 8500 9059 8501 9056 8498 9056 8498 9057 8499 9058 8500 9059 8501 9060 8502 9061 8503 9060 8502 9059 8501 9058 8500 9062 8504 9061 8503 9063 8504 9060 8502 9063 8504 9061 8503 9064 8505 9065 8505 9062 8504 9062 8504 9063 8504 9064 8505 9065 8505 9066 8506 9067 8507 9066 8506 9065 8505 9064 8505 9066 8506 9031 8478 9067 8507 9068 8508 9069 8479 9070 8508 9067 8507 9031 8478 9030 8478 9071 8509 9072 8510 9073 8511 9074 8512 9075 8512 9076 8510 9077 8513 9078 8514 9079 8514 9080 8515 9081 8516 9082 8517 9083 8518 9084 8518 9085 8519 9086 8520 9087 8521 9088 8522 9089 8523 9090 8524 9091 8525 9092 8526 9093 8527 9094 8524 9095 8528 9096 8529 9097 8530 9089 8523 9097 8530 9096 8529 9095 8528 9098 8531 9099 8532 9099 8532 9096 8529 9095 8528 9100 8533 9098 8531 9101 8534 9098 8531 9100 8533 9099 8532 9050 8494 9102 8535 9101 8534 9100 8533 9101 8534 9102 8535 9049 8494 9102 8535 9050 8494 9090 8524 9094 8524 9091 8525 9089 8523 9091 8525 9097 8530 9092 8526 9084 8518 9093 8527 9090 8524 9092 8526 9094 8524 9083 8518 9085 8519 9086 8520 9093 8527 9084 8518 9083 8518 9088 8522 9087 8521 9079 8514 9086 8520 9085 8519 9087 8521 9081 8516 9078 8514 9077 8513 9078 8514 9088 8522 9079 8514 9071 8509 9080 8515 9082 8517 9082 8517 9081 8516 9077 8513 9072 8510 9076 8510 9073 8511 9071 8509 9073 8511 9080 8515 9074 8512 9068 8508 9075 8512 9072 8510 9074 8512 9076 8510 9070 8508 9069 8479 9032 8479 9075 8512 9068 8508 9070 8508 9030 8478 9032 8479 9069 8479 9103 8536 9104 8536 9105 8536 9106 8537 9107 8537 9108 8537 9107 8538 9109 8538 9110 8538 9106 8539 9111 8539 9112 8539 9113 8540 9109 8540 9114 8540 9115 8541 9116 8541 9112 8541 9117 8542 9114 8542 9118 8542 9119 8543 9116 8543 9120 8543 9121 8544 9122 8544 9118 8544 9119 8545 9123 8545 9103 8545 9124 8546 9121 8546 9125 8546 9126 8547 9127 8547 9128 8547 9129 8548 9130 8548 9131 8548 9132 8549 9133 8549 9134 8549 9135 8550 9136 8550 9137 8550 9138 8551 9139 8551 9140 8551 9141 8552 9142 8552 9143 8552 9144 8553 9145 8553 9139 8553 9146 8554 9144 8554 9147 8554 9148 8555 9149 8555 9150 8555 9147 8556 9151 8556 9152 8556 9153 8557 9138 8557 9154 8557 9155 8558 9156 8558 9157 8558 9153 8559 9158 8559 9134 8559 9137 8560 9159 8560 9135 8560 9160 8561 9159 8561 9161 8561 9137 8562 9136 8562 9126 8562 9162 8563 9163 8563 9164 8563 9165 8564 9166 8564 9167 8564 9126 8565 9136 8565 9127 8565 9128 8566 9168 8566 9169 8566 9130 8567 9170 8567 9171 8567 9172 8568 9131 8568 9173 8568 9174 8569 9105 8569 9169 8569 9175 8570 9173 8570 9124 8570 9133 8571 9176 8571 9177 8571 9177 8572 9162 8572 9178 8572 9148 8573 9150 8573 9151 8573 9127 8574 9168 8574 9128 8574 9168 8575 9174 8575 9169 8575 9105 8576 9104 8576 9169 8576 9103 8560 9123 8560 9104 8560 9119 8577 9120 8577 9123 8577 9116 8578 9115 8578 9120 8578 9112 8579 9111 8579 9115 8579 9106 8580 9108 8580 9111 8580 9107 8581 9110 8581 9108 8581 9109 8582 9113 8582 9110 8582 9114 8583 9117 8583 9113 8583 9118 8584 9122 8584 9117 8584 9118 8585 9125 8585 9121 8585 9125 8586 9175 8586 9124 8586 9175 8587 9172 8587 9173 8587 9172 8588 9129 8588 9131 8588 9129 8589 9170 8589 9130 8589 9170 8590 9166 8590 9171 8590 9166 8591 9165 8591 9171 8591 9167 8592 9164 8592 9163 8592 9167 8593 9163 8593 9165 8593 9164 8594 9178 8594 9162 8594 9177 8595 9176 8595 9162 8595 9133 8596 9132 8596 9176 8596 9134 8597 9158 8597 9132 8597 9153 8598 9154 8598 9158 8598 9138 8599 9140 8599 9154 8599 9139 8600 9145 8600 9140 8600 9144 8601 9146 8601 9145 8601 9147 8602 9152 8602 9146 8602 9151 8603 9150 8603 9152 8603 9148 8604 9143 8604 9149 8604 9141 8605 9156 8605 9142 8605 9148 8606 9141 8606 9143 8606 9155 8607 9157 8607 9161 8607 9142 8608 9156 8608 9155 8608 9159 8609 9160 8609 9135 8609 9161 8610 9157 8610 9160 8610 9179 8520 9180 8519 9181 8521 9182 8507 9183 8611 9184 8611 9180 8519 9185 8612 9186 8518 9185 8612 9180 8519 9179 8520 9187 8613 9186 8518 9188 8526 9185 8612 9188 8526 9186 8518 9189 8524 9190 8524 9187 8613 9187 8613 9188 8526 9189 8524 9190 8524 9191 8523 9192 8523 9191 8523 9190 8524 9189 8524 9193 8614 9192 8523 9194 8614 9191 8523 9194 8614 9192 8523 9195 8528 9196 8528 9193 8614 9193 8614 9194 8614 9195 8528 9196 8528 9197 8533 9198 8533 9197 8533 9196 8528 9195 8528 9199 8615 9198 8533 9200 8615 9197 8533 9200 8615 9198 8533 9201 8616 9202 8617 9199 8615 9199 8615 9200 8615 9201 8616 9179 8520 9181 8521 9203 8521 9204 8514 9205 8514 9203 8521 9203 8521 9181 8521 9204 8514 9205 8514 9206 8513 9207 8516 9206 8513 9205 8514 9204 8514 9208 8517 9207 8516 9209 8515 9206 8513 9209 8515 9207 8516 9210 8618 9211 8511 9208 8517 9208 8517 9209 8515 9210 8618 9211 8511 9212 8510 9213 8510 9212 8510 9211 8511 9210 8618 9214 8512 9213 8510 9215 8512 9212 8510 9215 8512 9213 8510 9216 8619 9217 8508 9214 8512 9214 8512 9215 8512 9216 8619 9217 8508 9218 8479 9219 8620 9218 8479 9217 8508 9216 8619 9218 8479 9184 8611 9219 8620 9219 8620 9184 8611 9183 8611 9220 8621 9221 8622 9222 8623 9223 8505 9224 8624 9225 8625 9226 8626 9227 8627 9228 8628 9229 8629 9230 8630 9231 8631 9232 8632 9233 8633 9234 8634 9235 8635 9236 8636 9237 8637 9238 8638 9239 8639 9240 8640 9241 8641 9242 8642 9243 8643 9244 8644 9245 8645 9246 8646 9247 8647 9248 8648 9245 8645 9249 8649 9250 8650 9244 8644 9244 8644 9246 8646 9249 8649 9250 8650 9251 8651 9252 8652 9251 8651 9250 8650 9249 8649 9253 8492 9252 8652 9254 8493 9251 8651 9254 8493 9252 8652 9202 8617 9201 8616 9253 8492 9253 8492 9254 8493 9202 8617 9238 8638 9248 8648 9247 8647 9245 8645 9248 8648 9246 8646 9239 8639 9241 8641 9240 8640 9247 8647 9239 8639 9238 8638 9243 8643 9242 8642 9233 8633 9240 8640 9241 8641 9243 8643 9232 8632 9234 8634 9236 8636 9233 8633 9242 8642 9234 8634 9228 8628 9235 8635 9237 8637 9235 8635 9232 8632 9236 8636 9231 8631 9227 8627 9226 8626 9226 8626 9228 8628 9237 8637 9229 8629 9220 8621 9230 8630 9231 8631 9230 8630 9227 8627 9221 8622 9224 8624 9222 8623 9229 8629 9221 8622 9220 8621 9223 8505 9225 8625 9182 8507 9222 8623 9224 8624 9223 8505 9183 8611 9182 8507 9225 8625 9255 8653 9256 8653 9257 8653 9258 8654 9259 8654 9260 8654 9261 8539 9258 8539 9262 8539 9263 8655 9264 8655 9265 8655 9266 8656 9267 8656 9268 8656 9264 8657 9269 8657 9270 8657 9267 8658 9271 8658 9272 8658 9273 8659 9274 8659 9275 8659 9271 8660 9276 8660 9277 8660 9278 8661 9279 8661 9280 8661 9276 8662 9257 8662 9281 8662 9282 8663 9283 8663 9284 8663 9256 8587 9285 8587 9286 8587 9287 8664 9288 8664 9289 8664 9290 8665 9291 8665 9292 8665 9293 8666 9294 8666 9295 8666 9296 8667 9297 8667 9298 8667 9299 8668 9300 8668 9301 8668 9302 8669 9303 8669 9304 8669 9303 8670 9305 8670 9306 8670 9307 8671 9296 8671 9308 8671 9302 8669 9309 8669 9308 8669 9305 8672 9310 8672 9311 8672 9298 8673 9312 8673 9313 8673 9301 8674 9314 8674 9310 8674 9299 8675 9315 8675 9316 8675 9317 8676 9313 8676 9292 8676 9290 8677 9318 8677 9319 8677 9266 8678 9261 8678 9262 8678 9294 8679 9293 8679 9284 8679 9320 8680 9318 8680 9289 8680 9321 8681 9322 8681 9287 8681 9282 8682 9284 8682 9293 8682 9323 8587 9283 8587 9324 8587 9325 8683 9321 8683 9326 8683 9323 8684 9327 8684 9328 8684 9324 8685 9283 8685 9282 8685 9286 8686 9329 8686 9326 8686 9315 8687 9295 8687 9316 8687 9316 8688 9295 8688 9294 8688 9300 8539 9299 8539 9316 8539 9314 8662 9301 8662 9300 8662 9311 8689 9310 8689 9314 8689 9306 8690 9305 8690 9311 8690 9304 8691 9303 8691 9306 8691 9309 8692 9302 8692 9304 8692 9307 8693 9308 8693 9309 8693 9297 8694 9296 8694 9307 8694 9312 8695 9298 8695 9297 8695 9317 8696 9298 8696 9313 8696 9291 8697 9317 8697 9292 8697 9319 8698 9291 8698 9290 8698 9320 8699 9319 8699 9318 8699 9288 8685 9320 8685 9289 8685 9322 8700 9288 8700 9287 8700 9325 8701 9322 8701 9321 8701 9329 8702 9325 8702 9326 8702 9285 8703 9329 8703 9286 8703 9255 8704 9285 8704 9256 8704 9281 8587 9257 8587 9256 8587 9277 8694 9276 8694 9281 8694 9272 8705 9271 8705 9277 8705 9268 8706 9267 8706 9272 8706 9261 8707 9266 8707 9268 8707 9258 8708 9260 8708 9262 8708 9259 8709 9265 8709 9260 8709 9330 8710 9264 8710 9263 8710 9263 8588 9265 8588 9259 8588 9270 8711 9269 8711 9275 8711 9264 8712 9330 8712 9269 8712 9274 8713 9273 8713 9278 8713 9270 8550 9275 8550 9274 8550 9279 8714 9328 8714 9280 8714 9273 8715 9279 8715 9278 8715 9323 8677 9324 8677 9327 8677 9328 8716 9327 8716 9280 8716 9331 8717 9332 8717 9333 8717 9334 8718 9335 8718 9336 8718 9337 8719 9338 8719 9333 8719 9331 8720 9333 8720 9338 8720 9337 8721 9339 8721 9340 8721 9340 8722 9338 8722 9337 8722 9340 8723 9339 8723 9341 8723 9342 8724 9343 8724 9341 8724 9341 8725 9339 8725 9342 8725 9343 8726 9344 8726 9345 8726 9344 8727 9343 8727 9342 8727 9346 8728 9347 8728 9348 8728 9344 8729 9346 8729 9345 8729 9349 8730 9350 8730 9351 8730 9352 8731 9353 8731 9354 8731 9334 8732 9336 8732 9355 8732 9356 8733 9357 8733 9335 8733 9358 8734 9359 8734 9360 8734 9361 8735 9362 8735 9363 8735 9364 8736 9365 8736 9366 8736 9367 8737 9364 8737 9368 8737 9368 8738 9359 8738 9367 8738 9364 8739 9367 8739 9365 8739 9360 8740 9362 8740 9358 8740 9368 8741 9360 8741 9359 8741 9361 8742 9363 8742 9355 8742 9358 8743 9362 8743 9361 8743 9336 8744 9335 8744 9357 8744 9355 8745 9363 8745 9334 8745 9350 8746 9349 8746 9356 8746 9356 8747 9349 8747 9357 8747 9350 8748 9352 8748 9351 8748 9353 8749 9347 8749 9354 8749 9352 8750 9354 8750 9351 8750 9346 8751 9348 8751 9345 8751 9353 8752 9348 8752 9347 8752 9369 8753 9370 8521 9371 8519 9372 8493 9373 8616 9374 8616 9370 8521 9375 8514 9376 8754 9375 8514 9370 8521 9369 8753 9377 8755 9376 8754 9378 8513 9375 8514 9378 8513 9376 8754 9379 8756 9380 8515 9377 8755 9377 8755 9378 8513 9379 8756 9380 8515 9381 8757 9382 8618 9381 8757 9380 8515 9379 8756 9383 8758 9382 8618 9384 8759 9381 8757 9384 8759 9382 8618 9385 8512 9386 8760 9383 8758 9383 8758 9384 8759 9385 8512 9386 8760 9387 8508 9388 8508 9387 8508 9386 8760 9385 8512 9389 8761 9388 8508 9390 8620 9387 8508 9390 8620 9388 8508 9391 8611 9392 8478 9389 8761 9389 8761 9390 8620 9391 8611 9369 8753 9371 8519 9393 8520 9394 8518 9395 8762 9393 8520 9393 8520 9371 8519 9394 8518 9395 8762 9396 8526 9397 8613 9396 8526 9395 8762 9394 8518 9398 8524 9397 8613 9399 8524 9396 8526 9399 8524 9397 8613 9400 8523 9401 8523 9398 8524 9398 8524 9399 8524 9400 8523 9401 8523 9402 8530 9403 8530 9402 8530 9401 8523 9400 8523 9404 8528 9403 8530 9405 8528 9402 8530 9405 8528 9403 8530 9406 8763 9407 8764 9404 8528 9404 8528 9405 8528 9406 8763 9407 8764 9408 8765 9409 8535 9408 8765 9407 8764 9406 8763 9408 8765 9374 8616 9409 8535 9409 8535 9374 8616 9373 8616 9410 8766 9411 8767 9412 8768 9413 8769 9414 8490 9415 8770 9416 8484 9417 8771 9418 8772 9419 8773 9420 8774 9421 8775 9422 8776 9423 8777 9424 8778 9425 8779 9426 8780 9427 8781 9428 8782 9429 8783 9430 8784 9431 8785 9432 8786 9433 8787 9434 8502 9435 8500 9436 8788 9437 8789 9438 8790 9435 8500 9439 8791 9440 8792 9434 8502 9434 8502 9436 8788 9439 8791 9440 8792 9441 8793 9442 8505 9441 8793 9440 8792 9439 8791 9443 8794 9442 8505 9444 8795 9441 8793 9444 8795 9442 8505 9392 8478 9391 8611 9443 8794 9443 8794 9444 8795 9392 8478 9428 8782 9438 8790 9437 8789 9435 8500 9438 8790 9436 8788 9429 8783 9431 8785 9430 8784 9437 8789 9429 8783 9428 8782 9433 8787 9432 8786 9423 8777 9430 8784 9431 8785 9433 8787 9422 8776 9424 8778 9426 8780 9423 8777 9432 8786 9424 8778 9418 8772 9425 8779 9427 8781 9425 8779 9422 8776 9426 8780 9421 8775 9417 8771 9416 8484 9416 8484 9418 8772 9427 8781 9419 8773 9410 8766 9420 8774 9421 8775 9420 8774 9417 8771 9411 8767 9414 8490 9412 8768 9419 8773 9411 8767 9410 8766 9413 8769 9415 8770 9372 8493 9412 8768 9414 8490 9413 8769 9373 8616 9372 8493 9415 8770

+
+
+
+
+ + + + -1 2.46003e-14 1.50996e-7 -0.0584626 1.50996e-7 1.62921e-7 1 0.0649763 0 1 -1.62921e-7 0.0238849 0 0 0 1 + + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_wing_collision.stl b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_left_wing_collision.stl new file mode 100644 index 0000000000000000000000000000000000000000..85d25a4d3c96cef046131c7f07de853f9cce1d54 GIT binary patch literal 65334 zcmbS!bzBwO_x50SH(nD3J7}0a0|ttKEp}tKV$j%yjosZzDR9o%9oUIo*Y3K;yVoAi z_dLV({{DE+U+Z)BdRFh4z4x5caLmvl!-IPTmFqox$e?od2KE{p)N6Q+x;5P$Yr07P zAD@z0C24%(10`xNOKITSOPd=s+~ikiBAXezS)Ng(kEzD(WTobvZF1=sJ;nEn-zUkE zG-*LEbJV#`o;AWkG~`0G%f?WFHs4L)h+n4zw8XMyQ`&f!FzC2DKU~NiUEzpqMA(dt zP&*#|;vTg=pMu)`(|QZJxprNXPvqz=(2?IRa~*HLMXA}&+j%;5Ym|ysAp#{yQl*Pc zlmab7lVe_nswfK)4$nsj9X}V`M<0utd5K;c&7-3(JE1s8tCy^YThG1?mb9Y(lN_c zIaB-og1#|6k^7;4bi}Hm!J?(;hi&pFhoOQ#_sEDgB9`YJEx4YJNRbg;>P3k7-s30b z9Ch64J5sc4Uw2*3-%htGrPn3-eZx`Wd$qyY42a`T^!h0rf5yO-X@8hN>|Avq0|K=p z7g}qzs^80od(je`76XLbOXqLO#j*wonsi$c9cy~IVoR-_djGgRSCgk**6A@FPXdCl zC>Ql%M65c9!VF^8P@j(Y^(#u^#Sg3>te8JXxBR7@E?60e{&%dn=h~xY z!7fjE?b4WdVCQx@FRv1!myFvge>gN)(0}v3@;^T`qAu~;C9aOE_Q_A@1q=EE?{~>l zM+^E3uNWf&xeRE~ZAG;9tC?i6>KN})w!BA?zRSEvSuA|T>)47Q3b`uq3MWJjUg3X6 z#Kig}AlE`(;e?pWD?H$iPG<^E$)E#0eB3KcAj;o5C8JMPtG=CF;EYkkC|LZXs9O<4 zp>{-D{Gi2BVyEn(ZyK(8IfAKs_QR4_EALJ^RW-n7SAcO zMjePiE{wDlQS{LL1Z=_Fpd>y<*|gMxj%V@=>QhJ?RZpK&*G$#q7qj)c+7@+5*4F6r zig%q8+^Q#YyQ<&bCz zva%GA4064Dwh`YST95^Fylh|9^-N1uw75kamCvvD5OlZ0*X4`(6hWWyxy$pRf1=g8 zKFyOdYh6W4sXHg+%{IC|*E}imfWz&@_m0<(|3+Bm+RNn{h?cEoj?05mnhE;a!Ts{F zY2r_V+20 zbnH-1!FAmAq5QX_?$g7WH)YgqMG%E8XbDO(BG7is0iulv%sEyGqOFKhZ*RGxhv@mA zt0XCR;UtU|<{Z(w4$7dZz&HZ}vx(JXwTdX@!aV;QK{`GUYw3oSfpvvws}8S4#a$7B z)rV*+!mZpA7v#d6V@+ETL}3dej5+VNKa=X~e8qG;xP#_w3Sd)ydMRb5W@EM9F!ueI zm$IkwH+e{!7kirBS1GplBd^`PelwI40RiTo>xZf-{%zPp-V(m>fc)1sFZP1d1^D_Z z>YrvpQVWTmotH1qr5^23#^m`cP(`ky0G!^J#ya|so>7JGJOUVP3dxZ`F9#J2%q+H|i;rZ34(%CHta z*=KIaT;;8d2$UpA3mt;B#&>u5T z>a_ux_)PZt~&+H)3-&kg@!}j?Cb}cz~>L9-;6}cSmcMw*2?asuEi0x~7sO?(j zHq{yVQkmE|NN`neb4_N)^f5TC;RD%-80S4uUFvwqV{)}43bvpQlq5;sxhkor=T9;< z`dUxJmTKdg3w;l6B+89ub`*Y$`e5cg%9QW1ye(l2t1&1_L#|=f>I<%1^Gz8LnMU={ zR_|@blH0yCV-zvEh?b-Z8wzS_t<|Pqvs!4_g8ERBBu)6%S3UN(6KnM2f*I|_SfPKC z^loN=Hl$5;_Q|mXU;Ff8IVM(DO6|Wb*DBve(1F2O*@0u7*fTy7HFz%Z4F0+#tGAZ5 zGTm=iT|1S}o&C*Q3UzrR&l~S6=);LwS*yC9EIXGJv+4_vRlv~@b?wRqY?0Ja!IqGo z-a^O3^800!#Mg-z`>Bcd7Nn#ON>j4Cc?<1#%?Ax!h?b;Yn-pz!*d)(gm#eBHa{RVE zcQRkGT7AmguC}!PMS=vP-kn<<(LpP%__v-Sk9-$y z(1B>9RSyTuR*I>^QoGI@Y0!Z_84(44ZdShL31Iaq4%0AJ7+uVbB$cc++FaiKS8DBm zF&btHxe(3QqWK1E14GxPuFjciMg)3`QIMqmYx$YYK_$=dlCo9X} zydLxC<6!26Htf*mM(jSHyS@kIh#2DU&ff9r@w)YmM|Z)# zc3PE=wUtFLB^6r`5w+EwmB`_%oT%`aBdRqB*X|#UVzo+CP?(1cTgYX-Ty;rCv=LFe zNvPs#<0w~g8)NVTE!=muJIl-cIDaM+_oMkYZ&l4ZS=n}`gaLtEt26gvOS1VYj|<%6 zRt>&AM$JDuA1mKskb*6UIMBKed&I4EYjBk#)=&4=zWp7;rmU{4&55heI`Ec*trBGP z>AkBLJI+0S<8qiI$~Nk+jeO~&jJ+Oj#uh{vJzuhFr8#P%hcZ2Ru=XThE7p?BYOy>? zMtvwrl8P^MHe6xcXKf0W;VZFR`x?Z{Ltks?7;`@9%v+@k;pJ?rt zT+0=??v(KpTuYAU{0{^nhaBoIxW>4?m-9LW3EFQzfAy4(f12JLqhT+)CK^3+xyf|heowd)^U z2Xdt}(GeBSKllTJbi7;IFzHwxcOk1^`BU~L^-e1?OYOO5c7|D(sfv>1giln5z$t}hv4F_h`X6dp)SVi0;Cug#W0k<)(YCh`=gA zw9zW8E38CBTM?fo+PEMB`v;<}2%_vey9nD0H@Ycf<^Q=y5dv!o(f^IWibJ#!F>7pY zb;OQprjFeMwK~Ili51JvlgH$?o%;$4`=7ihH=5Bzr+;kYJu0_XnzG1#oNRNspEe`f zS0FY&*&!p^h;TnIYf;l@q+Cd^u3^j93C=?9=GQmm%;lZM3NYDpgX`El)>AuKDJ8jE zlbRZ~pgxo&Nqvh&sXM0HvjfE!vXRYt3afUTB!+&Vg_4whVz}Dr?c3Bm8&)fbm}t^R z3I8*h4QNSjz45_zPQ{AtS=6}fC~`G~RI z>3&8;!?pg}oF<1;7wj%+Ktw!n60w@~_X8QxlCtT}AIOM6 z-I7%BT#E!gmZ$;i0^Bb8xd_`GXFrfXj&KoibMJLi?$a^9_&zx74$nt)=?elumDq5u z-cmi_s(}m9l2oO~Ky`exO{R6ye)G*uqu8t6m6bB%-^rDpk7Plc>=b#(JNaY#VAdpi zCB>oOGp=LCOwC;CNPl%rwY=tvqa&Cytdg?V{kZlynTx*e5NQ?WNz&`d3VcC)@EB6;YGw49wl5}Tv4lT=aFYW5)BW6S( z7y8H7B~|OHCp+fS?i7BfpmszX5sn+8v=%*v#^37@Xu{|c?XkD4QiDgj7taULdOqAa zBCy9$r{b*wP1u52LrIcUqkSM7)S^io>2i$JXZ^>lSLw7=+X zM3AKWk<}EE#4F=BqV8`5J>3x^qdxkcsz;KN19ctF9D$Y~!l;8=qmor2To;XMq@Cth z9N{k4)92k6haYeq+!}$X(J_!=3(Jk)%~Tb7U2dt^q-4dMeI{mZUZ90!{TRtcxQZ*atC#h?bV_NkJa9m?w{Jb$zJp**auqxe2?44r@6^ev?ZKb_{; zr;)!}bXqgPHPj(Dn|`&A;L30NPVTv;kNBQFf6EbtN6rrb__J-u?=>nsz(HJRZJhr)^x9|93DhE*7I1sm=_yQ(Z!a$QK9Vks>(|K zXYYhQi*89e$*mf+-$v-b9H2f#OH!Fmfu`LZYdY8AIuLaz(Q9f>V2xLEZ>Uo~N z>xIZU^*hQxeNS`@|K8fq{dqsf3}!@IDu(aFwF_h`zgLZ?F%h{??&7i$qOK-+s?VrQ2?w&dIHgjyL8Mcv1+dYdXM*+YzIz9Y=7 z%JSp26Y20S)l=lWOTDKC9f;<8WZdIX$(x-C(Q8UD8+)>nlBL))8PP_>sO*V!^MGv|HM!&j=5ard z_T!_g&@piJ4H?l!#PH^Ww8>p6nWj83D>jk61mek>dveMYy~a+Lyf5dx*h%Q#nYy3n zV@0foR&erp*1dTRm2GYz5O!}8WkeehIepidCYIZ7TI>_4V$17<`aDJq zD|`))AI{h8h#widgwS&dlO&w-NO4LOI#$7Wy0vYppM za8;`<84xJRY86ot2f7Kw-EyC0ME@Cae&{%Z4n*TzV%2d!aJVbhE^;B-iXaNdT|{8t zG$N1-_5B&)xOBG5${~DnlaEUa-9O6XkLs15IQxU#wVsFgzUETeZ`VK3TAS!;N$&0q zMN6jvnb|NC6Lfq^CWdG$;-YrN6%ojVx~&MJFt?a<$DTeyUvi%uVl_>?(OQo?gIy7U zT&SD4>7&;!a-ko8Mx1!v(iLsTdi`^(vhMnkgj`tde@2jP*z)LuoA5R?`jlL4r7Gx- zN00o@hoygHJ+F_i3tacfafv~Kt8a&s@-P>@-}rsA?A%#A#}-74-lO+|u=vxE^QQCr zyPhkruUH4Sx*;PMqRD#tL~A$fmnI-Wx~s1&W_7(S&poWuS7v0~Nxc)PkL?e0-5hzKw$>KT23ZrnZNplgmQiXPb=Y+);MA)uvA`nvo;ns`T7sZw;0bYV@SL=N; zN-|o7T!{X6&Mkf*0=ckatU5-dhr3|)As5!0B=zaKkgxx`%70G|*3K1aENs7(b*EhC zqmP(zCU4s*cmCF0(4oC)R@0VmQ?{q6sa<~#H6W17ai=~Wzb<@`Bkb=DQfKFQ>shj@ z$xKsmlG+Vwti2u5+Vh`!Wwp)8&O*nkoHq@A z%$V&g{Co3}_Q>w+tFPHz=$=~Pi=Dv_4j(_rk|})rKmuLg)7!B+!T#F06Pi7WZqfLds6fLw^S zB8ttK;TpwP0ED>0R{+R`x~&MJXwD!+0-yVq^I4SWdB0~-qRBra0-p^~AI;i?pl4Al zqL+77S8Ty2J(|x6K~G3Jg7T5YoHq$uP#;RN>L3a&L2v&XK{F(2@A!KKKr}^xW>lgL zv$LoY%m;E|Zmd>aYB?(j5vUK*R)kwxjzr|bd|;leh^Dh*5|Ill5i3+jSgJjY&yeKd zWIjXE+(&dzKGzQ5b1l)0ajsR@KQz1klcqldOyjdNjuL-HRJ#;s7#WZY(N;f*LLG=e z3ylaIcaaPI(-Gvki`{w`L?9Q?-1FIuS2?EF&4*@f#^ z{8Ha38kq1<#L7}ji01b)cs^pkHcTW0%0e{eMw0IGouc>StBL(9tSel-4vL9jh4_Br z?QQf_f-h7htF&Qu;bQ;FZZdCysx%@h{@&B4y(L7HTs($(^Zlzl4o0*j)#HfS ze)%Z68p=h4v3~?`Ki1?PLpj$*KMiKn`2JO%BR36w5Ydu!hU<9HxVZ2fWo1Oub0R$f zNYaTGfoyx^4`&aqQPAvj=v?}OBl`OPPbD$3y_Y!Z9+K7bWrAJKvnOCJmn|v5RtQ zXbGZiZ6lap)5=Pw%haQy>t)s4JJrxq%V$+l7NU)a`}=3I68?R(mE*3N(RM@|5o7W! zH$^H@THV#-QwHT6&MH)^s1(TlPHuHBf@OPKL3vZ}y*#hGPHX3Audg;oM03Q*l<_Ip zvVG|=fj(EqhM^=$3Y^tj+gCT;T(7yeDeUz?w(N2xrB38q8MzQGN!>YO5l5U1@HSzK zX{?U!_EKUfNs_X>YN@qfUqJnmUfVQs=?M0{p@UMl&N~^o5UnHna76u!wN2QPR6|GK z^RZzli9a>wTh2n2DD_p?c+ZaAqu8C?4oaax?`7mdG{2#qe>oe?5v^{H_r#Xv?;`~| z?V$}rNs`olR&O=6Zn_fS@69%_aV)5NCFSkM_cC%Jnx7SM!~%{e+tQn1%h7B)+N(+? zgCt2h{<5XIdwl`z`t8~b^Njis&G%k8B8($?UaQTp1@n)R_*oI(3;!@9P4siL{ja5A zEPHTe<#cvq+<0BJ4rG%jWJ`48{Tw5Th{7JDSiOkKO896xmAT7LMzb#ON@qm|1ae{i z_5Jos-^Rq#emk}x;y`#XiwUcwq>0ldAHG8$p0BGDjaOK&h&CeL@$sr9^Kho|3K7Wl z_OH?G#u7WF^DOe?10O{*54|r&QH&y@jfnjmvA&vzIL%nxJe;-pV5eLv_1@5Hjfkdv zR+~QUHJuM?r~}cMe|}!e5n)c<66vG?xiB9_L}KSa_G*)ZIL*MEBNw72sV$$+SB%}B zz;mviyEKNa*j!mjm}_IGW9&DQln+jkvE@Xok?ebi%1V4s8-|i3X)IrtL?62!PwNsy zV4p`czmdXMOIPnVb)hvJauqKU%<=_PQa-e_VMatKKT%A3eL8{8IdQx~1WMw!Sh(1|d{HW?uEdv7cjA*_JUsFQ8@Uekf?QDPZ%8j9HXt149jlWA$ zym&DCUX0(SQQpb>evV*8_Eu6ZwGgvfT1C}%qNnEYbdb{h&={6_jE_-sY#4GOT9Uqx zudVtobktV$aWf#0YvPhn);zJY^6UlmbH_3xHMY~&9CNO%8Fe5RS}RFi*l?|^*4-S^ zez+OA3M%2u`IVh=zr=glh7Wi zlGjR&jpyVUBfMCJIm1{;v9ogCRt*I0=uU4al-kuvy=tG^bBf7En-|+gAbMv#AdkG! zRnYR62lB-09R%Xy)5F~Jkzd!EFCU6`x0^8BfIuCnTato%)H2@)xs^Q5HC#h3)MwP; z+hLmd%j`^^mqJFV`6qh|OP0O;Y_R>nkJjRQ?;(`)+XGstN|mb~;c{UWZAY$%I-P_c z8kfZ17+D{sMop@iGQL||6KY4a5%Kp-N2T4@aw)xYgsa$sI*ie6?;NE~$h<%K$&*zK zV}e}hA3fL6NB`ZADh1lHMLdH~oPNp$qq+z>>c|VZqqqLOZ5z7#p?`ElKcCiutL3DF z^7X%)3wnN!6LOSyTS0F-aV`TQJ#!<`QsBWE17dNoulPQC0__N+4s~=x(L&l&>MMdi zJNJn^Y?J;yS^M7zFy`zHeeJwz^yh*5{_GcO@)=-G1yt48##C%$j?mG1TF zpJ=sz!K{1Zs&*AEpBCMccQ@@Q=qmTp4UyLQEqhCIp6Xn+Q_mO>D9NfL^T6_ZQ9DK& zt+gV|EhF5J3v=*i1Yt4Hn14iDbr6NsfIcDmzY!QKL>m#vh1tY9HX<<37CPrh8}{Eh zw{TJY{Hd-8ZPbDFigk>6`X53g>QQnNF=qJnKOk?94-~W$?<>2{`U`p=?_EZOAMc$s z)+)Sz*zjIU^jh9)OY+`KbZ%$pAKJBdOI$ua=_p#llg}7*u;@18dz*uYKu2DGDKYnG zAJLM=`!ibjZ>xCi3O}y*t0xftyuw4=RY8+g_hu-9F2Z|(?gt_6Bv(l4&ik{)-deoR zTYO@?*AjjDf4$a%K+n>YxEG(|#%E%hx6n;_vLc8=1ae`Xj0kK&1ZLBSKzotv-&JDCIU>;W|Be;5V01CF zMyoKlf6BQn_Cb*kL|ACz!u;zxEPh}$V5G5n__@4ogqHV6Y%&{H(%g2lzLFWT;;ZZ) ztgl|C9JwfmWYhcL-m^4wrgU~SH;gfRth*JaAp*Ia^EVbbpT{Nfy`{Fl*rD_z$+M(L zwN-=qV*L@s<*rQ9*HrnMot0lo?Zx-cn$j<3afE5-(<2^)z!pTHg~AW@+M!qvnfpvU{3c*$SH*UrIe9(z9Cct65G{0QS@+LQ zF3EKu7y4xMW7Aka=AC)TC8Q+>^%hFcKCDB=G z{~g2C@8hnzP5rq>IUlXBESA0DCzZ<-!4>o6raacOo}kC}JIWDGy9TRLk2Cx1i|$jf z<=jDi*1!4nh>VgX>0A0V<$j(CZX^1PQjrVMXrUw(^NUhyK7Qf8{Ml#~xzKha!uD!& zZOE-!?rrlIF?f!M%p1E2KN_pBF41zXo#i^~S~Jn&&@WZ)wbe(^=_L-xZ$~v0^zoj1 zx##*vzbAt&h&WVG7KmCC@U{pcu>}$9i+Kse)V=U)Z`$16QWCaoo#-LB&P=;0qom(P z@%ts2`_6Yo1ZEJ?Rz&?yFOu$U?IGmeh)I)&%<3ZOs?W~L_Q~x8-QfqUMa5WxEf}{G zn>qm*%x&DdP=5O5QiaHSeX9OWpE=GE3g;qjG3(4|ZdY17DTTm`a(rvOJ(5n1{ zdJ4JqFWoUj!HP&L-OUxbp10{L5EFW5M0n5>eP$0Q+5<@MpOf7R_fneox*}iAQ<*iH zRbQFf>$-f0e@`@h&u@!x1Zg6~WzJQT|Gwln&PDXnBZ-3E?NeLOcSqAn!xp{=P~^&H zx|1ppic7rULLG#l?{$O=*Kz+vJ7E=ap@o}yjghryd5uZZGXCBNS;hC^RMd`gd-Zc+ z^lO-rr3o>a@0X;FTQ01^>O(GLB|hf6IF~90JM!H@gAPPsMCdpA0!??~mIws3EauN@ zk-uZr>S2nA0-;-STDNM^B;AjETnEY}3+YL3EFa;Fh*CVdm7nR+&B$f(7X9P9QQWG+ zkGDHg22mEG(OOB`#Xa}BwodH(U_LND7-@dy)g{oBT4<#s?UA7$$c1P=;&2^qw=M}C z*n;|uIj4ME)`=_Y%Ay(;B%G3w3oAzFryg}_^$J&PS$a*c`~x|T$|#Bdf*H3eEjn7n zDq@q&y!e?{{!XW4L=a8iALM9B`pgl{uMYSZg3wg2`7)q&t1M6SD2ps4xh;6VTh09= zn*1{&$XjYT$NK?tAzG5oajSj~h!fGJ+-_fKt4#Y{iS!G0GdWF?h`uO#)Qb%L+=4*4 zMAP?VA)lSOj#0bU#L?a>T7?MIElD!hv8i;tunM&!+KA}Db!1KID587Xc?$c-rn(Y3 z{h{2gNsO>$Nbg5-7fye#?x+mrH2*D5j>vLujnJ|B=4jC}>dQTuXzEe@IgMkbB)#B> zdi#%w(T8+UbV&zs5#5lFyM!jsM{~3!9pMN+yI}D?4kC~XEtI7D9I>MIQsD=V&S(jJ zPZoyqQCpJUa74G*Wx@|^K?M55@7!@jju%bD2#2vEE{YFDfzT8~@=205azwkd(?SQf zWJJ)4jAkGHdl@`~5#w_IE4rx9n2#8)gDRM+1i3J7##qhdh)w5biCB>(RHLE4Gib>H zSxevh3ajWXp$d1l3eT~H(1@^PliyDG@iURel7mH$CE%Dy)n^&0tJynddGK|!8w(?*|blenf9m%!K24ip9v*|p~xdz0_Q_DH9m3%gs zQ*Ij9!AEExoV|5>FHg;heHTdJK_PDI=Bm6H*Xlx{Ct4i$@)X>~?i z;e4gnhp#e;KF?Q~R>Z;B=}B=*LPX2)t}En9d=*Aq{(KeoZykKxRUgXtU9bhMLP=H~ zM4?>dn#b3{q^}HL2U`&x-r6RiA80$Gtq7t}7IGn)&rz4x@!#lGmb=9fi+a1&R9gwi>p)73iI%RLkSz^So^xBZmA)*H#4xht4 zr=CPU@L8H+M2WT_P?G*;m{+m$aTWQw?f9j72A|bkX&4iY2$D~pKPy($1?6Jje$#e_ z&^I&d{NMSYoZBYWNW>P4?FYH-D2e~d4fo@#eJ*Eb?gz@n(V%X-8EhLLcfH=l{`S1Q z?=B3(BadEqPzIXPJ!sN*vAQ5P#;RN z=A-TJd|2d?4$Ii}@@EM1=i^m{ZnGhShdBaUP#;>TXMDRom7>==(e? z?RP%NbHZXvukIZL*O%C2d4?1!==nBe6@5s@gC|J|dF>oTOZbwhGW+B&=)?~3a+PoO z1Z`gi`k>H(2$YLxU5CXgMARuH3%TB7Pm3oDiW{v_tcYihm0gev(f@4~B5=h)ee>Ts zNE^lnZAYJUt0-1PVGHI4qb{mMn|W@2+!{W%qjsXHVrX?{YwI8?vA`S4Y~ay!o?``$ zz!vlzCFxdCbe$XqI-^`%w@n zHRW@agVRzq&&AvYqu+E=Z$EmTh%H%vTbQ}b6j4_eeR^Gy_cM3~Q7+N6&pU6k9x!9nas?D{-KMoCsbCT2ho+Ope%Xh~|l>8n^}tX|mA1-bCa`_yDN zp|7nk#`cY1?8e7t5x)rhjMYXjB8&VF_l|1jQfEts1GGcQl2%t5-g+W zwt@Q7-Se84WPDDjzn};E&YxIfQ|P4HXYv&%LQMGLoP;fiz$Y28_R;qAs+Lfl-{Qe% z4%A09_4yZEw~nB?dcsE^M4%2t6EA(D)%jnXUCAnvHJ{r{mRO!SP?FBi{ZM27ZtIK) z?3-p})^>)SRE`+GUcB+0l-VUyKMtTL{K(eC-7hkj~@h|G?*XG;AG zVcD5Lv?Rr??V={_TAZp(|E}Qv1?p>`N8jtsK7e-BT($+Pwc_@B*e_q8^sDK?()n2H z8+=n(Wzk_ogw+YtCX6X2mub{cNvWjA>Z$KJ*>7bhVSBgf$#Ui+dffg>qi4>Y6S`^Y zkeQC}zkgJww&*N8-@3^pBbsP>u6@EK@#s2*X{)pOd7Sdsby!+*bGcMYrMcY2PxM{Y zOlL_)y(@#Y<(Gb>jA^)6!Iq5rERy(d@7Q+NZgmgZclXkJ1#L&G5Y5NLLqjy_`y+R| zA#nQ^7SAav_={%5G;> z3wD!z@<(aU`BQak{=~cEuc>mwTlQ=!f1>jm7%P_@>c(z9NKx+Hoz6X9J~@I7Z=}lU z5&X9L>JS#oxo*r}A$!||vi4r9m7(uu8PNRKVZx52%Gqo^kGzP|hLm++$$a(VwrjGC zv$Lt10}JGHqWv%$+lQtFv#Wz%C#Ot{((oyzhBSiJdhDPio|!FoUNL~h?y^^2zMjPq zp7$HFXR8)?42g@p4Cf`B8Tjt`yDLhkQpHV|?fYtu>2=sh zw|FH_>uH7=`LBU)>_K|6Qo3*qw`%t8gRIiP8}bP)QbSqDg}NnaN2}WG+|!#LRSp@W zixFK{Wh@)sypmE(p38MSf7FSsUtHE>#VTV4@p*7f(`Z(qzrFIP5+OP-@51&DXq;Sj zCBGF9&z6`?qmJXXdb8sdFSrj{WJDkr>f>)YC3~^Z%5yxABt~i2f(WBkn+~^RZI?`T zufEyn2XftW2xFb%9F*+~sIKNdY``|`sp8J!qcm*6+BMeIjr?Po*2^O$g!d?H!3xJ3 zlcY9vhO>&F26#S=G1e|tCB}{4pmXZO=3KV-^jjFEVV^)QL`zcX;x?(KA`Mb~zD8+S z88{kXUy-D7n-;Rqt=h|teWEnv!m-4N=;gnT#ZOF6O(|mZ13fqPs5iMK_V{s0&y#nI z2<$~h9h<-AR{A%wO}?-w!r%uYu;1`rtK?@Dn?LeMyK3|t={;E5iCAPibq0TT` zh0#s<6~a33XJ;FQMh3SgPg(6kWA_zlAE}`%T!kC0`thL>t9_wX%KH;h8a`)YWf*mI z=c~OwS)Yg-*tjaf8F^0dC^qG*gL1h4d2ZEizM}N$e_iaiBiFqygIG+cgOY7@nruXD zy#5IT_KC z^o&0TK6b6jC#;hgwniVMJ`=Pr#W5w2!AZ z4iPbr$0vS&1?3Qr52E=$xNt=1wsTH|!1Z9NXEf`-sFKos^ac6XkVv+spq=u@>jIB% zA)b%ecQ!7xONcrUjrt_%AxB8%OVhgmD#}7GMDyR%=lOU%qk_mF<{YguBBt?JZSdJD zPD~Kd!Y+!H7;djzZgoLMH2-HYZq=@UlHw*gRs$kX62F)6x~7^t+EpD~ET58aY$V$? ztAf%a#~k^|Uwv7o>y?z*CuhkemA))j13P8#OIjz^nEO}>pBto}UOdlze63(M?qCJw zc8&8gqK$~Ksom5rFW;DtJ03CZOd7%R%&(%PmOF2di~9JR7R~CY8%DWmzxr=v*wT|* z7+$Y%A3zd6yW0??#l_rHR@UEVT46Jmb*W*mT&q7v>F$*Cqm8m@S>LwT9AnDKh(NBmXCv98oK=)vw3w-6X8bz{*Ovl#DHbF_F@alMM+i!QRoN8XHb-W->X7P z_)jEJSJglC760@#w#^QCY-{~L4&(T5Z28~S{}uD}Ikw6FbRYt` zj5^k?9{xWBwxCs^vD1WAo7&T}n*NE_W=;K;5Wl#wOn%f3{v>yc%$GuR@wE5yuCmny z9bV@ZN8IqsB=-6Ux!?b8vJdCVHe{>(eR4yA_I_yTM*HDUNeFI z-p6t)jAGUJ#&~CJK?{vmk!(voum$y@B%R-a*w&2+?N98#89YaQR>W1aUDE!=dl<#1 zP>)<}MX&jSuIZhNxs;3*^o=s~J6;oqFB3bd+pD#8opOIZqgZ8Ma7s=tvWHP+D8NRS>`}fwezC9dgCSbO!!5+vcPCpWw)TsDe!hCb zC;7;xmg1y(_H}ySAj!>3>wl}(z9ogLXzD)wmggn!hXyXwMEySOj2iTA_{3ljZGDZ* z9u51~(ohznQ8#}!SZ-2wm6@=&%IQH`*AQ=E)z|!=WwgqOSevLf?l?@vCv&8EB)fhcRHsHA1`#E_KZ3#Xh{m=ziU9XLhlJ9g7jIqP`CbT z(}c+A2U$W0vczZ=*>9gEJpMIbTcahYZ{%w|R>ie+?g#%ZS*<~qa3_1dvyCl8Q+!Hr zE|jFls$H=d;W=^9sa`qGHJa0O233~Retq?INzaG0F5%B=tmff~^o*k+S44n*6YPok zh8)FdLOqO=~4$<-95@tLE<|==d!XI}xtm_@2Cz{$*_ZoHlCE z#x*H9D(BUZtK(%i(dWD5y(=3L$JP%~?Pq=S*pWBh?3Y!~$HZrMWJI7O{(H#7Kbs~+ zPfKZ1Hd5Oj-%-fzUMdqq3ynJB`gv#tt{(I(8eGeOXgIr<@Z+x!4`oF2e{gvbq*Z?3 zIOTMeM`q+geOGtutMe6&sh{&(Va%;#OdR!-o&5g|s7mhe(bC(j-{i>K^0A=l`vRQi z{exFYLJsi@;{rje?d!i0GIbZR0g~&Os^ob@!0lw-d-4;pQDz4+^ zsn!3o3c1ii{Ws!+QXK^XTXuNrw-~eR|6AV0Y3iFsRHvRPCjwh(PWpgw(M;I|D00(GG0gto+u|HIL}0os7x9X+>yJgV4K)&FDrUi&R_ zYf1ly=8gH!%kL8O^>v-&aomq(rEe>Cxhr|T+}K-1#HS`B#0ptywpG5;KHNkZOnscp z5j*CGnLicw_3*SGqoG{$JpKQ@mCzgV{uerW%X~VI+WWSNxoL;}9-p6wYJIco|9@QM z^JRloM#NzjrEPvwEM-{uauXuZcGN9N*}67UgPXKVZdAIMHtk}#uzfba1BY_aLVm_l zZ-6=?{+h>&J15MDKrW-_6?->QCl+{;JT#`9it$0T5fOKJruj#B!IV#zM;fAwexM{t zTJp3Yj~E|?ene?$%chICPuwt5E|O`hiB^CvQ)UR7@@j+~&=);ER(2h}T_8GsoyQR|_Zn&UOnp5ryeq4o z-LO?~eTp?AP?99IT2fRip1*-yJgJ$6vQWot?i2aZZ7BIsK6^gx_UiEUVkn3M-vpl9sOcQdx5H#r~`u|2) zxJVMwB#EC?Uu&+7o&HfSezUN;-=~IXX_@PV9NpGM==;0k3weM1L*e=AVV^i+W)){G z(}U6`&t*<3a;Rko|SwmLwd@!em&4sM@j{D@p4RpDW`EL^uO+FE= z+y7q(3l~Wunk4am)jiZiow8$sXGNdV+KcnLj@`BQ$=fQn5M0G-?vp2U^%lDQs_oP&0v9s}bTMe$jO>vHRDdjvhWSx!bY zSv7>ydgjQF1AjnRxJVMwB#Hmy?MPL<@h~cN@53tEf{FUGbG>Kh3U1EYbWH&ZT0<&z?chir%kZ}G33q# zuH)+a;#&3&-%^L&4KN^re_OIrI%PoX_WzEq>55sGyZ6Nf`S{Oy!uG%t*%;Ae7194U z!oo$8h$cyVT{5AbmQ8t>I=WG1b;|>N=f>w@E@n4hm%E^DHa6wjZ+)dn$BgaOwdkC? zoAR>BAL^>jXXq^(uIFW0is-epDk>*Cdr+_A!huw~>)#hw8~6N{ zI{$8f0TKV(lJJH`w0>VSBHx`odAW5X?}f0YT>D&8tl$+G*NxC2B7Zi8O&7*tZJ>PMDJ6iF`JXd&Yd19&a zDukWlZ%0hJI+y!FBLdkqoBM%?AKa2mH5`@t@p`N*Xx;Op`J&_8I09{FM?+XZsgug| z(~IOk>sZXKB827X2N5Vq_k*mWJHpSSLfB0H)Y!D~S~(-aB8i_=kKQKUL?YDr1N!?o zKN>HRai@UxH7q*_#7CcK?ewfNNoW;5tIdhj-}1OnbS;k+eJCGcYs>9B#!uf!don+L zqf;QFz4?jKKl~(4eE+YLIBY@0K7Ou72mV%3MJ`0^b1iYxt`ud8b~9;*uFiFPHu>`f zrF?3v*vqnJkZufQS~0=tCx5a(Z?b1&c})7GEi!N+TGX!ks6dPO<9v1=`OBWQ<~q7% zpY<;t7Tx^K=^ZZ|& z5rJH|8)@}ChI@|tpQG03I=E0qeWJD2ld>fs7otmhwG=w;E}O)4(5jU%ZMapqLyKI9*8Rv4wIg9EM`Yx(?C%b2 z&{FL6t{Xu*^iQ;Uz&D$Su4UgCxlp$iacs>5XXGMpE$HOLd4kR{jbcT9+-X-mp1)7e zP9B;k+wxuDJ+mjt$c1RVu1FL8^AxraZP{Z-N&K!s?!C@Dx*}e1G!byqb$4G*MHix=6t6)PuW@Wtl#<$w5HpJ zW>&xh$)YFv-s`JlBL?adOrIGLHhisb|BZpd-c%l^wnLJ_EL(RYY4P>0VgID>_l6mTde)(fdh=pu>G*RuP3?(zU!E1Ew{^^ zr1ke2Flx!+k(pu6|LwV@f6#pxLiq4oK@<6%BBIBbQVkYbts)97K?^Ioz82_A(`aX# zJ{BFH-I=iJR`6$;?qZORI{bD@*`My>`$^sKrcYmcXXb4JfGK4~GDg&!reMu8uTa$bl-S*YW` z{jkZK$4nmneW9DUeR6eu)sPS5!rWL9VcGB0#U5p!U0=gJ zyfeelyR3+n=c*+l0;7OvD}pFQU|&JB6_LZPnhW;SkMH}6-1r3U_>b{w%exOwh`^B= z(N-M;p6zr*E<|IESrJ5G#o@e!b!5BakZ@5WEtUb<&94eh&CednFG=2pAmuH zA{U}{gk=SQ(Z%>IuhL1xZS_a`HFo_It!;Z#Bnev(@#nho$eiekT)4*lGlFzYs=m)O zbjs^4F$&#rMvMgZZpRXQ;VuI>dYMUFUTFy{5*TD{uH9S@POv zs+8}Lk|1mH%xe2g6Z!Wg?e=j5-JF}4*=rB&QzI9m%lPg!g%zEk9Pt|P8$lM$)Ixy)N%4)oC0MW`t2B)2e}TR1LOlY6J{F?r_OraTF!U#FaZevi5561&v# z=|c=wA=-%OdhdsMt<4ipb3hk$?UQ)ZjE--WwLcFV{6PQs8`53@=0{a)$yH8)G##oQZ+6<$=3zP2^YvS~b<7RZ!mMT0eAh3^dB&ue z_V=rx9to#sgU43_&3PL)b?X%nYS4jlU#Gq{k?u(gX@xx6v$=Vi+XR-)HdGCE%5JX9 zvliyp%i#Il-dWAfhGbJ$t!u&&CGMx0YtDIXI(E8`y6)&RQ?^~UYDn59gH`bzADB`H z|E0d{MfVvt=khbZipXn9KNzY$p7YC8r&}TQ+PP+i_+Z@lP2!k_=1!er%}>7%QPJDO zyXTr*(@U$lH-63F`T7}t<_XbHl5;!^HPqGf?_Es+G;%iiCNE=?O%rofRpz~*f0vgx z1eiOw{;==(@lX|Gg0V6pKGgO%4|AHuD!PTLSmE6&_Aw2;n_ZnZBwaSfs#Z@wvsY3h zc3?rMS}lv4>20sP>cQeqWvmz@;#0Jbx$RSTbMv#K)O>5dn4+VLsaqC}l7H+RV;WVc zgjzoNsa$IMTT|f~CDkR}D1+@DdzlN5pJMLzb(kSmm>Y~6e_g>Bvts-o>^ zq0y=?&wR{o56+t|XdwoxFq;8iTbur}DWbM0Lw5&H-BiqvL*|%W4i8mP`@n3|On-$| zP!9&#GGpyFThzo{@69@o=r^G%#vS`P=82DR^%|L>GnjpNDJ8vyq==96vIQKC>H}U(|F>9h1$7u#N6-YB%|gQs~<^16q>afABX4 zyQh1$P776$3&$?h$9Fj&_?qXHRB3D@_ZpR8$k&7iU;KlC*M2L$gnfK+g}{ zDzv2f-9n~wowg_|_vT_otNP~iF~^2oP03RwOhqoNF(bn6mAAQN^{Mje)?tP!K|hQ+ zAD!rG?)af_%D8J`Dvq2*x~Zx4`6!y+;4g;O@^@b+c$-_CsF+-|XPBYaBHD;(f6mi9 z|4iM~HtUR5p&#Z}S5wcPzN+jWU4+kSqg>q0IcEfR{N8H^XY=8QPjVR2G8$?6fG~ zxI0|+x|20UJ{PRK=uwd&+K8xkxTN{Hwo%TMJHjxZW1cYz{I|{mYnuQ0-oo4|Lv+zw zi~|34{Oje-6MD{dcRC)fV!uNRjaG&4&1+8FwK`?|ln8_8cP~Bm=wJDP;`h}qL;qM6 zm){)qv}{V_(GelgRQ8}^go++wRlYfvkg_rGo3c7jY2H5^M%bB^ zQE92S7ls>hj+Ka#_1WHlFm^2qbZnFw`Pz80y6 zix*K(Ib~t-uA(TKrdsFh1y$(T|ZXnat++YUZvDLRG9d)PcJB|8w?u zZrajrm#5j^m=Dx}x+SS#rZ`i4;tJME<(^+&klb%lE_Kt#JPd8eDDbz0?kAYe#rv7> zT@O+BDzj5l9ZIU>OnKShJFcb&>&vMzKW&+@pSOu#W9m0(IlD19Qf<(olH7a#FQv%y zzZmK>>e%5h-qhDz%=~S8xIqWX#fV5!i*jpCt?w*MDOfAYP$fPqlH{R23Cg={RSgxx zpNi_uGiB-6C?$Vjl-g)$HWtXMFWatKYn0%VGJdyOy1?D8^ijhEam^1idLaq>?`~p^7!#4=aSQt zn$@PuwpQq{4I!d*VLl1 zjpR(9jTuCJBj(p(<+GJ*f^twuN2Yhje3pCi}1gg5fJ zrQa0EsXVu;V%6jF(F(=cDJ@Dh*b7yHqXhp~#7a|5ucsa{t@emiu^O-!VegWpi(~RI zzoD9`O>(4RESdRsylmrHRBcx{GdtXAd+NJuf2luxi*l=;_%4#yrS?ei{b1~a&yV$H zZNIrI+hUBPge18RA1~*sV&gf4XK>c-R%}D>aK*p1kqgoM4N%rz4qI2lGt)OC0&{Mx ztFf;fOh{%;`yl48N zy)5yAaiqqq8S*48&U{*~KeGlqy(>yZxu_4({MKi{N!hN^AyexE#(ZE7jFot6(_1+p zcwfrk`%!9G+mWmxAF0dtug)-{I9Bqyx;2}<*n5+$y&Iv1L`ZD;=Dg~qrdb%;ZnP>} z&L!+^=bNnF=?Hb4Rf+oen&HeWHY$h0 zqKg}=9d#HaNlD{ZuunmKJ-T@sbzrrlKE4k(FM+?SSBJgTB2|ncM%OR(WonHw<ml&Ybh#76jAZ88cE=j7| zF|)Ga{^ykKyxLz~Sj{@~{$b}^fsKh+#wvU%sN5)4nPI=->%`&dENXJAlzvf>Dso}| zjR>D3&)LJmSKS-%l_erD|A^-Ec_|0wURT5GzDu-1z^vmv>jD^vtHLnjB*2wFwv7v$f^2solP0HuPXgis-&Uxlnby zl9soh8XbDX{n9C0)%HgY_Nm4exo4x2s-N^y-e1rod7D3<4bEofRdT7GtzuiXBztu; z+H9+%Vh^`A7L zA|&(BTxOzBd$`K%nw7B(4H7C1N;DYDn2eb!Lv<;0k@P(0Qkf-+ONw$`vm_ZJyz4yO z-}_tJ`}WuKX|L~I<6dX)ea>E68C__?+g&oE*v}%OQ;Vsr#Z1%eEj`0{wJMWtQ+cuP zQ`!qYzvGrgkJ zMAXim!J1Yl6SL|iysKU&O|sp?R_hs2j200C#yPVk5e4Mi?_mOu7je62;nou7Qfo-X zC~4GUJd5wthd!MVCd3t{!e}@#a%nQFPTG0?77r6*7mpRuR!zT6Wp1x;!fCuPK@Z$7 z)(PH#r;K3yUOsJ`Cq^QU-BOci>Sk2S=HAi+e^f7YVO{!tp)Wl`IgVEx;UZ$!lQyiN zs+8_cSSmc#FdD}(oLJxO&9WxW=J#jbWsU(Wl%0MzyLu|0HZ|qTqMCtJ zo%5QqknK}>OTz}j3>l;GY#Gkcr_W-%M;*PD8zM-BB@xF*vQsomnN~*qrUna7PK>}~ z1@t3QB$p3{0@6k`My0W;-4L~aY-Z?C$ml3`8 z&q9tR$wNBSiSF9#&oLE_5)pBIX+FF0a0<1#IbT40DoCS= zAr-79T7zOV?3b{U?38&Lo!Z}z<5>_d)LF8uu!RB-j1a9mQz@|~`ZHNrwioX*)}BuN+?)sb-zL~MB4TjaSLXT@ z>NH9^97lLvMFZkBqXT!VdPB-ml%15p<7MSB5cD_a6lF13hvY@(m5G z=(QVDgh<4Q6Astt(cELKO7k<=ik7}*UDo%Yn*MV*ZoyG0^7!+BKGz72r9-Tpg-FC` z96eA+I7N#;jn`(c+^29H8JOx!UJ4D`Ud;k5<$K~bK5Weo*VwURHNyo2riwqXjqY&M zAX;p5(03YnqPv1Fp%upPfLx|HA; zQz+)WE?_=ze)sfabB-epM}`CR?s)qyvHpRxa;#@3iV zyyCgZx$4vbe5839wf|=l+wg~oz&$~fXc_bHw(ZH|Tf+nd_PH2WhZpzb4Q&sT){(Xx zQ(=A=UzE@TxlwF~>1(j=Pn{n8Tq6r=k;;9yWX<6b} z0fD0gqhUAdNndUkvyvvywdJ}?3TWTojx*PYf1uvZf8!PNRw(j5+3;qc_t9(LY&mhg zM8~CEV9x?X1nvpm8$55vuNCg2s~(ONq8+2(JU>UnKK{k#T$8{3s9oKXuh_PWwoDq! zaSM)JEFsK&F7)I>Uud#f<^u!-j$Mp~@$tlnduoNlXBI`Vq+iqL<-cEL2?vNUYB5#G;vb}$Uu!-s{w5&2 zPV4gBS1z&-Wt?Lw{KOIU$UfGF$2V@o*J-rlI2&Mu$Rn!o6LajQ$qlP)InEh48(_3T z(Y@dZJF(N9Cu~S!cqWWz$T+XSdxMC%{LQ&;OxgIV>Is~p>iGE?d(!O%*&P{2uNG?Z zqfbte6YmewlW8BBehYOiJ$)};TVu_xb}Ce1DvX}CKAUcIxx?~vWa|#SG@m=Rw`5UM zGX)+Uv{cln{~e}Z{fvl+hEo^vLwfgUD$P>i7K}KRf174mC9w8Me*zEf3qibOPZ6~b z+Mp`EP)rXe?_-mDJSUh6qhXCx7sSVUjiz&4wy1ozmCzY|SF$~?UI_@?6TDs0^x|;= zwd9h0x$1^P3Dy5ToGpEoFCcJFQ01npKUaoG#P9J5fyWv}8CBe#!kjm~A-E@nV)!Ol zMGWfT5Grj}VJgc>Wz=wfJGS=nuZVk{=JTO{_R47zbWM;7BTD@4(StA>@Vf(FQz~q_ zFXGv@5jp2#(p38EO6b+}?KJG~R|HdGH0-KHw&cSvr!&QMDy=dprMmj7sc-yk0fBph zbJWd4`0#nJ&TD9{VLLoZXeZ$A>F}Chw1~JnWg)MAMc9TPDMDOb%!;SyY&Ce{gS)>( z;_brUc*y$2Ea^-KsbY=?ozb`{KNPf!yfIis`*+sm15ExD;uvO@17~r+)-^0HD_)7I zFuHHBEnTw5kh`6ezZcao8_Sou)-i)y2UVCVHLO3Kp4WnZUY$rpMDHHfyzin8e5KJ7 z6{h;M`!4yks12WR@60a<^ZosK*CoAph>=32dXhm5v)Xcv9VG%4Mk^FeUVml#COYwe zTYstA%-ZUpsnwC&wWuZ-Eh4IPT5xT<5&T-WAQf&2{r$GXRrd}&u=QPndr~MCEG=c* zzkBg*4Gt0CKab?(w=?DsmerB3$1-vZs4>47)`*G-zpJ^d{N`ld{p0p9~EwiIJiLR|Jal_F*Kmkyxz((T~prXro5uBU7N(>ZUk_f!AyxI!Dtb| zD?Et*=5mMTUm~T1vs=kvsKu$dIGXsvX=(YCu??J-&hc(clE%~2bPA)J<#&+{Jg+(>HwJ^RWA$!A}?v`8X;PrEb!q06MKh;?*}}xU8JEz=Rui z`9^BP&MCDvneysmjc8LJL*xkN;~QHC>9-v$n!G(#nvW$-xnj!{vUQ^(j@&2->#;of>y8N1bCtJ7i$ zXHJY35gNNTvUuV|J1>t=St!RUCnfWTDvxdLBu zBn9%*O`=(piHVRI@Ce3P0(LoLH!!Dy)uh;Xv9xf)WU76nG5>LYosbPMKd6CSxQDgq z(UXqb7bs!w7>&n2RQcDN!6L%^`5(7qR5;>r>>6Y&Q_iw8<9UPRH*xm)?`Y?cS^PwP zr3$xTM7y7f%1d|6_>ea8H(rx{7@K$NZU`s0$kw)!CDBLDpq~lLMX9hp!NH{NHw1{y2oJfNM40*-4aRLvF#$yF; zgW8%zpRZjpklIB`F8|h5y6&=z;7DBkY>7I9$7;*>2~YWWj;5zk2aWd;0;1)xjp`ag zmQO^qLQy$~P`A_Z=c~>^1x!TM@%<9|?)q*v32GK$elUl7mP|V@cg)^x9VvJaQ(-jZ zE5pIGs<$io`xx8|g!;uk$FTsFTiPzBDSO)}HD^Q$(T)+NPD9DW@Z%SWH8l1&av6nWr&z0K}8EdTt7HC`gu#c6(|oO}t2 zCLWI>CES7$aZpKTG*r^DE|U>AGM|v?;f40MpG8V|X3^isnwr2YBmDCEUuGGO*^Mam zOCeP^BPHC|oaC(}1p0N|5<@U=c-v?HgLJ)Od%jnBq;vu1A2XmXio1KP&@bi(UplS6 zN@`|T*&DzOd3Yvsd03YE?9znq^MzRrobwv4A{)K^29B=;9{<)t851hbeJ~o%0(@vh z{ci3hQ*Mb;VYG;N(7u4|U%$@b$SZM1hG${@hD;z%FjM=(U9KnNJWzvf)X^cmU`B@R zgKPbCcbY&JLACkA(`AIk%QVt}rkzi(ij**S%mdpHzKwdELfbCeToN2HEzjiqIB5ckoFELk|KFAkBx(}l%1BIVB@-b z0b+gfL6UxBJlXIzQo=3R3b-ejQ`aOA?Welj|GSHXXA?Mc;#nrtjoN#LEK2{$EY7(~ zmrdXg}GyYU_U|i??q?H zu-~_mFHgl>f)ThUc=OXeom4+@RZ`NS*Dejgx4H+^@8mNGvvf% zGN%8U^G&P8*u~K3TAZy|oAx{DEg-*f$Er&V){EW3%ZFyI(95G6VLr7*|8Ct)m^M zzhn*ixeJ*Ak8N{}G^NjcGp?m*0qc+X-WCqmv<=Q5g!AG5=KY=Xx;+(2ADiEP<@WnjoxxXTn}1B?)TZrbXwL(|EIZ~Qt+fa22&WvVF^CH-T*a|SGe%UT(TrUshNVugEQ(^SmtJqP|X1VI$8O3`@hiUb{+sv0MVEzZe z&3>N6R2Yr<)ziyTb!?t60853@BI4G|5wiThBCsJN&j0>PPWN^`o;WY zY32XRHvF&Vvny=->r~daIGg}mAs#*R->MPW)pC@~JrJnok+k>g8QgCGoZFWBo$n@* z|DQ)AkD{}f3hVU$BV_pm1dp$g7v`q)gxqo^c%h>3%6ixMSpB~`(Nwg z7L33af%mnZUef6q1bdR<+ueSE(X;{zDbH)h1R^-g~y+4t32?JF2^kxF}3SuHNQv4vVKG&!P3H0ZTtz={9=60IQT>w^T1RX4X5a~#jt%t*OJr67fYBsM&O>{ zZHE3n8U^PW{4-WM95o7{v!_g>%)44_23Vn`Te&Oqyx##_@a{DO5B1Gq3@T|gPSdwVvtXOq6HKNOBnTKnvmy~Ezrt%&=NQql8;`@~d*d4KEo9kpfRsrI3pE4C2FCsA2zJ-x$ z#7JM6hn@aDCD=;x%~*LJw_rqT%|L1&Y|Zw&$vnFJi+GhUA~4n2)Oy5xn`+?Eu5tqZ zExDN#TGE^17L4dPc>yiavSh~EG7k+vcmg8vp@_g#%5U`upGf%z$q}($yxgXYrA-<{ zaSKLZ|3mfx#BxCJF(Lv};pl-c`{6d)ZGBua<+_%b%3zi|H8Zkcr5m*9T%CEejixC} zxi8-gGzuzfI3C=TA=lX!BtZz=6Rfu3ZrO)fgKgy-Z*jjE-ObpO9^G!mCLfY{1VJs1 zN2m5>z|B+q?u66?yCjgq-JO z&C`pQ(>2Z}>>JggPqS9hPUWU7cD>FoBTBBdy!o}BEz}s{yS@k0Nm5s~V~sY&Jh1;^ zbq74gxF==Gb$D&)8am;DIdja=p*Y$xKZPO?Y}K!soBHNn9Iu$4$fG?-WwYY2`d(zr zV^i2_ns>#Dl_rY(UEdnQaKq?m0GDD7b92q#;MGwZnt#A77 zZ~B3CB|JJSQoP|*jVZIydrwAbdC)H~9`9|cg3Qnj>Z96yPE+5agfj!CQo4K5k#$xq zsz63u0YrX}W9l37aKD&e-?0JIIn|hrYbs~BX;4vh@@0M5=MrwgPX^DzNLq2mn5Bfu zc{km~h0Z^=PL6g7w_rqzE>L~{o+(?ur3MfbH1C$LFI!i_PlHo6tEhhrJOQF>NJiQk zI_k6q+wr%I&;cI3GS_7c_yvLUJVrwuVYq9{s={2p*;>NfF+Y(fS!2M!=*a`|oOQ_U)s=2;AJ|yfZ{4Bwq zg}o*4;J^7wK(y|(kRGh)!ZcUDCm0Ry&jB&&`6PLqOSlCiL_HiqssR0a{bZ?xSVGSw z95L{|7I^G4v}*1#!dE7s#t4PiT0(MY(hyE0mbzL>UxmcKG)4eI3BUDi94--;Qj zd|ndFFcn7I*h6K?*Ve4#E_v>g*HXof=DA6iOOqMy3!@Xa1=9DH#*BH%GXT8|6CSBW zczKryK`OnO%cyj}D;w6~0}*+2HJiaMWiQ|vMM(^|V8r#2{`B0YuFTwC=5hV)Z&KRo zW>TD6I=kL)4vjCgU_HXMXy0Yt)bO1N%hq{MM5#vo`B+)d!CRs`3stxUBd~r@Pv*6c zl=Nw%($V>f3R7WzJEOel-b2=G&22gR%zQpf3ae<&3-wkqEH9?QXgF6?cT&~5z>^R#zyR0iqZXP9`D(ONh}B9`IGg$ZKQxyzDx%w$~DMTpin!E5sG{ze3Rf5TgNc z`?QF_5{go#e<@IHYURU!o;jL>y@vb6{)cxgwFRm*fN%&F5m-WuhG!Fuk3#2Y^_*dh z@e1lX#DeY4%OjW{_9ndBhUegb_6_Xh`(JUt$>YN4i?62a>$zNVD>Q)mUo>MIo?nC! zvmeriUhJX?}5B5tl9&G=x!`1XqgqhU`Uq>@LiEESf0 zQc@H>bis^u49X)|LdevfE;N1qoXoC(z#0xnSWe@!Et&J-Jc2EvP^^Gwl*~i@#6e^5 zC#;t@w6tc1ZSx35!-+#z7n)b3YugKWU@FWH$1&Wb47PgGN9TdG3Q-uzf^-901LS4(XwO)?z)dBv?Y& z%RqS-dkT9H>jxg33I1r__)Jfb3ipMnFdE*(^=u-w_%T}Y;ImnK-5@$?v>DseJeTyb z4Wm^>rmRcnVxoDU{<`ImB zSsw{vZvL~l&!f8xQ(;L&#O^b?ss?(2Jhg3{3L~&i7!4x|*5@vLr^~ZGzS&?o-M-v{ zg?}g}v%;h3xgaa{ptzWfo*YhRtg~VR1B*fPt*|QE-Q7!$cHX6TeT1im7m;(n1=B6_ ztyurvMI`Qi7#+~fnhozQBX&%3QF?v6CdV$nsS2Pm`_0&Uu;SeXp)_H&8JqO3h;-}~ zK<7l8vx;G|b$`sLU(xrL5gQlLy>^zY)~<;3f8$5PVlA1iUJ*Gz!H*`ivS6LR-2uc} zkm_EwhrBA{xG#(r5p6-L4}Ww&1M3e#4~)P%!8gKyAbRU>T$376PTLT^( zH+}ILSg~+Sg*_-D*8XcD_bGhr2REDWMofgqB z$&&SRfA|Z+vez`}`aB)gUx^wLrow2fAM9lqpJquh^CYGHG=}vEi4CStx0|u3dk=|- zsIUre*P2O}aRkl@IIoh?3Wy-mvN6cb+Gq`BEl-&MS1^pM&`TZNItuKF`cs3oN1ocrR(=BrrP^0+1%s0 zwDGh+dgl)d_Qy*34DSTUB}YaCWy-na^Pn(#CfJhAEZ3zN{ZCdH{a9wsc0ZF5ZNEAz zVP~RL115&>9T)v5rfTjONULvKu+SB{ zR7Bj%b>(9`KB<;WZOoiALumIU=B%4amtuY*VpDaPly1;VwSVGuCFWsOwU~MzH)kQ= w9umwCPSMR8A{}gKCOv=p$sY5-R2U8QGHP$JdD-)%$m{KtxCKjvdr~O=2d->1RR910 literal 0 HcmV?d00001 diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_main_wheel.dae b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_main_wheel.dae new file mode 100644 index 00000000..904415fc --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_main_wheel.dae @@ -0,0 +1,151 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-05T10:10:19 + 2023-07-05T10:10:19 + + Z_UP + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.298039 0.298039 0.298039 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + 0.004999995 -0.001542866 -0.001967072 0.005002856 -0.005440711 -0.005864977 0.004999995 -0.005440711 -0.005864977 0.007854163 -0.001542866 -0.001967072 0.005002856 -0.005864977 -0.005440711 0.004999995 -0.001967072 -0.001542806 0.004999995 -0.005864977 -0.005440711 0.007854163 -0.001967072 -0.001542806 0.004999995 -0.002481937 -3.00004e-4 0.007854163 -0.002481937 -3.00004e-4 0.005002856 -0.007994353 -3.00004e-4 0.004999995 -0.007994353 -3.00004e-4 0.005002856 -0.007994353 2.99996e-4 0.004999995 -0.002481937 2.99996e-4 0.004999995 -0.007994353 2.99996e-4 0.007854163 -0.002481937 2.99996e-4 0.004999995 -0.001967072 0.001542806 0.005002856 -0.005864977 0.005440711 0.004999995 -0.005864977 0.005440711 0.007854163 -0.001967072 0.001542806 0.005002856 -0.005440711 0.005864977 0.004999995 -0.001542866 0.001967072 0.004999995 -0.005440711 0.005864977 0.007854163 -0.001542866 0.001967072 0.004999995 -3.0001e-4 0.002481877 0.005002856 -3.0001e-4 0.007994353 0.004999995 -3.0001e-4 0.007994353 0.007854163 -3.0001e-4 0.002481877 0.005002856 2.9999e-4 0.007994353 0.004999995 2.9999e-4 0.002481877 0.004999995 2.9999e-4 0.007994353 0.007854163 2.9999e-4 0.002481877 0.004999995 0.001542806 0.001967072 0.005002856 0.005440711 0.005864977 0.004999995 0.005440711 0.005864977 0.007854163 0.001542806 0.001967072 0.005002856 0.005864977 0.005440711 0.004999995 0.001967072 0.001542806 0.004999995 0.005864977 0.005440711 0.007854163 0.001967072 0.001542806 0.007854163 0.002481877 2.99996e-4 0.005002856 0.007994353 2.99996e-4 0.004999995 0.002481877 2.99996e-4 0.004999995 0.007994353 2.99996e-4 0.005002856 0.007994353 -3.00004e-4 0.004999995 0.002481877 -3.00004e-4 0.004999995 0.007994353 -3.00004e-4 0.007854163 0.002481877 -3.00004e-4 0.004999995 0.001967072 -0.001542806 0.005002856 0.005864977 -0.005440711 0.004999995 0.005864977 -0.005440711 0.007854163 0.001967072 -0.001542806 0.005002856 0.005440711 -0.005864977 0.004999995 0.001542806 -0.001967072 0.004999995 0.005440711 -0.005864977 0.007854163 0.001542806 -0.001967072 0.004999995 2.9999e-4 -0.002481877 0.005002856 2.9999e-4 -0.007994353 0.004999995 2.9999e-4 -0.007994353 0.007854163 2.9999e-4 -0.002481877 0.005002856 -3.0001e-4 -0.007994353 0.004999995 -3.0001e-4 -0.002481877 0.004999995 -3.0001e-4 -0.007994353 0.007854163 -3.0001e-4 -0.002481877 0.007999956 0 -0.002499997 0.007844746 0 -0.002499997 0.007854163 2.9999e-4 -0.002481877 0.004999995 -0.002481937 2.99996e-4 0.007854163 -0.002481937 2.99996e-4 0.007999956 -0.002423465 6.1371e-4 0.007999956 -0.002491414 2.06444e-4 0.007844746 -0.002499997 0 0.007999956 -0.002289414 0.001004219 0.004999995 -0.002386808 7.43687e-4 0.004999995 -0.002213239 0.001162469 0.007999956 -0.002092897 0.00136733 0.007854163 -0.001967072 0.001542806 0.004999995 -0.001967072 0.001542806 0.007999956 -0.001189827 0.002198636 0.004999995 -0.001542866 0.001967072 0.007999956 -0.001535534 0.001972794 0.007854163 -0.001542866 0.001967072 0.007999956 -8.11759e-4 0.002364516 0.004999995 -0.001161813 0.002213537 0.004999995 -7.43037e-4 0.002386987 0.007999956 -4.11496e-4 0.002465844 0.007854163 -3.0001e-4 0.002481877 0.004999995 -3.0001e-4 0.002481877 0.007999956 0 0.002499938 0.007844746 0 0.002499938 0.004999995 -0.002481937 -3.00004e-4 0.004999995 -0.002386987 -7.43031e-4 0.007999956 -0.002423465 -6.13718e-4 0.007854163 -0.002481937 -3.00004e-4 0.007999956 -0.002289414 -0.001004219 0.004999995 -0.002213597 -0.001161813 0.007999956 -0.00183928 0.001693189 0.007844746 -0.001767754 0.001767754 0.004999995 -0.001967072 -0.001542806 0.007999956 -0.002092897 -0.00136733 0.007854163 -0.001967072 -0.001542806 0.007844746 -0.001767754 -0.001767754 0.007999956 -0.00183928 -0.001693189 0.007999956 -0.002491414 -2.06452e-4 0.007999956 -0.001535534 -0.001972854 0.004999995 -0.001542866 -0.001967072 0.007999956 -0.001189827 -0.002198636 0.004999995 -0.001162469 -0.002213239 0.007999956 -8.11759e-4 -0.002364516 0.007854163 -0.001542866 -0.001967072 0.004999995 -7.43701e-4 -0.002386748 0.007999956 -4.11496e-4 -0.002465903 0.004999995 -3.0001e-4 -0.002481877 0.007854163 -3.0001e-4 -0.002481877 0.004999995 7.43017e-4 -0.002386987 0.007999956 4.11476e-4 -0.002465903 0.004999995 2.9999e-4 -0.002481877 0.007999956 0.001189827 -0.002198636 0.007999956 8.11739e-4 -0.002364516 0.004999995 0.001161813 -0.002213537 0.004999995 0.001542806 -0.001967072 0.007854163 0.001542806 -0.001967072 0.007999956 0.001535475 -0.001972854 0.007854163 0.001967072 -0.001542806 0.004999995 0.001967072 -0.001542806 0.007999956 0.002092897 -0.00136733 0.004999995 0.002213239 -0.001162469 0.004999995 0.002386748 -7.43695e-4 0.007999956 0.002289414 -0.001004219 0.004999995 0.002386987 7.43023e-4 0.007999956 0.002289414 0.001004219 0.007999956 0.002423465 6.1371e-4 0.004999995 0.002481877 -3.00004e-4 0.007854163 0.002481877 -3.00004e-4 0.007999956 0.002423465 -6.13718e-4 0.007854163 0.002481877 2.99996e-4 0.004999995 0.002481877 2.99996e-4 0.007999956 0.001535475 0.001972794 0.007844746 0.001767754 0.001767754 0.007854163 0.001542806 0.001967072 0.004999995 0.001162469 0.002213239 0.007999956 8.11739e-4 0.002364516 0.007999956 0.001189827 0.002198636 0.004999995 0.001967072 0.001542806 0.007854163 0.001967072 0.001542806 0.007999956 0.002092897 0.00136733 0.004999995 0.002213537 0.001161813 0.004999995 7.43681e-4 0.002386748 0.004999995 0.001542806 0.001967072 0.007999956 4.11476e-4 0.002465844 0.007854163 2.9999e-4 0.002481877 0.004999995 2.9999e-4 0.002481877 0.007999956 0.00183928 0.001693189 0.007999956 0.002491414 2.06444e-4 0.007999956 0.002491414 -2.06452e-4 0.007844746 0.002499938 0 0.007999956 0.00183928 -0.001693189 0.007844746 0.001767754 -0.001767754 0.007999956 6.14203e-4 -7.89145e-4 0.007999956 4.75937e-4 -8.79478e-4 0.007999956 0.001535475 -0.001972854 0.007999956 0.002491414 2.06444e-4 0.007999956 9.96574e-4 8.25753e-5 0.007999956 0.002491414 -2.06452e-4 0.007999956 9.96574e-4 -8.25833e-5 0.007999956 0.002423465 -6.13718e-4 0.007999956 0.002423465 6.1371e-4 0.007999956 9.6939e-4 2.45481e-4 0.007999956 9.6939e-4 -2.45489e-4 0.007999956 0.002289414 -0.001004219 0.007999956 0.002289414 0.001004219 0.007999956 9.15763e-4 4.01691e-4 0.007999956 0.002092897 -0.00136733 0.007999956 9.15763e-4 -4.01699e-4 0.007999956 0.002092897 0.00136733 0.007999956 8.37157e-4 5.46944e-4 0.007999956 8.37157e-4 -5.46952e-4 0.007999956 0.00183928 -0.001693189 0.007999956 0.00183928 0.001693189 0.007999956 7.35714e-4 6.77278e-4 0.007999956 7.35714e-4 -6.77286e-4 0.007999956 8.11739e-4 0.002364516 0.007999956 3.24689e-4 9.45813e-4 0.007999956 4.75937e-4 8.7947e-4 0.007999956 0.001189827 -0.002198636 0.007999956 3.24689e-4 -9.45821e-4 0.007999956 1.64585e-4 -9.86365e-4 0.007999956 8.11739e-4 -0.002364516 0.007999956 -1.6465e-4 -9.86357e-4 0.007999956 -4.11496e-4 -0.002465903 0.007999956 0 -0.002499997 0.007999956 -1.6465e-4 9.86349e-4 0.007999956 -8.11759e-4 0.002364516 0.007999956 -3.24796e-4 9.45782e-4 0.007999956 -8.36977e-4 -5.47205e-4 0.007999956 -0.00183928 -0.001693189 0.007999956 -7.35512e-4 -6.77484e-4 0.007999956 -0.00183928 0.001693189 0.007999956 -7.35875e-4 6.77113e-4 0.007999956 -0.001535534 0.001972794 0.007999956 -0.002491414 2.06444e-4 0.007999956 -0.002491414 -2.06452e-4 0.007999956 -9.96544e-4 -8.29161e-5 0.007999956 -9.96601e-4 8.22504e-5 0.007999956 -9.69469e-4 2.45181e-4 0.007999956 -0.002423465 6.1371e-4 0.007999956 -9.15623e-4 -4.01995e-4 0.007999956 -0.002289414 -0.001004219 0.007999956 -9.69302e-4 -2.45812e-4 0.007999956 -0.002423465 -6.13718e-4 0.007999956 -0.002289414 0.001004219 0.007999956 -9.15884e-4 4.01428e-4 0.007999956 -0.002092897 0.00136733 0.007999956 -0.001535534 -0.001972854 0.007999956 -0.001189827 -0.002198636 0.007999956 -6.14e-4 -7.89284e-4 0.007999956 -8.37305e-4 5.46728e-4 0.007999956 -3.24555e-4 -9.45855e-4 0.007999956 -4.75757e-4 -8.79559e-4 0.007999956 -8.11759e-4 -0.002364516 0.007999956 4.11476e-4 -0.002465903 0.007999956 0 -0.000999987 0.007999956 -4.76076e-4 8.79402e-4 0.007999956 -0.001189827 0.002198636 0.007999956 1.64585e-4 9.86357e-4 0.007999956 0 0.002499938 0.007999956 0 9.99996e-4 0.007999956 4.11476e-4 0.002465844 0.007999956 0.001189827 0.002198636 0.007999956 6.14203e-4 7.89137e-4 0.007999956 0.001535475 0.001972794 0.007999956 -4.11496e-4 0.002465844 0.007999956 -6.1436e-4 7.89023e-4 0.007999956 -0.002092897 -0.00136733 0.004999995 -3.0001e-4 -0.002481877 0.004999995 -0.001109302 -0.007922649 0.004999995 -3.0001e-4 -0.007994353 0.004999995 -0.001906692 -0.007769346 0.004999995 -7.43701e-4 -0.002386748 0.004999995 -0.003432869 -0.00722599 0.004999995 -0.001162469 -0.002213239 0.004999995 -0.001542866 -0.001967072 0.004999995 -0.002683401 -0.007536411 0.004999995 -0.004147887 -0.006840586 0.004999995 -0.004817724 -0.006386578 0.004999995 -0.005440711 -0.005864977 0.007844746 -0.001767754 -0.001767754 0.005002856 -0.005440711 -0.005864977 0.007854163 -0.001542866 -0.001967072 0.005002856 -0.005864977 -0.005440711 0.007854163 -0.001967072 -0.001542806 0.004999995 -0.007922649 -0.001109302 0.004999995 -0.002481937 -3.00004e-4 0.004999995 -0.007994353 -3.00004e-4 0.004999995 -0.006842017 -0.004145503 0.004999995 -0.006386578 -0.004817724 0.004999995 -0.001967072 -0.001542806 0.004999995 -0.005864977 -0.005440711 0.004999995 -0.002213597 -0.001161813 0.004999995 -0.007536947 -0.002682149 0.004999995 -0.007226526 -0.003431558 0.004999995 -0.002386987 -7.43031e-4 0.004999995 -0.007770061 -0.001903951 0.007844746 -0.002499997 0 0.005002856 -0.007994353 -3.00004e-4 0.007854163 -0.002481937 -3.00004e-4 0.005002856 -0.007994353 2.99996e-4 0.007854163 -0.002481937 2.99996e-4 0.004999995 -0.007922649 0.001109302 0.004999995 -0.002386808 7.43687e-4 0.004999995 -0.007769346 0.001906692 0.004999995 -0.002213239 0.001162469 0.004999995 -0.007536411 0.002683401 0.004999995 -0.002481937 2.99996e-4 0.004999995 -0.007994353 2.99996e-4 0.004999995 -0.00722599 0.003432869 0.004999995 -0.001967072 0.001542806 0.004999995 -0.006840586 0.004147887 0.004999995 -0.006386578 0.004817724 0.004999995 -0.005864977 0.005440711 0.007844746 -0.001767754 0.001767754 0.005002856 -0.005864977 0.005440711 0.007854163 -0.001967072 0.001542806 0.005002856 -0.005440711 0.005864977 0.007854163 -0.001542866 0.001967072 0.004999995 -0.001542866 0.001967072 0.004999995 -0.004817724 0.006386578 0.004999995 -0.005440711 0.005864977 0.004999995 -0.004145503 0.006841957 0.004999995 -0.003431558 0.007226526 0.004999995 -0.001161813 0.002213537 0.004999995 -0.002682149 0.007536947 0.004999995 -0.001109302 0.007922649 0.004999995 -7.43037e-4 0.002386987 0.004999995 -3.0001e-4 0.002481877 0.004999995 -0.001903951 0.007770001 0.004999995 -3.0001e-4 0.007994353 0.007844746 0 0.002499938 0.005002856 -3.0001e-4 0.007994353 0.007854163 -3.0001e-4 0.002481877 0.005002856 2.9999e-4 0.007994353 0.007854163 2.9999e-4 0.002481877 0.004999995 0.004147887 0.006840527 0.004999995 0.001542806 0.001967072 0.004999995 0.004817724 0.006386578 0.004999995 7.43681e-4 0.002386748 0.004999995 0.001906692 0.007769346 0.004999995 0.001109302 0.007922649 0.004999995 2.9999e-4 0.002481877 0.004999995 2.9999e-4 0.007994353 0.004999995 0.001162469 0.002213239 0.004999995 0.003432869 0.00722599 0.004999995 0.002683401 0.007536411 0.004999995 0.005440711 0.005864977 0.007844746 0.001767754 0.001767754 0.005002856 0.005440711 0.005864977 0.007854163 0.001542806 0.001967072 0.005002856 0.005864977 0.005440711 0.007854163 0.001967072 0.001542806 0.004999995 0.001967072 0.001542806 0.004999995 0.006386578 0.004817724 0.004999995 0.005864977 0.005440711 0.004999995 0.007226526 0.003431558 0.004999995 0.006841957 0.004145503 0.004999995 0.007536947 0.002682089 0.004999995 0.002386987 7.43023e-4 0.004999995 0.007770001 0.001903951 0.004999995 0.002213537 0.001161813 0.004999995 0.007922649 0.001109302 0.004999995 0.002481877 2.99996e-4 0.004999995 0.007994353 2.99996e-4 0.007844746 0.002499938 0 0.005002856 0.007994353 2.99996e-4 0.007854163 0.002481877 2.99996e-4 0.005002856 0.007994353 -3.00004e-4 0.007854163 0.002481877 -3.00004e-4 0.004999995 0.002386748 -7.43695e-4 0.004999995 0.007769346 -0.001906692 0.004999995 0.007922649 -0.001109302 0.004999995 0.007536411 -0.002683401 0.004999995 0.002481877 -3.00004e-4 0.004999995 0.007994353 -3.00004e-4 0.004999995 0.002213239 -0.001162469 0.004999995 0.001967072 -0.001542806 0.004999995 0.00722599 -0.003432869 0.004999995 0.006386578 -0.004817724 0.004999995 0.006840527 -0.004147887 0.004999995 0.005864977 -0.005440711 0.007844746 0.001767754 -0.001767754 0.005002856 0.005864977 -0.005440711 0.007854163 0.001967072 -0.001542806 0.005002856 0.005440711 -0.005864977 0.007854163 0.001542806 -0.001967072 0.004999995 0.001542806 -0.001967072 0.004999995 0.003705263 -0.007090151 0.004999995 0.004318296 -0.006734311 0.004999995 0.004898726 -0.006324648 0.004999995 0.005440711 -0.005864977 0.004999995 0.003061413 -0.007391035 0.004999995 0.001161813 -0.002213537 0.004999995 0.001008212 -0.007936179 0.004999995 0.001706719 -0.007815718 0.004999995 7.43017e-4 -0.002386987 0.004999995 0.002393424 -0.007633507 0.004999995 2.9999e-4 -0.002481877 0.004999995 2.9999e-4 -0.007994353 0.007844746 0 -0.002499997 0.005002856 2.9999e-4 -0.007994353 0.007854163 2.9999e-4 -0.002481877 0.005002856 -3.0001e-4 -0.007994353 0.007854163 -3.0001e-4 -0.002481877 -0.007999956 -3.24709e-4 9.45813e-4 0.007999956 -1.6465e-4 9.86349e-4 0.007999956 -3.24796e-4 9.45782e-4 0.007999956 0 9.99996e-4 -0.007999956 -1.64605e-4 9.86357e-4 -0.007999956 0 9.99996e-4 0.007999956 -6.1436e-4 7.89023e-4 0.007999956 -7.35875e-4 6.77113e-4 -0.007999956 -7.35734e-4 6.77278e-4 -0.007999956 -6.14223e-4 7.89137e-4 -0.007999956 -4.75957e-4 8.7947e-4 0.007999956 -4.76076e-4 8.79402e-4 -0.007999956 -9.6941e-4 2.45481e-4 0.007999956 -9.15884e-4 4.01428e-4 0.007999956 -9.69469e-4 2.45181e-4 -0.007999956 -9.15783e-4 4.01691e-4 -0.007999956 -8.37177e-4 5.46944e-4 0.007999956 -8.37305e-4 5.46728e-4 0.007999956 -9.69302e-4 -2.45812e-4 -0.007999956 -9.6941e-4 -2.45489e-4 0.007999956 -9.96544e-4 -8.29161e-5 0.007999956 -9.96601e-4 8.22504e-5 -0.007999956 -9.96594e-4 -8.25833e-5 -0.007999956 -9.96594e-4 8.25753e-5 0.007999956 -8.36977e-4 -5.47205e-4 0.007999956 -7.35512e-4 -6.77484e-4 -0.007999956 -7.35734e-4 -6.77286e-4 -0.007999956 -9.15783e-4 -4.01699e-4 0.007999956 -9.15623e-4 -4.01995e-4 -0.007999956 -8.37177e-4 -5.46952e-4 -0.007999956 -3.24709e-4 -9.45821e-4 0.007999956 -4.75757e-4 -8.79559e-4 0.007999956 -3.24555e-4 -9.45855e-4 -0.007999956 -4.75957e-4 -8.79478e-4 -0.007999956 -6.14223e-4 -7.89145e-4 0.007999956 -6.14e-4 -7.89284e-4 0.007999956 1.64585e-4 -9.86365e-4 -0.007999956 1.64585e-4 -9.86365e-4 0.007999956 0 -0.000999987 0.007999956 -1.6465e-4 -9.86357e-4 -0.007999956 0 -0.000999987 -0.007999956 -1.64605e-4 -9.86365e-4 0.007999956 4.75937e-4 -8.79478e-4 0.007999956 6.14203e-4 -7.89145e-4 -0.007999956 6.14203e-4 -7.89145e-4 -0.007999956 3.24689e-4 -9.45821e-4 0.007999956 3.24689e-4 -9.45821e-4 -0.007999956 4.75937e-4 -8.79478e-4 -0.007999956 9.15763e-4 -4.01699e-4 0.007999956 8.37157e-4 -5.46952e-4 0.007999956 9.15763e-4 -4.01699e-4 -0.007999956 8.37157e-4 -5.46952e-4 -0.007999956 7.35714e-4 -6.77286e-4 0.007999956 7.35714e-4 -6.77286e-4 0.007999956 9.96574e-4 8.25753e-5 -0.007999956 9.96574e-4 8.25753e-5 0.007999956 9.96574e-4 -8.25833e-5 0.007999956 9.6939e-4 -2.45489e-4 -0.007999956 9.96574e-4 -8.25833e-5 -0.007999956 9.6939e-4 -2.45489e-4 -0.007999956 9.6939e-4 2.45481e-4 0.007999956 9.6939e-4 2.45481e-4 -0.007999956 9.15763e-4 4.01691e-4 0.007999956 9.15763e-4 4.01691e-4 -0.007999956 8.37157e-4 5.46944e-4 -0.007999956 7.35714e-4 6.77278e-4 0.007999956 8.37157e-4 5.46944e-4 0.007999956 7.35714e-4 6.77278e-4 -0.007999956 6.14203e-4 7.89137e-4 0.007999956 6.14203e-4 7.89137e-4 -0.007999956 4.75937e-4 8.7947e-4 -0.007999956 3.24689e-4 9.45813e-4 0.007999956 4.75937e-4 8.7947e-4 0.007999956 3.24689e-4 9.45813e-4 -0.007999956 1.64585e-4 9.86357e-4 0.007999956 1.64585e-4 9.86357e-4 0.004999995 0.007922649 0.001109302 0.004999995 0.007994353 2.99996e-4 0.005499958 0.007988274 4.31978e-4 0.005002856 2.9999e-4 0.007994353 0.005499958 0 0.007999956 0.005002856 -3.0001e-4 0.007994353 0.005002856 0.007994353 2.99996e-4 0.005499958 0.007993042 -3.27464e-4 0.004999995 0.007922649 -0.001109302 0.005499958 0.007926642 -0.001080453 0.005002856 0.007994353 -3.00004e-4 0.005499958 0.007788181 -0.001827836 0.004999995 0.007994353 -3.00004e-4 0.005499958 0.007580995 -0.002554774 0.004999995 0.007769346 -0.001906692 0.004999995 0.007536411 -0.002683401 0.005499958 0.00730431 -0.003262519 0.004999995 0.00722599 -0.003432869 0.005499958 0.006963133 -0.003938496 0.005499958 0.006558954 -0.004580199 0.004999995 0.006840527 -0.004147887 0.004999995 0.006386578 -0.004817724 0.005499958 0.006095707 -0.005180597 0.005002856 0.005864977 -0.005440711 0.004999995 0.005864977 -0.005440711 0.005002856 0.005440711 -0.005864977 0.005499958 0.005578696 -0.005733788 0.004999995 0.005440711 -0.005864977 0.004999995 0.004898726 -0.006324648 0.005499958 0.005009949 -0.006236672 0.004999995 0.004318296 -0.006734311 0.005499958 0.004398822 -0.006682038 0.005499958 0.00374931 -0.007066786 0.004999995 0.003705263 -0.007090151 0.005499958 0.003061413 -0.007391035 0.004999995 0.003061413 -0.007391035 0.005499958 0.007911503 0.00118488 0.004999995 0.007770001 0.001903951 0.005499958 0.007763862 0.001928985 0.004999995 0.007536947 0.002682089 0.005499958 0.007546305 0.002655088 0.005499958 0.007261395 0.003357052 0.004999995 0.007226526 0.003431558 0.005499958 0.006910383 0.004030406 0.004999995 0.006841957 0.004145503 0.005499958 0.006498813 0.004665017 0.004999995 0.006386578 0.004817724 0.005499958 0.006026744 0.005260944 0.004999995 0.005864977 0.005440711 0.005499958 0.005503296 0.005806028 0.005002856 0.005440711 0.005864977 0.005002856 0.005864977 0.005440711 0.005499958 0.004927873 0.006301999 0.004999995 0.004817724 0.006386578 0.004999995 0.005440711 0.005864977 0.004999995 0.004147887 0.006840527 0.005499958 0.004310429 0.006739139 0.005499958 0.003652513 0.00711739 0.004999995 0.003432869 0.00722599 0.005499958 0.002962827 0.007430851 0.004999995 0.002683401 0.007536411 0.005499958 0.00224632 0.007678031 0.004999995 0.001906692 0.007769346 0.005499958 0.001508653 0.007856249 0.005499958 7.5956e-4 0.007963716 0.004999995 0.001109302 0.007922649 0.004999995 2.9999e-4 0.007994353 0.004999995 -0.001109302 0.007922649 0.004999995 -3.0001e-4 0.007994353 0.005499958 -7.62529e-4 0.007963418 0.005499958 -0.003664672 0.007111072 0.004999995 -0.003431558 0.007226526 0.005499958 -0.002971708 0.007427453 0.005499958 -0.001513123 0.007855534 0.005499958 -0.002251803 0.007676303 0.004999995 -0.001903951 0.007770001 0.005499958 -0.004945099 0.006288528 0.005499958 -0.005518853 0.005791306 0.005002856 -0.005440711 0.005864977 0.004999995 -0.004145503 0.006841957 0.005499958 -0.004323244 0.006731092 0.004999995 -0.004817724 0.006386578 0.004999995 -0.005440711 0.005864977 0.005499958 -0.006045281 0.005239665 0.004999995 -0.005864977 0.005440711 0.005002856 -0.005864977 0.005440711 0.004999995 -0.006386578 0.004817724 0.004999995 -0.007536411 0.002683401 0.004999995 -0.00722599 0.003432869 0.005499958 -0.007276535 0.003324091 0.005499958 -0.006927251 0.004001498 0.004999995 -0.006840586 0.004147887 0.005499958 -0.006515324 0.00464189 0.005499958 -0.00755912 0.002618551 0.005499958 -0.007774353 0.001886367 0.004999995 -0.007769346 0.001906692 0.005499958 -0.007990837 3.81867e-4 0.005499958 -0.007990837 -3.78864e-4 0.005002856 -0.007994353 -3.00004e-4 0.004999995 -0.007922649 0.001109302 0.005499958 -0.007918059 0.001140713 0.004999995 -0.007770061 -0.001903951 0.005499958 -0.00756061 -0.002614319 0.004999995 -0.007536947 -0.002682149 0.004999995 -0.007922649 -0.001109302 0.005499958 -0.007918715 -0.0011366 0.005002856 -0.007994353 2.99996e-4 0.004999995 -0.007994353 2.99996e-4 0.005499958 -0.006929159 -0.003997981 0.004999995 -0.006842017 -0.004145503 0.004999995 -0.007226526 -0.003431558 0.004999995 -0.007994353 -3.00004e-4 0.005499958 -0.005522012 -0.005788385 0.005002856 -0.005864977 -0.005440711 0.005499958 -0.006046891 -0.005237519 0.005499958 -0.00651735 -0.004639267 0.004999995 -0.004147887 -0.006840586 0.004999995 -0.004817724 -0.006386578 0.005499958 -0.004326939 -0.006728649 0.005499958 -0.0036664 -0.007110297 0.005499958 -0.002975225 -0.007425963 0.004999995 -0.003432869 -0.00722599 0.005499958 -0.00225526 -0.007675468 0.004999995 -0.002683401 -0.007536411 0.004999995 -0.005864977 -0.005440711 0.005499958 -0.001515388 -0.007854998 0.004999995 -0.001906692 -0.007769346 0.004999995 -0.005440711 -0.005864977 0.005499958 -0.004945516 -0.00628817 0.004999995 -0.001109302 -0.007922649 0.004999995 -3.0001e-4 -0.007994353 0.005499958 -7.62529e-4 -0.007963418 0.005499958 0 -0.007999956 0.005002856 -3.0001e-4 -0.007994353 0.005002856 2.9999e-4 -0.007994353 0.005499958 7.84822e-4 -0.007961392 0.004999995 0.001008212 -0.007936179 0.005499958 0.001559555 -0.007846415 0.004999995 2.9999e-4 -0.007994353 0.004999995 0.001706719 -0.007815718 0.005499958 0.002321541 -0.00765568 0.004999995 0.002393424 -0.007633507 0.005002856 -0.005440711 -0.005864977 0.004999995 -0.006386578 -0.004817724 0.005499958 -0.00727725 -0.00332278 0.005499958 -0.007774531 -0.001885414 0.004999995 -0.002682149 0.007536947 -0.007999956 0.001535475 0.001972794 -0.007999956 6.14203e-4 7.89137e-4 -0.007999956 4.75937e-4 8.7947e-4 -0.007999956 0.002491414 2.06444e-4 -0.007999956 9.96574e-4 8.25753e-5 -0.007999956 0.002423465 6.1371e-4 -0.007999956 0.002491414 -2.06452e-4 -0.007999956 9.96574e-4 -8.25833e-5 -0.007999956 0.002289414 0.001004219 -0.007999956 9.6939e-4 2.45481e-4 -0.007999956 9.6939e-4 -2.45489e-4 -0.007999956 0.002423465 -6.13718e-4 -0.007999956 9.15763e-4 4.01691e-4 -0.007999956 0.002092897 0.00136733 -0.007999956 9.15763e-4 -4.01699e-4 -0.007999956 0.002289414 -0.001004219 -0.007999956 8.37157e-4 5.46944e-4 -0.007999956 0.00183928 0.001693189 -0.007999956 8.37157e-4 -5.46952e-4 -0.007999956 0.002092897 -0.00136733 -0.007999956 7.35714e-4 6.77278e-4 -0.007999956 7.35714e-4 -6.77286e-4 -0.007999956 0.00183928 -0.001693189 -0.007999956 3.24689e-4 9.45813e-4 -0.007999956 8.11739e-4 0.002364516 -0.007999956 0.001189827 0.002198636 -0.007999956 3.24689e-4 -9.45821e-4 -0.007999956 4.75937e-4 -8.79478e-4 -0.007999956 8.11739e-4 -0.002364516 -0.007999956 0 -0.000999987 -0.007999956 -4.11611e-4 -0.002465844 -0.007999956 -1.64605e-4 -9.86365e-4 -0.007999956 -7.35734e-4 -6.77286e-4 -0.007999956 -0.001535832 -0.001972556 -0.007999956 -0.001839637 -0.001692771 -0.007999956 0 9.99996e-4 -0.007999956 0 0.002499938 -0.007999956 4.11476e-4 0.002465844 -0.007999956 -9.6941e-4 -2.45489e-4 -0.007999956 -0.002423644 -6.12966e-4 -0.007999956 -9.96594e-4 -8.25833e-5 -0.007999956 -6.14223e-4 7.89137e-4 -0.007999956 -0.001534938 0.001973152 -0.007999956 -0.001189351 0.002198874 -0.007999956 -0.002491295 2.07276e-4 -0.007999956 -9.96594e-4 8.25753e-5 -0.007999956 -0.002491474 -2.0564e-4 -0.007999956 -9.6941e-4 2.45481e-4 -0.007999956 -0.002423226 6.14517e-4 -0.007999956 -9.15783e-4 4.01691e-4 -0.007999956 -7.35734e-4 6.77278e-4 -0.007999956 -0.002092421 0.001367986 -0.007999956 -0.001838743 0.001693665 -0.007999956 -8.37177e-4 5.46944e-4 -0.007999956 -0.002288997 0.001004934 -0.007999956 -0.002289652 -0.001003563 -0.007999956 -9.15783e-4 -4.01699e-4 -0.007999956 -0.002093195 -0.001366794 -0.007999956 -8.11373e-4 0.002364575 -0.007999956 -3.24709e-4 9.45813e-4 -0.007999956 -4.75957e-4 8.7947e-4 -0.007999956 -8.37177e-4 -5.46952e-4 -0.007999956 -1.64605e-4 9.86357e-4 -0.007999956 -4.11611e-4 0.002465844 -0.007999956 1.64585e-4 9.86357e-4 -0.007999956 -4.75957e-4 -8.79478e-4 -0.007999956 -0.001190125 -0.002198517 -0.007999956 1.64585e-4 -9.86365e-4 -0.007999956 0 -0.002499997 -0.007999956 4.11476e-4 -0.002465903 -0.007999956 0.001189827 -0.002198636 -0.007999956 6.14203e-4 -7.89145e-4 -0.007999956 0.001535475 -0.001972854 -0.007999956 -8.11975e-4 -0.002364456 -0.007999956 -3.24709e-4 -9.45821e-4 -0.007999956 -6.14223e-4 -7.89145e-4 0.005499958 0.006505608 -0.006218969 0.005499958 0.007037937 -0.005609214 0.005499958 0.006095707 -0.005180597 0.005499958 0.004927873 0.006301999 0.005499958 0.005919814 0.006778895 0.005499958 0.005288362 0.007282078 0.005499958 0.007546305 0.002655088 0.005499958 0.007763862 0.001928985 0.005499958 0.008558511 0.002783536 0.005499958 0.0075109 0.004958331 0.005499958 0.006910383 0.004030406 0.005499958 0.00792396 0.004266977 0.005499958 0.006026744 0.005260944 0.005499958 0.007034897 0.005613148 0.005499958 0.006504118 0.00622034 0.005499958 0.007261395 0.003357052 0.005499958 0.008275568 0.003537535 0.005499958 0.007911503 0.00118488 0.005499958 0.007988274 4.31978e-4 0.005499958 0.008917987 0.001210451 0.005499958 0.008774101 0.00200355 0.005499958 0.008990764 -4.01676e-4 0.005499958 0.007993042 -3.27464e-4 0.005499958 0.007926642 -0.001080453 0.005499958 0.006498813 0.004665017 0.005499958 0.005503296 0.005806028 0.005499958 0.008990764 4.05242e-4 0.005499958 0.008560061 -0.002778947 0.005499958 0.008774518 -0.002001106 0.005499958 0.007788181 -0.001827836 0.005499958 0.008918702 -0.001206159 0.005499958 0.003902673 0.008109509 0.005499958 0.003652513 0.00711739 0.005499958 0.004614651 0.007726788 0.005499958 0.004310429 0.006739139 0.005499958 0.003161251 0.008426487 0.005499958 0.002962827 0.007430851 0.005499958 0.007580995 -0.002554774 0.005499958 0.008275926 -0.003536522 0.005499958 0.002391755 0.008676111 0.005499958 0.001606404 0.008855402 0.005499958 0.001508653 0.007856249 0.005499958 0.00730431 -0.003262519 0.005499958 0.007926344 -0.004262506 0.005499958 0 0.007999956 0.005499958 -8.09684e-4 0.008963286 0.005499958 -7.62529e-4 0.007963418 0.005499958 0.002321541 -0.00765568 0.005499958 0.003163933 -0.008425295 0.005499958 0.003061413 -0.007391035 0.005499958 0.004617869 -0.007724702 0.005499958 0.00374931 -0.007066786 0.005499958 0.003906488 -0.008107841 0.005499958 0.002396345 -0.008674979 0.005499958 0.001559555 -0.007846415 0.005499958 0.001607954 -0.008855044 0.005499958 7.84822e-4 -0.007961392 0.005499958 8.09166e-4 -0.008963406 0.005499958 -0.001606762 -0.008855402 0.005499958 -7.62529e-4 -0.007963418 0.005499958 -0.001515388 -0.007854998 0.005499958 0 -0.007999956 0.005499958 -8.09684e-4 -0.008963286 0.005499958 0 -0.009000003 0.005499958 -0.005920767 -0.00677818 0.005499958 -0.004945516 -0.00628817 0.005499958 -0.005522012 -0.005788385 0.005499958 -0.0036664 -0.007110297 0.005499958 -0.003902077 -0.008109807 0.005499958 -0.002975225 -0.007425963 0.005499958 -0.00727725 -0.00332278 0.005499958 -0.007924675 -0.004265964 0.005499958 -0.006929159 -0.003997981 0.005499958 -0.007509291 -0.004960358 0.005499958 -0.007035732 -0.005612254 0.005499958 -0.00651735 -0.004639267 0.005499958 -0.008773446 -0.002005279 0.005499958 -0.007774531 -0.001885414 0.005499958 -0.007918715 -0.0011366 0.005499958 -0.006046891 -0.005237519 0.005499958 -0.006502866 -0.006221532 0.005499958 -0.004326939 -0.006728649 0.005499958 -0.005287468 -0.007282733 0.005499958 -0.004615485 -0.007726371 0.005499958 -0.008558988 -0.002782583 0.005499958 -0.00756061 -0.002614319 0.005499958 -0.008274376 -0.003539741 0.005499958 -0.007990837 -3.78864e-4 0.005499958 -0.008918225 -0.001209795 0.005499958 -0.008990943 4.01868e-4 0.005499958 -0.008990526 -4.06411e-4 0.005499958 -0.008918583 0.001205563 0.005499958 -0.007918059 0.001140713 0.005499958 -0.008774697 0.002000629 0.005499958 -0.007990837 3.81867e-4 0.005499958 -0.00225526 -0.007675468 0.005499958 -0.003161907 -0.008426249 0.005499958 -0.002391338 -0.00867623 0.005499958 -0.00755912 0.002618551 0.005499958 -0.008276522 0.003535091 0.005499958 -0.008559942 0.002778887 0.005499958 -0.007774353 0.001886367 0.005499958 -0.007276535 0.003324091 0.005499958 -0.007926106 0.004262864 0.005499958 -0.006045281 0.005239665 0.005499958 -0.0065068 0.006217598 0.005499958 -0.007037401 0.005609869 0.005499958 -0.004945099 0.006288528 0.005499958 -0.005292117 0.007279455 0.005499958 -0.005922436 0.006776511 0.005499958 -0.005518853 0.005791306 0.005499958 -0.004323244 0.006731092 0.005499958 -0.004617035 0.007725298 0.005499958 -0.002971708 0.007427453 0.005499958 -0.003907382 0.008107364 0.005499958 -0.003664672 0.007111072 0.005499958 -0.002251803 0.007676303 0.005499958 -0.003163099 0.008425712 0.005499958 -0.00239706 0.008674681 0.005499958 -0.001513123 0.007855534 0.005499958 0.005578696 -0.005733788 0.005499958 0.005923151 -0.006775796 0.005499958 0.005291044 -0.007280349 0.005499958 0.005009949 -0.006236672 0.005499958 8.09166e-4 0.008963406 0.005499958 7.5956e-4 0.007963716 0.005499958 0 0.008999943 0.005499958 0.007511258 -0.004957914 0.005499958 0.006963133 -0.003938496 0.005499958 0.006558954 -0.004580199 0.005499958 0.00224632 0.007678031 0.005499958 -0.006927251 0.004001498 0.005499958 -0.00751239 0.004955947 0.005499958 -0.006515324 0.00464189 0.005499958 0.004398822 -0.006682038 0.005499958 -0.001607418 0.008855223 -0.005002856 -0.005440711 0.005864977 -0.004999995 -0.001542866 0.001967072 -0.007854163 -0.001542866 0.001967072 -0.004999995 -0.005440711 0.005864977 -0.005002856 -0.005864977 0.005440711 -0.004999995 -0.001967072 0.001542806 -0.004999995 -0.005864977 0.005440711 -0.007854163 -0.001967072 0.001542806 -0.005002856 -0.007994353 2.99996e-4 -0.004999995 -0.002481937 2.99996e-4 -0.007854163 -0.002481937 2.99996e-4 -0.004999995 -0.007994353 2.99996e-4 -0.004999995 -0.002481937 -3.00004e-4 -0.005002856 -0.007994353 -3.00004e-4 -0.007854163 -0.002481937 -3.00004e-4 -0.004999995 -0.007994353 -3.00004e-4 -0.005002856 -0.005864977 -0.005440711 -0.004999995 -0.001967072 -0.001542806 -0.007854163 -0.001967072 -0.001542806 -0.004999995 -0.005864977 -0.005440711 -0.005002856 -0.005440711 -0.005864977 -0.004999995 -0.001542866 -0.001967072 -0.004999995 -0.005440711 -0.005864977 -0.007854163 -0.001542866 -0.001967072 -0.005002856 -3.0001e-4 -0.007994353 -0.004999995 -3.0001e-4 -0.002481877 -0.007854163 -3.0001e-4 -0.002481877 -0.004999995 -3.0001e-4 -0.007994353 -0.005002856 2.9999e-4 -0.007994353 -0.004999995 2.9999e-4 -0.002481877 -0.004999995 2.9999e-4 -0.007994353 -0.007854163 2.9999e-4 -0.002481877 -0.005002856 0.005440711 -0.005864977 -0.004999995 0.001542806 -0.001967072 -0.007854163 0.001542806 -0.001967072 -0.004999995 0.005440711 -0.005864977 -0.005002856 0.005864977 -0.005440711 -0.004999995 0.001967072 -0.001542806 -0.004999995 0.005864977 -0.005440711 -0.007854163 0.001967072 -0.001542806 -0.004999995 0.007994353 -3.00004e-4 -0.004999995 0.002481877 -3.00004e-4 -0.005002856 0.007994353 -3.00004e-4 -0.007854163 0.002481877 -3.00004e-4 -0.005002856 0.007994353 2.99996e-4 -0.007854163 0.002481877 2.99996e-4 -0.004999995 0.002481877 2.99996e-4 -0.004999995 0.007994353 2.99996e-4 -0.005002856 0.005864977 0.005440711 -0.004999995 0.001967072 0.001542806 -0.007854163 0.001967072 0.001542806 -0.004999995 0.005864977 0.005440711 -0.005002856 0.005440711 0.005864977 -0.004999995 0.001542806 0.001967072 -0.004999995 0.005440711 0.005864977 -0.007854163 0.001542806 0.001967072 -0.005002856 2.9999e-4 0.007994353 -0.004999995 2.9999e-4 0.002481877 -0.007854163 2.9999e-4 0.002481877 -0.004999995 2.9999e-4 0.007994353 -0.007999956 0.002092897 -0.00136733 -0.004999995 0.002213537 -0.001161813 -0.004999995 0.001967072 -0.001542806 -0.007999956 0 0.002499938 -0.007854163 -3.0001e-4 0.002481877 -0.007844805 0 0.002499938 -0.007999956 -4.11611e-4 0.002465844 -0.007999956 -0.001189351 0.002198874 -0.004999995 -0.001162469 0.002213239 -0.007999956 -8.11373e-4 0.002364575 -0.004999995 -0.002213239 -0.001162469 -0.004999995 -0.002386808 -7.43695e-4 -0.007999956 -0.002289652 -0.001003563 -0.007999956 -0.002423226 6.14517e-4 -0.007854163 -0.002481937 2.99996e-4 -0.004999995 -0.002481937 2.99996e-4 -0.007999956 -4.11611e-4 -0.002465844 -0.007854163 -3.0001e-4 -0.002481877 -0.004999995 -3.0001e-4 -0.002481877 -0.004999995 -0.001542866 -0.001967072 -0.007999956 -0.001535832 -0.001972556 -0.007999956 -0.001190125 -0.002198517 -0.007999956 0.001189827 -0.002198636 -0.004999995 0.001162469 -0.002213239 -0.007999956 8.11739e-4 -0.002364516 -0.004999995 7.43681e-4 -0.002386748 -0.007999956 0.001535475 -0.001972854 -0.004999995 0.001542806 -0.001967072 -0.007844805 0.001767754 -0.001767754 -0.007999956 0.00183928 -0.001693189 -0.007854163 0.001967072 -0.001542806 -0.007999956 0.002289414 -0.001004219 -0.004999995 0.002386987 -7.43031e-4 -0.004999995 0.002481877 -3.00004e-4 -0.007999956 0.002423465 -6.13718e-4 -0.007844805 0.002499938 0 -0.007999956 0.002491414 2.06444e-4 -0.007854163 0.002481877 2.99996e-4 -0.007999956 0.002289414 0.001004219 -0.004999995 0.002386748 7.43687e-4 -0.007999956 0.002423465 6.1371e-4 -0.004999995 0.002481877 2.99996e-4 -0.004999995 0.002213239 0.001162469 -0.007854163 0.002481877 -3.00004e-4 -0.007854163 0.001967072 0.001542806 -0.004999995 0.001967072 0.001542806 -0.007999956 0.002092897 0.00136733 -0.004999995 0.001542806 0.001967072 -0.007999956 0.001189827 0.002198636 -0.004999995 0.001161813 0.002213537 -0.007999956 0.001535475 0.001972794 -0.004999995 7.43017e-4 0.002386987 -0.007999956 8.11739e-4 0.002364516 -0.007999956 4.11476e-4 0.002465844 -0.004999995 2.9999e-4 0.002481877 -0.007854163 2.9999e-4 0.002481877 -0.007999956 4.11476e-4 -0.002465903 -0.004999995 2.9999e-4 -0.002481877 -0.004999995 -7.43037e-4 -0.002386987 -0.007854163 0.001542806 0.001967072 -0.007844805 0.001767754 0.001767754 -0.007999956 0.00183928 0.001693189 -0.007999956 -8.11975e-4 -0.002364456 -0.004999995 -0.001161813 -0.002213537 -0.007999956 0.002491414 -2.06452e-4 -0.004999995 -0.001967072 -0.001542806 -0.007999956 -0.002093195 -0.001366794 -0.007854163 -0.001967072 -0.001542806 -0.007854163 0.001542806 -0.001967072 -0.007999956 -0.002423644 -6.12966e-4 -0.004999995 -0.002481937 -3.00004e-4 -0.007999956 0 -0.002499997 -0.007854163 2.9999e-4 -0.002481877 -0.007844805 0 -0.002499997 -0.007844805 -0.002499997 0 -0.007999956 -0.002491474 -2.0564e-4 -0.007854163 -0.002481937 -3.00004e-4 -0.004999995 -0.002386987 7.43023e-4 -0.007999956 -0.002288997 0.001004934 -0.007854163 -0.001542866 -0.001967072 -0.007844805 -0.001767754 -0.001767754 -0.007999956 -0.001839637 -0.001692771 -0.004999995 -0.002213597 0.001161813 -0.007999956 -0.002092421 0.001367986 -0.004999995 -0.001967072 0.001542806 -0.007999956 -0.001838743 0.001693665 -0.007854163 -0.001967072 0.001542806 -0.007844805 -0.001767754 0.001767754 -0.007999956 -0.002491295 2.07276e-4 -0.007999956 -0.001534938 0.001973152 -0.004999995 -0.001542866 0.001967072 -0.004999995 -7.43701e-4 0.002386748 -0.007854163 -0.001542866 0.001967072 -0.004999995 -3.0001e-4 0.002481877 -0.005002856 -3.0001e-4 0.007994353 -0.004999995 -3.0001e-4 0.002481877 -0.004999995 -3.0001e-4 0.007994353 -0.007854163 -3.0001e-4 0.002481877 0.005499958 0.008990764 -4.01676e-4 0.004499971 0.008990764 4.01668e-4 0.005499958 0.008990764 4.05242e-4 0.005499958 -8.09684e-4 -0.008963286 0.004499971 0 -0.009000003 0.005499958 0 -0.009000003 0.005499958 0.008917987 0.001210451 0.004499971 0.008918702 0.001206159 0.004499971 0.008774518 0.002001106 0.005499958 0.008774101 0.00200355 0.004499971 0.008560061 0.002778947 0.005499958 0.008558511 0.002783536 0.005499958 0.008275568 0.003537535 0.004499971 0.008275926 0.003536522 0.004499971 0.007926344 0.004262506 0.005499958 0.00792396 0.004266977 0.004499971 0.007511258 0.004957854 0.005499958 0.0075109 0.004958331 0.005499958 0.007034897 0.005613148 0.004499971 0.007037937 0.005609214 0.004499971 0.006505608 0.006218969 0.005499958 0.006504118 0.00622034 0.004499971 0.005923151 0.006775796 0.005499958 0.005919814 0.006778895 0.005499958 0.005288362 0.007282078 0.004499971 0.005291044 0.007280349 0.004499971 0.004617869 0.007724702 0.005499958 0.004614651 0.007726788 0.004499971 0.003906488 0.008107841 0.005499958 0.003902673 0.008109509 0.005499958 0.003161251 0.008426487 0.004499971 0.003163933 0.008425295 0.004499971 0.002396345 0.008674979 0.005499958 0.002391755 0.008676111 0.004499971 0.001607954 0.008855044 0.005499958 0.001606404 0.008855402 0.005499958 8.09166e-4 0.008963406 0.004499971 8.09166e-4 0.008963406 0.004499971 0 0.008999943 0.005499958 0 0.008999943 0.004499971 0.008990764 -4.0525e-4 0.005499958 0.008918702 -0.001206159 0.004499971 0.008917987 -0.001210451 0.004499971 0.008774101 -0.00200361 0.005499958 0.008774518 -0.002001106 0.005499958 0.008560061 -0.002778947 0.004499971 0.008558511 -0.002783536 0.005499958 0.008275926 -0.003536522 0.004499971 0.008275568 -0.003537535 0.004499971 0.00792396 -0.004266977 0.005499958 0.007926344 -0.004262506 0.005499958 0.007511258 -0.004957914 0.004499971 0.0075109 -0.004958331 0.005499958 0.007037937 -0.005609214 0.004499971 0.007034897 -0.005613148 0.004499971 0.006504118 -0.00622034 0.005499958 0.006505608 -0.006218969 0.005499958 0.005923151 -0.006775796 0.004499971 0.005919814 -0.006778895 0.005499958 0.005291044 -0.007280349 0.004499971 0.005288362 -0.007282137 0.004499971 0.004614651 -0.007726788 0.005499958 0.004617869 -0.007724702 0.005499958 0.003906488 -0.008107841 0.004499971 0.003902673 -0.008109509 0.005499958 0.003163933 -0.008425295 0.004499971 0.003161251 -0.008426487 0.004499971 0.002391755 -0.008676111 0.005499958 0.002396345 -0.008674979 0.005499958 0.001607954 -0.008855044 0.004499971 0.001606404 -0.008855462 0.005499958 8.09166e-4 -0.008963406 0.004499971 8.09166e-4 -0.008963406 0.005499958 -0.003161907 -0.008426249 0.004499971 -0.002396345 -0.008674979 0.005499958 -0.002391338 -0.00867623 0.005499958 -0.001606762 -0.008855402 0.004499971 -0.001607954 -0.008855044 0.004499971 -8.09186e-4 -0.008963406 0.004499971 -0.004617869 -0.007724702 0.005499958 -0.004615485 -0.007726371 0.005499958 -0.005287468 -0.007282733 0.004499971 -0.003163933 -0.008425295 0.005499958 -0.003902077 -0.008109807 0.004499971 -0.003906488 -0.008107841 0.005499958 -0.006502866 -0.006221532 0.005499958 -0.007035732 -0.005612254 0.004499971 -0.006505668 -0.006218969 0.005499958 -0.005920767 -0.00677818 0.004499971 -0.005923211 -0.006775796 0.004499971 -0.005291104 -0.007280349 0.005499958 -0.008274376 -0.003539741 0.004499971 -0.007926404 -0.004262506 0.005499958 -0.007924675 -0.004265964 0.004499971 -0.007511258 -0.004957914 0.004499971 -0.007037937 -0.005609214 0.005499958 -0.007509291 -0.004960358 0.004499971 -0.008774518 -0.002001106 0.005499958 -0.008773446 -0.002005279 0.005499958 -0.008918225 -0.001209795 0.004499971 -0.008275926 -0.003536522 0.005499958 -0.008558988 -0.002782583 0.004499971 -0.008560061 -0.002778947 0.005499958 -0.008990943 4.01868e-4 0.005499958 -0.008918583 0.001205563 0.004499971 -0.008990824 4.05242e-4 0.005499958 -0.008990526 -4.06411e-4 0.004499971 -0.008990824 -4.01676e-4 0.004499971 -0.008918702 -0.001206159 0.005499958 -0.008276522 0.003535091 0.004499971 -0.008558511 0.002783536 0.005499958 -0.008559942 0.002778887 0.004499971 -0.008774101 0.00200355 0.004499971 -0.008917987 0.001210451 0.005499958 -0.008774697 0.002000629 0.004499971 -0.0075109 0.004958331 0.005499958 -0.00751239 0.004955947 0.005499958 -0.007037401 0.005609869 0.004499971 -0.008275568 0.003537535 0.005499958 -0.007926106 0.004262864 0.004499971 -0.00792402 0.004266977 0.004499971 -0.006504118 0.00622034 0.005499958 -0.005922436 0.006776511 0.004499971 -0.005919814 0.006778895 0.005499958 -0.0065068 0.006217598 0.004499971 -0.007034897 0.005613148 0.004499971 -0.005288362 0.007282078 0.005499958 -0.005292117 0.007279455 0.005499958 -0.004617035 0.007725298 0.004499971 -0.004614651 0.007726788 0.005499958 -0.003907382 0.008107364 0.004499971 -0.003902733 0.008109509 0.004499971 -0.003161311 0.008426487 0.005499958 -0.003163099 0.008425712 0.005499958 -0.00239706 0.008674681 0.004499971 -0.002391755 0.008676111 0.005499958 -0.001607418 0.008855223 0.004499971 -0.001606404 0.008855402 0.004499971 -8.09186e-4 0.008963406 0.005499958 -8.09684e-4 0.008963286 -0.004999995 -7.43701e-4 0.002386748 -0.004999995 -0.001162469 0.002213239 -0.004999995 -0.002683401 0.007536411 -0.004999995 -3.0001e-4 0.002481877 -0.004999995 -0.001109302 0.007922649 -0.004999995 -3.0001e-4 0.007994353 -0.004999995 -0.001906692 0.007769346 -0.004999995 -0.001542866 0.001967072 -0.004999995 -0.003432869 0.00722599 -0.004999995 -0.004817724 0.006386578 -0.004999995 -0.004147887 0.006840527 -0.004999995 -0.005440711 0.005864977 -0.007844805 -0.001767754 0.001767754 -0.007854163 -0.001967072 0.001542806 -0.005002856 -0.005864977 0.005440711 -0.005002856 -0.005440711 0.005864977 -0.007854163 -0.001542866 0.001967072 -0.004999995 -0.006842017 0.004145503 -0.004999995 -0.001967072 0.001542806 -0.004999995 -0.007226526 0.003431558 -0.004999995 -0.002386987 7.43023e-4 -0.004999995 -0.007922649 0.001109302 -0.004999995 -0.007770061 0.001903951 -0.004999995 -0.006386578 0.004817724 -0.004999995 -0.005864977 0.005440711 -0.004999995 -0.002213597 0.001161813 -0.004999995 -0.007536947 0.002682089 -0.004999995 -0.002481937 2.99996e-4 -0.004999995 -0.007994353 2.99996e-4 -0.007844805 -0.002499997 0 -0.007854163 -0.002481937 -3.00004e-4 -0.005002856 -0.007994353 -3.00004e-4 -0.005002856 -0.007994353 2.99996e-4 -0.007854163 -0.002481937 2.99996e-4 -0.004999995 -0.002481937 -3.00004e-4 -0.004999995 -0.002386808 -7.43695e-4 -0.004999995 -0.007922649 -0.001109302 -0.004999995 -0.007994353 -3.00004e-4 -0.004999995 -0.002213239 -0.001162469 -0.004999995 -0.007536411 -0.002683401 -0.004999995 -0.007769346 -0.001906692 -0.004999995 -0.001967072 -0.001542806 -0.004999995 -0.00722599 -0.003432869 -0.004999995 -0.006386578 -0.004817724 -0.004999995 -0.006840586 -0.004147887 -0.004999995 -0.005864977 -0.005440711 -0.007844805 -0.001767754 -0.001767754 -0.007854163 -0.001542866 -0.001967072 -0.005002856 -0.005440711 -0.005864977 -0.005002856 -0.005864977 -0.005440711 -0.007854163 -0.001967072 -0.001542806 -0.004999995 -7.43037e-4 -0.002386987 -0.004999995 -0.001008272 -0.007936179 -0.004999995 -0.001706779 -0.007815718 -0.004999995 -0.001542866 -0.001967072 -0.004999995 -0.004898786 -0.006324648 -0.004999995 -0.005440711 -0.005864977 -0.004999995 -0.003705263 -0.007090151 -0.004999995 -0.001161813 -0.002213537 -0.004999995 -0.004318296 -0.006734311 -0.004999995 -0.003061473 -0.007391035 -0.004999995 -0.002393424 -0.007633507 -0.004999995 -3.0001e-4 -0.007994353 -0.004999995 -3.0001e-4 -0.002481877 -0.005002856 -3.0001e-4 -0.007994353 -0.007854163 -3.0001e-4 -0.002481877 -0.007844805 0 -0.002499997 -0.007854163 2.9999e-4 -0.002481877 -0.005002856 2.9999e-4 -0.007994353 -0.004999995 0.001906692 -0.007769346 -0.004999995 7.43681e-4 -0.002386748 -0.004999995 0.002683401 -0.007536411 -0.004999995 2.9999e-4 -0.002481877 -0.004999995 0.001109302 -0.007922649 -0.004999995 0.001162469 -0.002213239 -0.004999995 2.9999e-4 -0.007994353 -0.004999995 0.001542806 -0.001967072 -0.004999995 0.003432869 -0.00722599 -0.004999995 0.004817724 -0.006386578 -0.004999995 0.004147887 -0.006840586 -0.004999995 0.005440711 -0.005864977 -0.007844805 0.001767754 -0.001767754 -0.007854163 0.001967072 -0.001542806 -0.005002856 0.005864977 -0.005440711 -0.005002856 0.005440711 -0.005864977 -0.007854163 0.001542806 -0.001967072 -0.004999995 0.002213537 -0.001161813 -0.004999995 0.007536947 -0.002682149 -0.004999995 0.007226526 -0.003431558 -0.004999995 0.002386987 -7.43031e-4 -0.004999995 0.007770001 -0.001903951 -0.004999995 0.002481877 -3.00004e-4 -0.004999995 0.007922649 -0.001109302 -0.004999995 0.001967072 -0.001542806 -0.004999995 0.007994353 -3.00004e-4 -0.004999995 0.006841957 -0.004145503 -0.004999995 0.006386578 -0.004817724 -0.004999995 0.005864977 -0.005440711 -0.007844805 0.002499938 0 -0.007854163 0.002481877 2.99996e-4 -0.005002856 0.007994353 2.99996e-4 -0.005002856 0.007994353 -3.00004e-4 -0.007854163 0.002481877 -3.00004e-4 -0.004999995 0.002386748 7.43687e-4 -0.004999995 0.002213239 0.001162469 -0.004999995 0.007536411 0.002683401 -0.004999995 0.007922649 0.001109302 -0.004999995 0.002481877 2.99996e-4 -0.004999995 0.007994353 2.99996e-4 -0.004999995 0.007769346 0.001906692 -0.004999995 0.001967072 0.001542806 -0.004999995 0.00722599 0.003432869 -0.004999995 0.006386578 0.004817724 -0.004999995 0.006840527 0.004147887 -0.004999995 0.005864977 0.005440711 -0.007844805 0.001767754 0.001767754 -0.007854163 0.001542806 0.001967072 -0.005002856 0.005440711 0.005864977 -0.005002856 0.005864977 0.005440711 -0.007854163 0.001967072 0.001542806 -0.004999995 0.001109302 0.007922649 -0.004999995 0.001903951 0.007770001 -0.004999995 7.43017e-4 0.002386987 -0.004999995 0.004145503 0.006841957 -0.004999995 0.001542806 0.001967072 -0.004999995 0.003431558 0.007226526 -0.004999995 0.004817724 0.006386578 -0.004999995 0.005440711 0.005864977 -0.004999995 0.001161813 0.002213537 -0.004999995 0.002682089 0.007536947 -0.004999995 2.9999e-4 0.002481877 -0.004999995 2.9999e-4 0.007994353 -0.005002856 2.9999e-4 0.007994353 -0.007854163 2.9999e-4 0.002481877 -0.007844805 0 0.002499938 -0.007854163 -3.0001e-4 0.002481877 -0.005002856 -3.0001e-4 0.007994353 0.004499971 0.007511258 0.004957854 0.004499971 0.006515324 0.00464189 0.004499971 0.007037937 0.005609214 0.004499971 0.00792396 -0.004266977 0.004499971 0.006929099 -0.003997981 0.004499971 0.00727725 -0.00332278 0.004499971 0.007560551 -0.002614319 0.004499971 0.007774531 -0.001885414 0.004499971 0.008558511 -0.002783536 0.004499971 0.0075109 -0.004958331 0.004499971 0.006046891 -0.005237519 0.004499971 0.007034897 -0.005613148 0.004499971 0.006504118 -0.00622034 0.004499971 0.007918715 -0.0011366 0.004499971 0.008774101 -0.00200361 0.004499971 0.008275568 -0.003537535 0.004499971 0.008990764 -4.0525e-4 0.004499971 0.007990837 -3.78864e-4 0.004499971 0.008990764 4.01668e-4 0.004499971 0.008917987 -0.001210451 0.004499971 0.00651735 -0.004639267 0.004499971 0.007990837 3.81867e-4 0.004499971 0.008918702 0.001206159 0.004499971 0.005521953 -0.005788385 0.004499971 0.005919814 -0.006778895 0.004499971 0.007918059 0.001140713 0.004499971 0.008774518 0.002001106 0.004499971 0.005288362 -0.007282137 0.004499971 0.004945456 -0.00628817 0.004499971 0.007774353 0.001886367 0.004499971 0.008560061 0.002778947 0.004499971 0.004614651 -0.007726788 0.004499971 0.004326939 -0.006728649 0.004499971 0.008275926 0.003536522 0.004499971 0.00755912 0.002618551 0.004499971 0.003902673 -0.008109509 0.004499971 0.0036664 -0.007110297 0.004499971 0.007276535 0.003324091 0.004499971 0.007926344 0.004262506 0.004499971 0.003161251 -0.008426487 0.004499971 0.002975165 -0.007425963 0.004499971 0.006927192 0.004001498 0.004499971 0.005923151 0.006775796 0.004499971 0.004945099 0.006288528 0.004499971 0.005291044 0.007280349 0.004499971 0.002391755 -0.008676111 0.004499971 0.001606404 -0.008855462 0.004499971 0.001515328 -0.007854998 0.004499971 0.002971708 0.007427453 0.004499971 0.003906488 0.008107841 0.004499971 0.003664672 0.007111072 0.004499971 -8.09186e-4 -0.008963406 0.004499971 -7.6298e-4 -0.007963359 0.004499971 0 -0.007999956 0.004499971 -0.002251207 -0.007676482 0.004499971 -0.003163933 -0.008425295 0.004499971 -0.002972126 -0.007427334 0.004499971 -0.004617869 -0.007724702 0.004499971 -0.005291104 -0.007280349 0.004499971 -0.004323542 -0.006730914 0.004499971 0.001607954 0.008855044 0.004499971 0.002396345 0.008674979 0.004499971 0.001513063 0.007855534 0.004499971 -0.007511258 -0.004957914 0.004499971 -0.006514966 -0.004642426 0.004499971 -0.007037937 -0.005609214 0.004499971 8.09166e-4 0.008963406 0.004499971 7.62509e-4 0.007963418 0.004499971 0 0.007999956 0.004499971 -0.007559776 -0.00261712 0.004499971 -0.008275926 -0.003536522 0.004499971 -0.008560061 -0.002778947 0.004499971 -0.003161311 0.008426487 0.004499971 -0.002391755 0.008676111 0.004499971 -0.002255976 0.00767517 0.004499971 -0.008990824 4.05242e-4 0.004499971 -0.007990956 3.78865e-4 0.004499971 -0.008990824 -4.01676e-4 0.004499971 -0.00552237 0.005787849 0.004499971 -0.005919814 0.006778895 0.004499971 -0.004946231 0.006287574 0.004499971 -0.008558511 0.002783536 0.004499971 -0.007560193 0.002615392 0.004499971 -0.007774889 0.001883864 0.004499971 -0.00792402 0.004266977 0.004499971 -0.006928205 0.003999948 0.004499971 -0.007277965 0.003320932 0.004499971 -0.007918596 0.0011366 0.004499971 -0.008774101 0.00200355 0.004499971 -0.006046414 0.005238354 0.004499971 -0.007034897 0.005613148 0.004499971 -0.006504118 0.00622034 0.004499971 -0.008275568 0.003537535 0.004499971 -0.0075109 0.004958331 0.004499971 -0.008918702 -0.001206159 0.004499971 -0.007990598 -3.83059e-4 0.004499971 -0.008917987 0.001210451 0.004499971 -0.007918357 -0.0011397 0.004499971 -0.008774518 -0.002001106 0.004499971 -0.006518006 0.004638135 0.004499971 -0.007773637 -0.001888573 0.004499971 -0.002974987 0.007426023 0.004499971 -0.003667354 0.007109761 0.004499971 -0.003902733 0.008109509 0.004499971 -0.004614651 0.007726788 0.004499971 -0.004326999 0.00672847 0.004499971 -0.005288362 0.007282078 0.004499971 -0.006928205 -0.003999948 0.004499971 -0.007926404 -0.004262506 0.004499971 -0.00727576 -0.0033257 0.004499971 -8.09186e-4 0.008963406 0.004499971 0 0.008999943 0.004499971 -0.001606404 0.008855402 0.004499971 -7.6298e-4 0.007963359 0.004499971 -0.00151503 0.007855057 0.004499971 -0.004943609 -0.006289422 0.004499971 -0.005923211 -0.006775796 0.004499971 -0.006505668 -0.006218969 0.004499971 -0.005518913 -0.005791306 0.004499971 -0.003906488 -0.008107841 0.004499971 -0.003663539 -0.007111549 0.004499971 0.002251803 0.007676303 0.004499971 0.003163933 0.008425295 0.004499971 -0.001513361 -0.007855534 0.004499971 -0.002396345 -0.008674979 0.004499971 0.004323184 0.006731092 0.004499971 0.004617869 0.007724702 0.004499971 8.09166e-4 -0.008963406 0.004499971 7.62509e-4 -0.007963418 0.004499971 0 -0.009000003 0.004499971 0.006045222 0.005239665 0.004499971 0.006505608 0.006218969 0.004499971 0.005518794 0.005791306 0.004499971 0.00225526 -0.007675468 0.004499971 -0.006045162 -0.005239605 0.004499971 -0.001607954 -0.008855044 -0.005499958 -7.84842e-4 -0.007961392 -0.005002856 -3.0001e-4 -0.007994353 -0.005499958 0 -0.007999956 -0.004999995 -0.001008272 -0.007936179 -0.004999995 -3.0001e-4 -0.007994353 -0.005002856 2.9999e-4 -0.007994353 -0.004999995 -0.006386578 0.004817724 -0.005499958 -0.006498813 0.004665017 -0.005499958 -0.006026744 0.005260944 -0.004999995 -0.002393424 -0.007633507 -0.005499958 -0.0023216 -0.00765568 -0.005499958 -0.003061473 -0.007391035 -0.004999995 -0.001706779 -0.007815718 -0.004999995 -0.005864977 0.005440711 -0.005002856 -0.005440711 0.005864977 -0.005002856 -0.005864977 0.005440711 -0.005499958 -0.005503296 0.005806028 -0.005499958 -0.004927873 0.006301999 -0.004999995 -0.003061473 -0.007391035 -0.005499958 -0.001559615 -0.007846415 -0.005499958 0.001515328 -0.007854998 -0.004999995 0.001109302 -0.007922649 -0.004999995 0.001906692 -0.007769346 -0.004999995 0.004147887 -0.006840586 -0.005499958 0.0036664 -0.007110297 -0.004999995 0.003432869 -0.00722599 -0.004999995 0.002683401 -0.007536411 -0.005499958 0.002975165 -0.007425963 -0.005499958 0.00225526 -0.007675468 -0.005499958 0.005521953 -0.005788385 -0.005002856 0.005440711 -0.005864977 -0.005002856 0.005864977 -0.005440711 -0.005499958 0.004945456 -0.00628817 -0.004999995 0.004817724 -0.006386578 -0.004999995 0.005440711 -0.005864977 -0.005499958 0.006929099 -0.003997981 -0.004999995 0.006841957 -0.004145503 -0.004999995 0.007226526 -0.003431558 -0.005499958 0.00651735 -0.004639267 -0.005499958 0.006046891 -0.005237519 -0.004999995 0.006386578 -0.004817724 -0.004999995 0.007770001 -0.001903951 -0.004999995 0.007922649 -0.001109302 -0.005499958 0.007918715 -0.0011366 -0.004999995 0.007536947 -0.002682149 -0.005499958 0.007560551 -0.002614319 -0.005002856 0.007994353 2.99996e-4 -0.004999995 0.007994353 2.99996e-4 -0.004999995 0.007922649 0.001109302 -0.005499958 0.007990837 -3.78864e-4 -0.005002856 0.007994353 -3.00004e-4 -0.004999995 0.00722599 0.003432869 -0.005499958 0.007276535 0.003324091 -0.004999995 0.007536411 0.002683401 -0.004999995 0.007769346 0.001906692 -0.005499958 0.00755912 0.002618551 -0.005499958 0.007774353 0.001886367 -0.004999995 0.006386578 0.004817724 -0.005499958 0.006045222 0.005239665 -0.005499958 0.006515324 0.00464189 -0.004999995 0.006840527 0.004147887 -0.005499958 0.006927192 0.004001498 -0.005499958 0.004945099 0.006288528 -0.004999995 0.004817724 0.006386578 -0.005499958 0.004323184 0.006731092 -0.005002856 0.005440711 0.005864977 -0.005499958 0.005518794 0.005791306 -0.005002856 0.005864977 0.005440711 -0.005499958 0.002251803 0.007676303 -0.005499958 0.002971708 0.007427453 -0.004999995 0.002682089 0.007536947 -0.004999995 0.003431558 0.007226526 -0.005499958 0.003664672 0.007111072 -0.004999995 0.004145503 0.006841957 -0.005002856 2.9999e-4 0.007994353 -0.005499958 0 0.007999956 -0.005499958 7.62509e-4 0.007963418 -0.005499958 0.001513063 0.007855534 -0.004999995 0.001109302 0.007922649 -0.005499958 -0.001508653 0.007856249 -0.004999995 -0.001906692 0.007769346 -0.005499958 -0.00224632 0.007678031 -0.005499958 -7.5958e-4 0.007963716 -0.004999995 -3.0001e-4 0.007994353 -0.004999995 -0.001109302 0.007922649 -0.004999995 -0.004817724 0.006386578 -0.005499958 -0.004310488 0.006739139 -0.004999995 -0.004147887 0.006840527 -0.004999995 -0.003432869 0.00722599 -0.005499958 -0.003652513 0.00711739 -0.005499958 -0.002962827 0.007430851 -0.004999995 -0.005440711 0.005864977 -0.005499958 -0.007261395 0.003357052 -0.004999995 -0.007226526 0.003431558 -0.004999995 -0.007536947 0.002682089 -0.004999995 -0.006842017 0.004145503 -0.004999995 -0.007922649 0.001109302 -0.005499958 -0.007911503 0.00118488 -0.004999995 -0.007770061 0.001903951 -0.005499958 -0.007763862 0.001928985 -0.005499958 -0.007988274 4.31978e-4 -0.004999995 -0.007994353 2.99996e-4 -0.005002856 -0.007994353 2.99996e-4 -0.005499958 -0.007993042 -3.27464e-4 -0.005002856 -0.007994353 -3.00004e-4 -0.004999995 -0.007922649 -0.001109302 -0.005499958 -0.007926702 -0.001080453 -0.005499958 -0.007788181 -0.001827836 -0.004999995 -0.007994353 -3.00004e-4 -0.004999995 -0.007769346 -0.001906692 -0.005499958 -0.007580995 -0.002554774 -0.005499958 -0.00730437 -0.003262519 -0.004999995 -0.007536411 -0.002683401 -0.004999995 -0.00722599 -0.003432869 -0.005499958 -0.006963133 -0.003938496 -0.004999995 -0.006840586 -0.004147887 -0.005499958 -0.006558954 -0.004580199 -0.005499958 -0.006095707 -0.005180597 -0.004999995 -0.006386578 -0.004817724 -0.004999995 -0.005864977 -0.005440711 -0.005002856 -0.005864977 -0.005440711 -0.005002856 -0.005440711 -0.005864977 -0.005499958 -0.005578756 -0.005733788 -0.005499958 -0.005009949 -0.006236672 -0.004999995 -0.005440711 -0.005864977 -0.004999995 -0.004898786 -0.006324648 -0.004999995 -0.004318296 -0.006734311 -0.005499958 -0.004398822 -0.006682038 -0.004999995 -0.003705263 -0.007090151 -0.005499958 -0.00374931 -0.007066786 -0.005499958 -0.007546305 0.002655088 -0.005499958 -0.006910383 0.004030406 -0.004999995 -0.002683401 0.007536411 -0.005002856 -3.0001e-4 0.007994353 -0.004999995 2.9999e-4 0.007994353 -0.004999995 0.001903951 0.007770001 -0.004999995 0.005864977 0.005440711 -0.004999995 0.005440711 0.005864977 -0.005499958 0.007918059 0.001140713 -0.005499958 0.007990837 3.81867e-4 -0.004999995 0.007994353 -3.00004e-4 -0.005499958 0.007774531 -0.001885414 -0.005499958 0.00727725 -0.00332278 -0.004999995 0.005864977 -0.005440711 -0.005499958 0.004326939 -0.006728649 -0.005499958 7.62509e-4 -0.007963418 -0.004999995 2.9999e-4 -0.007994353 -0.004499971 0.007990837 3.78856e-4 0.004499971 0.007990837 3.81867e-4 -0.004499971 0.007990837 -3.81875e-4 0.004499971 0 -0.007999956 0.004499971 -7.6298e-4 -0.007963359 -0.004499971 -7.62529e-4 -0.007963418 -0.004499971 0.007918715 0.0011366 0.004499971 0.007918059 0.001140713 0.004499971 0.007774353 0.001886367 -0.004499971 0.007774531 0.001885354 -0.004499971 0.007560551 0.002614319 0.004499971 0.00755912 0.002618551 -0.004499971 0.00727725 0.00332278 0.004499971 0.007276535 0.003324091 0.004499971 0.006927192 0.004001498 -0.004499971 0.006929099 0.003997921 -0.004499971 0.00651735 0.004639267 0.004499971 0.006515324 0.00464189 -0.004499971 0.006046891 0.005237519 0.004499971 0.006045222 0.005239665 0.004499971 0.005518794 0.005791306 -0.004499971 0.005521953 0.005788385 -0.004499971 0.004945456 0.00628817 0.004499971 0.004945099 0.006288528 -0.004499971 0.004326939 0.006728589 0.004499971 0.004323184 0.006731092 0.004499971 0.003664672 0.007111072 -0.004499971 0.0036664 0.007110297 -0.004499971 0.002975165 0.007425963 0.004499971 0.002971708 0.007427453 -0.004499971 0.00225526 0.007675409 0.004499971 0.002251803 0.007676303 0.004499971 0.001513063 0.007855534 -0.004499971 0.001515328 0.007854998 -0.004499971 7.62509e-4 0.007963418 0.004499971 7.62509e-4 0.007963418 -0.004499971 0 0.007999956 0.004499971 0 0.007999956 -0.004499971 0.007918059 -0.001140713 0.004499971 0.007990837 -3.78864e-4 0.004499971 0.007918715 -0.0011366 -0.004499971 0.007774353 -0.001886367 0.004499971 0.007774531 -0.001885414 -0.004499971 0.00755912 -0.00261861 -0.004499971 0.007276535 -0.003324091 0.004499971 0.007560551 -0.002614319 0.004499971 0.00727725 -0.00332278 -0.004499971 0.006927192 -0.004001498 0.004499971 0.006929099 -0.003997981 -0.004499971 0.006515324 -0.00464189 -0.004499971 0.006045222 -0.005239665 0.004499971 0.00651735 -0.004639267 0.004499971 0.006046891 -0.005237519 -0.004499971 0.005518794 -0.005791306 0.004499971 0.005521953 -0.005788385 -0.004499971 0.004945099 -0.006288528 -0.004499971 0.004323184 -0.006731092 0.004499971 0.004945456 -0.00628817 0.004499971 0.004326939 -0.006728649 -0.004499971 0.003664672 -0.007111072 0.004499971 0.0036664 -0.007110297 -0.004499971 0.002971708 -0.007427453 -0.004499971 0.002251803 -0.007676303 0.004499971 0.002975165 -0.007425963 0.004499971 0.00225526 -0.007675468 -0.004499971 0.001513063 -0.007855534 0.004499971 0.001515328 -0.007854998 -0.004499971 7.62509e-4 -0.007963418 -0.004499971 0 -0.007999956 0.004499971 7.62509e-4 -0.007963418 -0.004499971 -0.00225526 -0.007675468 -0.004499971 -0.001515388 -0.007854998 0.004499971 -0.001513361 -0.007855534 -0.004499971 -0.004326939 -0.006728649 -0.004499971 -0.0036664 -0.007110297 0.004499971 -0.003663539 -0.007111549 -0.004499971 -0.002975225 -0.007425963 0.004499971 -0.002251207 -0.007676482 0.004499971 -0.002972126 -0.007427334 -0.004499971 -0.005522012 -0.005788385 0.004499971 -0.005518913 -0.005791306 -0.004499971 -0.006046891 -0.005237519 0.004499971 -0.004323542 -0.006730914 0.004499971 -0.004943609 -0.006289422 -0.004499971 -0.004945516 -0.00628817 0.004499971 -0.006928205 -0.003999948 -0.004499971 -0.00727725 -0.00332278 -0.004499971 -0.006929159 -0.003997981 0.004499971 -0.006514966 -0.004642426 -0.004499971 -0.00651735 -0.004639267 0.004499971 -0.006045162 -0.005239605 -0.004499971 -0.007918715 -0.0011366 -0.004499971 -0.007774531 -0.001885414 0.004499971 -0.007773637 -0.001888573 -0.004499971 -0.00756061 -0.002614319 0.004499971 -0.00727576 -0.0033257 0.004499971 -0.007559776 -0.00261712 -0.004499971 -0.007990837 3.81867e-4 0.004499971 -0.007990956 3.78865e-4 -0.004499971 -0.007918059 0.001140713 0.004499971 -0.007918357 -0.0011397 0.004499971 -0.007990598 -3.83059e-4 -0.004499971 -0.007990837 -3.78864e-4 0.004499971 -0.007560193 0.002615392 -0.004499971 -0.007276535 0.003324091 -0.004499971 -0.00755912 0.002618551 0.004499971 -0.007774889 0.001883864 -0.004499971 -0.007774353 0.001886367 0.004499971 -0.007918596 0.0011366 -0.004499971 -0.006045281 0.005239665 -0.004499971 -0.006515324 0.00464189 0.004499971 -0.006518006 0.004638135 -0.004499971 -0.006927251 0.004001498 0.004499971 -0.007277965 0.003320932 0.004499971 -0.006928205 0.003999948 -0.004499971 -0.004945099 0.006288528 -0.004499971 -0.005518853 0.005791306 0.004499971 -0.00552237 0.005787849 0.004499971 -0.006046414 0.005238354 0.004499971 -0.004946231 0.006287574 -0.004499971 -0.004323244 0.006731092 0.004499971 -0.004326999 0.00672847 -0.004499971 -0.003664672 0.007111072 -0.004499971 -0.002971708 0.007427453 0.004499971 -0.003667354 0.007109761 0.004499971 -0.002974987 0.007426023 -0.004499971 -0.002251803 0.007676303 0.004499971 -0.002255976 0.00767517 -0.004499971 -0.001513123 0.007855534 -0.004499971 -7.62529e-4 0.007963418 0.004499971 -0.00151503 0.007855057 0.004499971 -7.6298e-4 0.007963359 -0.005499958 0.006505608 0.006218969 -0.005499958 0.007037937 0.005609214 -0.005499958 0.006045222 0.005239665 -0.005499958 0.004945456 -0.00628817 -0.005499958 0.005919814 -0.006778895 -0.005499958 0.005288362 -0.007282137 -0.005499958 0.007560551 -0.002614319 -0.005499958 0.007774531 -0.001885414 -0.005499958 0.008558511 -0.002783536 -0.005499958 0.0075109 -0.004958331 -0.005499958 0.006929099 -0.003997981 -0.005499958 0.00792396 -0.004266977 -0.005499958 0.006046891 -0.005237519 -0.005499958 0.007034897 -0.005613148 -0.005499958 0.006504118 -0.00622034 -0.005499958 0.00727725 -0.00332278 -0.005499958 0.008275568 -0.003537535 -0.005499958 0.007918715 -0.0011366 -0.005499958 0.007990837 -3.78864e-4 -0.005499958 0.008917987 -0.001210451 -0.005499958 0.008774101 -0.00200361 -0.005499958 0.008918702 0.001206159 -0.005499958 0.008990764 4.01668e-4 -0.005499958 0.007990837 3.81867e-4 -0.005499958 0.00651735 -0.004639267 -0.005499958 0.005521953 -0.005788385 -0.005499958 0.008990764 -4.0525e-4 -0.005499958 0.008560061 0.002778947 -0.005499958 0.008774518 0.002001106 -0.005499958 0.007774353 0.001886367 -0.005499958 0.007918059 0.001140713 -0.005499958 0.003902673 -0.008109509 -0.005499958 0.0036664 -0.007110297 -0.005499958 0.004614651 -0.007726788 -0.005499958 0.004326939 -0.006728649 -0.005499958 0.003161251 -0.008426487 -0.005499958 0.002975165 -0.007425963 -0.005499958 0.00755912 0.002618551 -0.005499958 0.008275926 0.003536522 -0.005499958 0.002391755 -0.008676111 -0.005499958 0.001606404 -0.008855462 -0.005499958 0.001515328 -0.007854998 -0.005499958 0.007276535 0.003324091 -0.005499958 0.007926344 0.004262506 -0.005499958 0.005291044 0.007280349 -0.005499958 0.004323184 0.006731092 -0.005499958 0.004617869 0.007724702 -0.005499958 0 -0.007999956 -0.005499958 -8.09684e-4 -0.008963286 -0.005499958 -7.84842e-4 -0.007961392 -0.005499958 0.002251803 0.007676303 -0.005499958 0.003163933 0.008425295 -0.005499958 0.002971708 0.007427453 -0.005499958 0.003664672 0.007111072 -0.005499958 0.002396345 0.008674979 -0.005499958 0.001513063 0.007855534 -0.005499958 0.001607954 0.008855044 -0.005499958 7.62509e-4 0.007963418 -0.005499958 8.09166e-4 0.008963406 -0.005499958 -0.001606762 0.008855402 -0.005499958 -7.5958e-4 0.007963716 -0.005499958 -0.001508653 0.007856249 -0.005499958 0 0.007999956 -0.005499958 -8.09684e-4 0.008963286 -0.005499958 0 0.008999943 -0.005499958 -0.005920767 0.00677818 -0.005499958 -0.004927873 0.006301999 -0.005499958 -0.005503296 0.005806028 -0.005499958 -0.003652513 0.00711739 -0.005499958 -0.003902077 0.008109807 -0.005499958 -0.002962827 0.007430851 -0.005499958 -0.008274376 0.003539741 -0.005499958 -0.007924675 0.004265964 -0.005499958 -0.007261395 0.003357052 -0.005499958 -0.007509291 0.004960358 -0.005499958 -0.007035732 0.005612254 -0.005499958 -0.006498813 0.004665017 -0.005499958 -0.008773446 0.002005279 -0.005499958 -0.007763862 0.001928985 -0.005499958 -0.007911503 0.00118488 -0.005499958 -0.006910383 0.004030406 -0.005499958 -0.006026744 0.005260944 -0.005499958 -0.006502866 0.006221532 -0.005499958 -0.004310488 0.006739139 -0.005499958 -0.005287468 0.007282733 -0.005499958 -0.004615485 0.007726371 -0.005499958 -0.008558988 0.002782583 -0.005499958 -0.007546305 0.002655088 -0.005499958 -0.008918225 0.001209795 -0.005499958 -0.007988274 4.31978e-4 -0.005499958 -0.008990526 4.06403e-4 -0.005499958 -0.007993042 -3.27464e-4 -0.005499958 -0.008918583 -0.001205563 -0.005499958 -0.007926702 -0.001080453 -0.005499958 -0.008774697 -0.002000629 -0.005499958 -0.008990943 -4.01876e-4 -0.005499958 -0.00224632 0.007678031 -0.005499958 -0.003161907 0.008426249 -0.005499958 -0.002391338 0.00867623 -0.005499958 -0.007580995 -0.002554774 -0.005499958 -0.008276522 -0.003535091 -0.005499958 -0.008559942 -0.002778887 -0.005499958 -0.007788181 -0.001827836 -0.005499958 -0.00730437 -0.003262519 -0.005499958 -0.007926106 -0.004262864 -0.005499958 -0.006095707 -0.005180597 -0.005499958 -0.0065068 -0.006217598 -0.005499958 -0.007037401 -0.005609869 -0.005499958 -0.005009949 -0.006236672 -0.005499958 -0.005292117 -0.007279455 -0.005499958 -0.005922436 -0.006776511 -0.005499958 -0.005578756 -0.005733788 -0.005499958 -0.004398822 -0.006682038 -0.005499958 -0.004617035 -0.007725298 -0.005499958 -0.00374931 -0.007066786 -0.005499958 -0.003061473 -0.007391035 -0.005499958 -0.003907382 -0.008107364 -0.005499958 -0.0023216 -0.00765568 -0.005499958 -0.003163099 -0.008425712 -0.005499958 0.003906488 0.008107841 -0.005499958 -0.00239706 -0.00867474 -0.005499958 -0.001559615 -0.007846415 -0.005499958 0.005518794 0.005791306 -0.005499958 0.005923151 0.006775796 -0.005499958 0.004945099 0.006288528 -0.005499958 8.09166e-4 -0.008963406 -0.005499958 7.62509e-4 -0.007963418 -0.005499958 0 -0.009000003 -0.005499958 0.007511258 0.004957854 -0.005499958 0.006927192 0.004001498 -0.005499958 0.006515324 0.00464189 -0.005499958 0.00225526 -0.007675468 -0.005499958 -0.006963133 -0.003938496 -0.005499958 -0.00751239 -0.004955947 -0.005499958 -0.006558954 -0.004580199 -0.005499958 -0.001607418 -0.008855223 -0.004499971 0.007511258 -0.004957914 -0.004499971 0.006515324 -0.00464189 -0.004499971 0.007037937 -0.005609214 -0.004499971 0.00792396 0.004266977 -0.004499971 0.006929099 0.003997921 -0.004499971 0.00727725 0.00332278 -0.004499971 0.007560551 0.002614319 -0.004499971 0.007774531 0.001885354 -0.004499971 0.008558511 0.002783536 -0.004499971 0.0075109 0.004958331 -0.004499971 0.006046891 0.005237519 -0.004499971 0.007034897 0.005613148 -0.004499971 0.006504118 0.00622034 -0.004499971 0.007918715 0.0011366 -0.004499971 0.008774101 0.00200355 -0.004499971 0.008275568 0.003537535 -0.004499971 0.008990764 4.05242e-4 -0.004499971 0.007990837 3.78856e-4 -0.004499971 0.008990764 -4.01676e-4 -0.004499971 0.008917987 0.001210451 -0.004499971 0.00651735 0.004639267 -0.004499971 0.007990837 -3.81875e-4 -0.004499971 0.008918702 -0.001206159 -0.004499971 0.005521953 0.005788385 -0.004499971 0.005919814 0.006778895 -0.004499971 0.007918059 -0.001140713 -0.004499971 0.008774518 -0.002001106 -0.004499971 0.005288362 0.007282078 -0.004499971 0.004945456 0.00628817 -0.004499971 0.007774353 -0.001886367 -0.004499971 0.008560061 -0.002778947 -0.004499971 0.004614651 0.007726788 -0.004499971 0.004326939 0.006728589 -0.004499971 0.008275926 -0.003536522 -0.004499971 0.00755912 -0.00261861 -0.004499971 0.003902673 0.008109509 -0.004499971 0.0036664 0.007110297 -0.004499971 0.007276535 -0.003324091 -0.004499971 0.007926344 -0.004262506 -0.004499971 0.003161251 0.008426487 -0.004499971 0.002975165 0.007425963 -0.004499971 0.006927192 -0.004001498 -0.004499971 0.005923151 -0.006775796 -0.004499971 0.004945099 -0.006288528 -0.004499971 0.005291044 -0.007280349 -0.004499971 0.002391755 0.008676111 -0.004499971 0.001606404 0.008855402 -0.004499971 0.001515328 0.007854998 -0.004499971 0.002971708 -0.007427453 -0.004499971 0.003906488 -0.008107841 -0.004499971 0.003664672 -0.007111072 -0.004499971 -8.09684e-4 0.008963286 -0.004499971 -7.62529e-4 0.007963418 -0.004499971 0 0.007999956 -0.004499971 -0.002251803 0.007676303 -0.004499971 -0.003163099 0.008425712 -0.004499971 -0.002971708 0.007427453 -0.004499971 -0.004617035 0.007725298 -0.004499971 -0.005292117 0.007279455 -0.004499971 -0.004323244 0.006731092 -0.004499971 0.001607954 -0.008855044 -0.004499971 0.002396345 -0.008674979 -0.004499971 0.001513063 -0.007855534 -0.004499971 -0.00751239 0.004955947 -0.004499971 -0.006515324 0.00464189 -0.004499971 -0.007037401 0.005609869 -0.004499971 8.09166e-4 -0.008963406 -0.004499971 7.62509e-4 -0.007963418 -0.004499971 0 -0.007999956 -0.004499971 -0.00755912 0.002618551 -0.004499971 -0.008276522 0.003535091 -0.004499971 -0.008559942 0.002778887 -0.004499971 -0.003161907 -0.008426249 -0.004499971 -0.002391338 -0.00867623 -0.004499971 -0.00225526 -0.007675468 -0.004499971 -0.008990526 -4.06411e-4 -0.004499971 -0.007990837 -3.78864e-4 -0.004499971 -0.008990943 4.01868e-4 -0.004499971 -0.005522012 -0.005788385 -0.004499971 -0.005920767 -0.00677818 -0.004499971 -0.004945516 -0.00628817 -0.004499971 -0.008558988 -0.002782583 -0.004499971 -0.00756061 -0.002614319 -0.004499971 -0.007774531 -0.001885414 -0.004499971 -0.007924675 -0.004265964 -0.004499971 -0.006929159 -0.003997981 -0.004499971 -0.00727725 -0.00332278 -0.004499971 -0.007918715 -0.0011366 -0.004499971 -0.008773446 -0.002005279 -0.004499971 -0.006046891 -0.005237519 -0.004499971 -0.007035732 -0.005612254 -0.004499971 -0.006502866 -0.006221532 -0.004499971 -0.008274376 -0.003539741 -0.004499971 -0.007509291 -0.004960358 -0.004499971 -0.008918583 0.001205563 -0.004499971 -0.007990837 3.81867e-4 -0.004499971 -0.008918225 -0.001209795 -0.004499971 -0.007918059 0.001140713 -0.004499971 -0.008774697 0.002000629 -0.004499971 -0.00651735 -0.004639267 -0.004499971 -0.007774353 0.001886367 -0.004499971 -0.002975225 -0.007425963 -0.004499971 -0.0036664 -0.007110297 -0.004499971 -0.003902077 -0.008109807 -0.004499971 -0.004615485 -0.007726371 -0.004499971 -0.004326939 -0.006728649 -0.004499971 -0.005287468 -0.007282733 -0.004499971 -0.006927251 0.004001498 -0.004499971 -0.007926106 0.004262864 -0.004499971 -0.007276535 0.003324091 -0.004499971 -8.09684e-4 -0.008963286 -0.004499971 0 -0.009000003 -0.004499971 -0.001606762 -0.008855402 -0.004499971 -7.62529e-4 -0.007963418 -0.004499971 -0.001515388 -0.007854998 -0.004499971 -0.004945099 0.006288528 -0.004499971 -0.005922436 0.006776511 -0.004499971 -0.0065068 0.006217598 -0.004499971 -0.005518853 0.005791306 -0.004499971 -0.003907382 0.008107364 -0.004499971 -0.003664672 0.007111072 -0.004499971 0.002251803 -0.007676303 -0.004499971 0.003163933 -0.008425295 -0.004499971 -0.001513123 0.007855534 -0.004499971 -0.00239706 0.008674681 -0.004499971 0.004323184 -0.006731092 -0.004499971 0.004617869 -0.007724702 -0.004499971 8.09166e-4 0.008963406 -0.004499971 7.62509e-4 0.007963418 -0.004499971 0 0.008999943 -0.004499971 0.006045222 -0.005239665 -0.004499971 0.006505608 -0.006218969 -0.004499971 0.005518794 -0.005791306 -0.004499971 0.00225526 0.007675409 -0.004499971 -0.006045281 0.005239665 -0.004499971 -0.001607418 0.008855223 -0.004499971 0.008990764 -4.01676e-4 -0.005499958 0.008990764 4.01668e-4 -0.004499971 0.008990764 4.05242e-4 -0.004499971 -8.09684e-4 -0.008963286 -0.005499958 0 -0.009000003 -0.004499971 0 -0.009000003 -0.004499971 0.008917987 0.001210451 -0.005499958 0.008918702 0.001206159 -0.005499958 0.008774518 0.002001106 -0.004499971 0.008774101 0.00200355 -0.005499958 0.008560061 0.002778947 -0.004499971 0.008558511 0.002783536 -0.004499971 0.008275568 0.003537535 -0.005499958 0.008275926 0.003536522 -0.005499958 0.007926344 0.004262506 -0.004499971 0.00792396 0.004266977 -0.005499958 0.007511258 0.004957854 -0.004499971 0.0075109 0.004958331 -0.004499971 0.007034897 0.005613148 -0.005499958 0.007037937 0.005609214 -0.005499958 0.006505608 0.006218969 -0.004499971 0.006504118 0.00622034 -0.005499958 0.005923151 0.006775796 -0.004499971 0.005919814 0.006778895 -0.004499971 0.005288362 0.007282078 -0.005499958 0.005291044 0.007280349 -0.005499958 0.004617869 0.007724702 -0.004499971 0.004614651 0.007726788 -0.005499958 0.003906488 0.008107841 -0.004499971 0.003902673 0.008109509 -0.004499971 0.003161251 0.008426487 -0.005499958 0.003163933 0.008425295 -0.005499958 0.002396345 0.008674979 -0.004499971 0.002391755 0.008676111 -0.005499958 0.001607954 0.008855044 -0.004499971 0.001606404 0.008855402 -0.004499971 8.09166e-4 0.008963406 -0.005499958 8.09166e-4 0.008963406 -0.005499958 0 0.008999943 -0.004499971 0 0.008999943 -0.005499958 0.008990764 -4.0525e-4 -0.004499971 0.008918702 -0.001206159 -0.005499958 0.008917987 -0.001210451 -0.005499958 0.008774101 -0.00200361 -0.004499971 0.008774518 -0.002001106 -0.004499971 0.008560061 -0.002778947 -0.005499958 0.008558511 -0.002783536 -0.004499971 0.008275926 -0.003536522 -0.005499958 0.008275568 -0.003537535 -0.005499958 0.00792396 -0.004266977 -0.004499971 0.007926344 -0.004262506 -0.004499971 0.007511258 -0.004957914 -0.005499958 0.0075109 -0.004958331 -0.004499971 0.007037937 -0.005609214 -0.005499958 0.007034897 -0.005613148 -0.005499958 0.006504118 -0.00622034 -0.004499971 0.006505608 -0.006218969 -0.004499971 0.005923151 -0.006775796 -0.005499958 0.005919814 -0.006778895 -0.004499971 0.005291044 -0.007280349 -0.005499958 0.005288362 -0.007282137 -0.005499958 0.004614651 -0.007726788 -0.004499971 0.004617869 -0.007724702 -0.004499971 0.003906488 -0.008107841 -0.005499958 0.003902673 -0.008109509 -0.004499971 0.003163933 -0.008425295 -0.005499958 0.003161251 -0.008426487 -0.005499958 0.002391755 -0.008676111 -0.004499971 0.002396345 -0.008674979 -0.004499971 0.001607954 -0.008855044 -0.005499958 0.001606404 -0.008855462 -0.004499971 8.09166e-4 -0.008963406 -0.005499958 8.09166e-4 -0.008963406 -0.004499971 -0.003161907 -0.008426249 -0.005499958 -0.00239706 -0.00867474 -0.004499971 -0.002391338 -0.00867623 -0.004499971 -0.001606762 -0.008855402 -0.005499958 -0.001607418 -0.008855223 -0.005499958 -8.09684e-4 -0.008963286 -0.005499958 -0.004617035 -0.007725298 -0.004499971 -0.004615485 -0.007726371 -0.004499971 -0.005287468 -0.007282733 -0.005499958 -0.003163099 -0.008425712 -0.004499971 -0.003902077 -0.008109807 -0.005499958 -0.003907382 -0.008107364 -0.004499971 -0.006502866 -0.006221532 -0.004499971 -0.007035732 -0.005612254 -0.005499958 -0.0065068 -0.006217598 -0.004499971 -0.005920767 -0.00677818 -0.005499958 -0.005922436 -0.006776511 -0.005499958 -0.005292117 -0.007279455 -0.004499971 -0.008274376 -0.003539741 -0.005499958 -0.007926106 -0.004262864 -0.004499971 -0.007924675 -0.004265964 -0.005499958 -0.00751239 -0.004955947 -0.005499958 -0.007037401 -0.005609869 -0.004499971 -0.007509291 -0.004960358 -0.005499958 -0.008774697 -0.002000629 -0.004499971 -0.008773446 -0.002005279 -0.004499971 -0.008918225 -0.001209795 -0.005499958 -0.008276522 -0.003535091 -0.004499971 -0.008558988 -0.002782583 -0.005499958 -0.008559942 -0.002778887 -0.004499971 -0.008990943 4.01868e-4 -0.004499971 -0.008918583 0.001205563 -0.005499958 -0.008990526 4.06403e-4 -0.004499971 -0.008990526 -4.06411e-4 -0.005499958 -0.008990943 -4.01876e-4 -0.005499958 -0.008918583 -0.001205563 -0.004499971 -0.008276522 0.003535091 -0.005499958 -0.008558988 0.002782583 -0.004499971 -0.008559942 0.002778887 -0.005499958 -0.008773446 0.002005279 -0.005499958 -0.008918225 0.001209795 -0.004499971 -0.008774697 0.002000629 -0.005499958 -0.007509291 0.004960358 -0.004499971 -0.00751239 0.004955947 -0.004499971 -0.007037401 0.005609869 -0.005499958 -0.008274376 0.003539741 -0.004499971 -0.007926106 0.004262864 -0.005499958 -0.007924675 0.004265964 -0.005499958 -0.006502866 0.006221532 -0.004499971 -0.005922436 0.006776511 -0.005499958 -0.005920767 0.00677818 -0.004499971 -0.0065068 0.006217598 -0.005499958 -0.007035732 0.005612254 -0.005499958 -0.005287468 0.007282733 -0.004499971 -0.005292117 0.007279455 -0.004499971 -0.004617035 0.007725298 -0.005499958 -0.004615485 0.007726371 -0.004499971 -0.003907382 0.008107364 -0.005499958 -0.003902077 0.008109807 -0.005499958 -0.003161907 0.008426249 -0.004499971 -0.003163099 0.008425712 -0.004499971 -0.00239706 0.008674681 -0.005499958 -0.002391338 0.00867623 -0.004499971 -0.001607418 0.008855223 -0.005499958 -0.001606762 0.008855402 -0.005499958 -8.09684e-4 0.008963286 -0.004499971 -8.09684e-4 0.008963286 + + + + + + + + + + 0 0.7070695 -0.7071442 0 0.7071077 -0.7071059 0 -0.7071824 0.7070313 0 -0.7071059 0.7071077 0 0 -1 0 0 1 0 -0.7070686 -0.707145 0 -0.7071059 -0.7071077 0 0.7070695 0.7071442 0 0.7071077 0.7071059 0 -1 0 0 1 0 0 1 0 0 -0.7070695 0.7071441 0 -0.7071077 0.7071059 0 0.7070686 -0.707145 0 0.7071059 -0.7071077 0 0.7071824 0.7070313 0 0.7071059 0.7071077 0 -0.7070695 -0.7071441 0 -0.7071077 -0.7071059 0 1 0 0.01336711 0 -0.9999107 0.01736509 0.1116374 -0.9935973 -0.002655088 -0.9781607 0.2078335 0.009186267 -0.9886385 0.1500323 0.006683647 -0.96788 0.2513241 0.01190239 -0.9966009 0.0815165 0.02264511 -0.9997436 0 0.002349913 -0.9158127 0.4015988 -0.002807676 -0.954776 0.2973127 -0.003082394 -0.8853592 0.4648975 0.0122078 -0.8432856 0.5373271 0.01971554 -0.7945732 0.6068482 -0.0032655 -0.8383486 0.545125 2.13632e-4 -0.4762477 0.8793112 -8.24005e-4 -0.5436294 0.839325 0.007294118 -0.6079187 0.7939658 0 -0.6158666 0.7878506 0.001068174 -0.3249397 0.9457342 -0.00125122 -0.4650441 0.8852867 -0.002014219 -0.2974697 0.9547292 0.01416075 -0.1764606 0.9842059 0.01736509 -0.1116374 0.9935973 -0.002471983 -0.2078629 0.978155 0.01336711 0 0.9999107 -0.002655088 -0.9781931 -0.2076814 -0.002807736 -0.9548308 -0.2971372 0.006683647 -0.96788 -0.2513241 0.009186267 -0.9886385 -0.1500323 0.002349913 -0.9158127 -0.4015988 -0.003082394 -0.8854543 -0.4647163 0.01181089 -0.7359387 0.6769452 0.01495432 -0.6982764 0.7156721 0.00137335 -0.632815 0.7743019 -0.0032655 -0.8384455 -0.5449758 0.0122078 -0.8432856 -0.5373271 0.01971554 -0.7945732 -0.6068482 0.01495432 -0.6982764 -0.7156721 0.01181089 -0.7359387 -0.6769452 0.01190239 -0.9966009 -0.0815165 0.007294118 -0.6079187 -0.7939658 -7.93494e-4 -0.5437572 -0.8392422 2.13632e-4 -0.4762477 -0.8793112 -0.001220703 -0.4652014 -0.8852041 0.001068174 -0.3249397 -0.9457342 0 -0.6158744 -0.7878444 0.00137335 -0.6328483 -0.7742747 -0.002014219 -0.2976539 -0.9546717 0.01416075 -0.1764606 -0.9842059 -0.00250256 -0.2080212 -0.9781212 0.01736509 -0.1116374 -0.9935973 -0.002014219 0.2974697 -0.9547292 0.01416075 0.1764606 -0.9842059 -0.002471983 0.2078629 -0.978155 2.13632e-4 0.4762477 -0.8793112 0.001068174 0.3249397 -0.9457342 -0.00125122 0.4650441 -0.8852867 0 0.6158697 -0.7878482 -8.24005e-4 0.5436294 -0.839325 0.01971554 0.7945732 -0.6068482 -0.0032655 0.8383486 -0.545125 0.0122078 0.8432856 -0.5373271 0.007294118 0.6079187 -0.7939658 -0.003082394 0.8853592 -0.4648975 -0.002807676 0.954776 -0.2973127 0.002349913 0.9158127 -0.4015988 -0.002807736 0.9548308 0.2971372 0.002349913 0.9158127 0.4015988 0.006683647 0.96788 0.2513241 -0.002655088 0.9781607 -0.2078335 0.009186267 0.9886385 -0.1500323 0.006683647 0.96788 -0.2513241 0.009186267 0.9886385 0.1500323 -0.002655088 0.9781931 0.2076814 0.007294118 0.6079187 0.7939658 0.01495432 0.6982764 0.7156721 0.00137335 0.6328483 0.7742747 -0.001220703 0.4652014 0.8852041 0.001068174 0.3249397 0.9457342 2.13632e-4 0.4762477 0.8793112 -0.0032655 0.8384455 0.5449758 0.01971554 0.7945732 0.6068482 0.0122078 0.8432856 0.5373271 -0.003082394 0.8854543 0.4647163 -0.002014219 0.2976539 0.9546717 -7.93494e-4 0.5437572 0.8392422 0.01416075 0.1764606 0.9842059 0.01736509 0.1116374 0.9935973 -0.00250256 0.2080212 0.9781212 0.01181089 0.7359387 0.6769452 0 0.6158744 0.7878444 0.01190239 0.9966009 0.0815165 0.01190239 0.9966009 -0.0815165 0.02264511 0.9997436 0 0.01181089 0.7359387 -0.6769452 0.01495432 0.6982764 -0.7156721 0.001373291 0.6328333 -0.7742869 1 0 0 1 -7.36755e-7 0 1 -1.47351e-6 0 1 -1.47353e-6 0 1 1.47353e-6 0 1 7.36756e-7 0 1 7.36753e-6 0 1 5.89401e-6 0 1 -5.98615e-6 0 1 7.36545e-6 0 1 -7.36842e-6 0 1 -3.68431e-6 0 1 -1.47348e-6 0 1 -2.94702e-6 0 1 -4.14424e-6 0 1 1.38142e-6 0 1 1.8419e-6 0 1 7.36548e-6 0 1 -5.52568e-6 0 1 -7.36753e-6 0 1 2.76283e-6 0 1 3.68379e-6 0 1 9.20945e-7 0 1 -1.84189e-6 0 1 -1.47351e-6 0 1 -2.947e-6 0 1 2.94702e-6 0 1 -2.94703e-6 0 1 -2.30171e-6 0 1 1.84152e-6 0 1 4.14312e-6 0 1 3.68315e-6 0 1 9.20813e-7 0 1 1.84171e-6 0 1 3.68366e-7 0 1 9.20932e-7 0 1 -9.2102e-7 0 1 7.36736e-7 0 1 1.10509e-6 0 1 3.68374e-6 0 1 -7.36755e-7 0 1 -2.94701e-6 0 1 4.02802e-6 0 1 4.84098e-6 0 1 4.58672e-7 0 1 -5.53305e-7 0 1 -5.60593e-7 0 1 -8.18066e-7 0 1 8.10453e-7 0 1 8.15427e-7 0 1 1.45916e-6 0 1 -2.73834e-7 0 1 -8.17214e-7 0 0.8882158 -0.3249701 -0.3247571 0.8882184 -0.3248603 -0.3248598 0.8882161 -0.3247557 -0.3249706 1 8.15255e-7 0 1 0 0 1 3.05786e-7 0 1 0 0 1 -3.65668e-7 0 1 4.07898e-7 0 1 -2.552e-7 0 1 -1.82394e-7 0 1 -4.60381e-7 0 0.8882152 -0.4594278 1.57293e-4 0.8882187 -0.459421 0 0.8882152 -0.4594277 -1.57293e-4 1 -2.03459e-7 0 1 -4.05227e-7 0 1 7.3774e-7 0 1 2.04303e-7 0 1 -2.03852e-7 0 0.8882156 -0.3247574 0.3249704 0.8882188 -0.3248593 0.3248597 0.8882152 -0.3249719 0.3247569 1 -4.07714e-7 0 1 -8.15428e-7 0 1 8.91315e-7 0 1 8.15417e-7 0 1 1.74945e-6 0 1 5.47181e-7 0 0.8882152 1.56316e-4 0.4594278 0.8882187 0 0.459421 0.8882152 -1.56316e-4 0.4594278 1 -8.18066e-7 0 1 0 0 1 -4.58672e-7 0 1 -1.47548e-6 0 1 8.15427e-7 0 1 8.10453e-7 0 1 -8.17214e-7 0 1 1.45916e-6 0 1 2.73834e-7 0 0.888215 0.3249722 0.3247572 0.8882187 0.3248594 0.3248599 0.8882155 0.324757 0.324971 1 0 0 1 -4.07714e-7 0 1 4.60381e-7 0 0.8882153 0.4594277 -1.56316e-4 0.8882187 0.4594209 0 0.8882153 0.4594277 1.56316e-4 1 -2.03459e-7 0 1 -7.3774e-7 0 1 2.03852e-7 0 1 0 0 0.8882161 0.3247553 -0.3249712 0.8882184 0.3248603 -0.3248598 0.8882154 0.3249707 -0.3247577 1 -9.31783e-7 0 1 -4.65912e-7 0 1 1.18952e-6 0 0.8882152 -1.60224e-4 -0.4594278 0.8882187 0 -0.459421 0.8882152 1.60224e-4 -0.4594278 0 0.3246934 -0.9458194 0 0.1646217 -0.9863569 0 0.3247846 -0.945788 0 0.164587 -0.9863626 0 0.6143611 -0.7890251 0 0.735886 -0.6771055 0 0.7357248 -0.6772807 0 0.6142068 -0.7891451 0 0.4759479 -0.8794736 0 0.4760679 -0.8794087 0 0.9694057 -0.2454643 0 0.9158973 -0.4014127 0 0.969482 -0.245163 0 0.9157767 -0.401688 0 0.8371744 -0.546936 0 0.8373178 -0.5467164 0 0.9693129 0.2458302 0 0.9694057 0.2454643 0 0.9965563 0.08291918 0 0.9966145 -0.08221703 0 0.9965868 0.08255296 0 0.9965868 -0.08255296 0 0.8369939 0.5472124 0 0.7355343 0.6774875 0 0.7357248 0.6772807 0 0.9157767 0.401688 0 0.9156397 0.4020001 0 0.8371744 0.546936 0 0.3246934 0.9458194 0 0.4757679 0.8795709 0 0.3246294 0.9458414 0 0.4759479 0.8794736 0 0.6142068 0.7891451 0 0.6140188 0.7892915 0 -0.164587 0.9863626 0 0.1646217 0.9863569 0 0.164587 0.9863626 0 -0.4759479 0.8794736 0 -0.6142068 0.7891451 0 -0.3246934 0.9458194 0 -0.9157767 0.401688 0 -0.8371744 0.546936 0 -0.7357248 0.6772807 0 -0.9965868 -0.08255296 0 -0.9965868 0.08255296 0 -0.9694057 0.2454643 0 -0.9694057 -0.2454643 0 -0.9157767 -0.401688 0 -0.8371744 -0.546936 0 -0.7357248 -0.6772807 0 -0.6142068 -0.7891451 0 -0.4759479 -0.8794736 0 -0.3246934 -0.9458194 0 -0.164587 -0.9863626 0.002868831 -0.9903885 -0.1382839 0.009338796 -0.9966284 -0.0815162 -0.001495361 -0.99839 -0.0567038 -0.002288937 -0.04687768 -0.998898 -0.00753808 3.05186e-5 -0.9999716 -0.002319455 0.04696905 -0.9988937 -0.002960324 -0.9995279 -0.03058004 -0.001739561 -0.9990243 0.04413115 0.001922667 -0.9903782 0.138374 1.22076e-4 -0.991046 0.1335209 -6.10376e-5 -0.9983316 0.05774158 -0.00100708 -0.9741138 0.2260562 0 -0.9961029 0.08819931 -0.001403868 -0.9485052 0.3167584 0.003143429 -0.9710835 0.2387195 0.003967404 -0.9416862 0.3364691 -0.001770079 -0.91421 0.4052372 0.004242122 -0.9026955 0.4302591 -0.001678526 -0.8716135 0.4901911 -0.001586973 -0.8209136 0.5710504 0.004394769 -0.8545137 0.5194103 0.004364252 -0.7977492 0.6029738 -0.001525938 -0.7627112 0.6467374 -0.003173947 -0.7357503 0.6772456 0.01211607 -0.7595003 0.6503942 -0.001068115 -0.669743 0.7425922 -0.007110893 -0.6970853 0.7169531 0.004425287 -0.6503727 0.7596024 0.001434385 -0.6105962 0.7919408 -0.004303157 -0.6270461 0.7789703 0.00125128 -0.5379607 0.842969 -0.003357112 -0.5503582 0.834922 -0.002563595 -0.4685928 0.8834106 2.13634e-4 -0.4616333 0.8870709 -0.002197325 -0.382403 0.9239931 0 -0.3826816 0.9238803 -0.001159667 -0.9886062 -0.1505203 0.001678466 -0.9711629 -0.2384113 1.22076e-4 -0.9701353 -0.2425643 0.001648008 -0.9422884 -0.3347985 -1.22075e-4 -0.943885 -0.3302743 -0.00100708 -0.9086757 -0.4175013 0.003143429 -0.9030805 -0.4294599 -0.001464903 -0.8652156 -0.5013978 0.003967404 -0.8547083 -0.5190936 -0.001709043 -0.8140127 -0.5808447 0.004242181 -0.7975913 -0.6031835 -0.001586973 -0.7550151 -0.6557055 0.01229929 -0.7601183 -0.6496683 -0.00564599 -0.6870113 -0.7266248 -2.44149e-4 -0.6673817 -0.7447159 -0.003326535 -0.7317886 -0.6815236 -0.00149542 -0.6181969 -0.786022 0.003997981 -0.6013226 -0.7989964 0.004730403 -0.6458721 -0.763431 0.004181146 -0.5173966 -0.8557355 -0.001831114 -0.5411037 -0.8409539 -0.001617491 -0.4587604 -0.8885585 0.004455804 -0.4280021 -0.9037668 -0.001586973 -0.371969 -0.9282439 0.004425287 -0.3347048 -0.9423127 -0.001312255 -0.2816869 -0.9595056 0.004516839 -0.2380208 -0.9712496 -0.001281797 -0.1886684 -0.9820401 -0.001403868 -0.0939995 -0.9955713 0.004455804 -0.1389542 -0.9902888 0.01052904 -0.07794541 -0.9969021 0.00451672 0.13889 -0.9902976 0.01049852 0.07794547 -0.9969024 -0.001403808 0.09424155 -0.9955485 -0.001617491 0.4600822 -0.8878749 0.004425227 0.4279654 -0.9037843 -0.001525938 0.3729473 -0.9278514 -0.001312315 0.1891268 -0.9819519 -0.001464903 0.2822701 -0.9593339 0.00439471 0.2379275 -0.971273 -0.001586973 0.6202777 -0.7843809 -0.006164729 0.6892336 -0.7245131 -3.6623e-4 0.6679119 -0.7442404 0.004364192 0.5170558 -0.8559406 -0.001709103 0.5426405 -0.8399634 0.004150569 0.601132 -0.799139 0.005462944 0.6464961 -0.7628978 -0.001617491 0.757054 -0.6533504 0.01251292 0.7597786 -0.6500616 -0.00350964 0.7326999 -0.680543 0.004242181 0.7975655 -0.6032175 0.002807796 0.941959 -0.3357163 0.003601193 0.9028152 -0.4300137 -0.001525938 0.9106944 -0.413078 -0.001678526 0.8672919 -0.4977971 0.004089534 0.8543871 -0.5196211 -0.001922667 0.8159757 -0.5780832 -8.5454e-4 0.9456403 -0.3252136 2.74669e-4 0.9720851 -0.2346286 0.001770019 0.9712526 -0.2380446 -0.001068174 0.9987431 -0.0501126 -0.001190185 0.9987583 0.04980665 -4.88307e-4 0.9984356 0.05591112 0.001709043 0.9902888 -0.1390152 -1.52594e-4 0.989544 -0.1442322 0.001648008 0.971341 0.2376851 -9.76604e-4 0.9458409 0.3246293 0.002746701 0.9420046 0.3355888 0.001678526 0.9903021 0.1389212 -6.10384e-5 0.9896458 0.1435317 -3.66233e-4 0.9984425 -0.05578947 0 0.9961029 -0.08819931 -0.001739561 0.8675367 0.4973702 0.004089593 0.8546072 0.5192589 0.003845393 0.9028555 0.4299268 0 0.9961029 0.08819931 -0.006195306 0.6895772 0.7241857 -0.003479123 0.7330673 0.6801472 -0.001739561 0.7572938 0.653072 -0.001678526 0.8162057 0.5777592 0.004242122 0.5173606 0.8557569 0.004119992 0.6012199 0.7990731 -0.001831114 0.5430315 0.8397104 -0.001586973 0.4603487 0.8877369 -0.001586973 0.3732784 0.9277181 0.004425287 0.4280638 0.9037377 -0.001342833 0.2826684 0.9592169 0.004364192 0.3347957 0.9422807 0.01232969 0.7598642 0.6499649 -0.001373291 0.1893385 0.981911 0.004455745 0.2380497 0.9712428 0.005432426 0.6463978 0.7629813 -0.001678526 0.6204159 0.7842711 0.004364192 0.139044 0.9902766 0.01049852 0.07794547 0.9969024 -0.001464903 0.09433513 0.9955394 -0.007812976 -3.96753e-4 0.9999695 -0.002349972 0.04696905 0.9988937 -0.002624571 -0.04782307 0.9988524 -0.005218803 -0.09732645 0.9952389 0.001068115 -0.1284844 0.991711 -0.004730463 -0.1943764 0.9809156 0.006927847 -0.07498615 0.9971606 9.76594e-4 -0.2161935 0.9763501 -0.003540217 -0.2902063 0.9569576 3.35707e-4 -0.3015871 0.9534386 -3.35714e-4 0.6677666 0.7443706 0.004364192 0.7975246 0.6032707 -0.00137335 0.9107509 0.4129539 3.05188e-5 0.9721147 0.2345063 0.004333615 0.3344863 -0.9423907 -1 -4.60472e-6 0 -1 -1.47351e-6 0 -1 0 0 -1 7.36752e-7 0 -1 -1.47353e-6 0 -1 1.47351e-6 0 -1 7.36764e-7 0 -1 -2.947e-6 0 -1 -2.94703e-6 0 -1 -1.10513e-6 0 -1 -7.3676e-6 0 -1 -3.68306e-6 0 -1 0 0 -1 -7.3701e-7 0 -1 7.36763e-7 0 -1 9.20939e-7 0 -1 6.44694e-6 0 -1 -2.67e-6 0 -1 -1.43897e-6 0 -1 -2.94623e-6 0 -1 -2.30238e-7 0 -1 1.01304e-5 0 -1 9.20947e-7 0 -1 4.6048e-7 0 -1 2.94702e-6 0 -1 7.36687e-7 0 -1 8.28853e-6 0 -1 -9.20942e-7 0 -1 1.84189e-6 0 -1 9.20946e-7 0 -1 1.8419e-6 0 -1 9.20945e-7 0 -1 -3.68378e-6 0 -1 -9.20938e-7 0 -1 2.94701e-6 0 -1 -2.94706e-6 0 -1 2.94626e-6 0 -1 -9.20966e-7 0 -1 6.44649e-6 0 -1 -2.76291e-6 0 -1 9.20927e-7 0 -1 1.84186e-6 0 -1 -4.60466e-6 0 -1 1.10508e-6 0 -1 -9.20942e-7 0 -1 -1.84187e-6 0 -1 -7.36837e-7 0 -1 3.68401e-7 0 -1 7.36954e-7 0 -1 7.36802e-6 0 -1 -2.95069e-6 0 -1 -2.94816e-6 0 -1 1.43897e-6 0 -1 2.30237e-7 0 1 -5.66532e-7 0 1 5.68213e-7 0 1 5.69523e-7 0 1 5.69089e-7 0 1 -1.19706e-6 0 1 1.19241e-6 0 1 5.66763e-7 0 1 0 0 1 4.24034e-7 0 1 5.66978e-7 0 1 -1.13254e-6 0 1 1.15562e-6 0 1 1.48985e-7 0 1 -4.21232e-7 0 1 -5.90666e-7 0 1 5.94085e-7 0 1 -5.66544e-7 0 1 5.66888e-7 0 1 -9.14498e-7 0 1 1.15512e-6 0 1 -5.69048e-7 0 1 -5.67532e-7 0 1 -8.48496e-7 0 1 -1.18557e-6 0 1 2.96422e-7 0 1 5.69343e-7 0 1 -5.67354e-7 0 1 -3.16119e-7 0 1 -5.65368e-7 0 1 5.67639e-7 0 1 5.69747e-7 0 1 2.83852e-7 0 1 2.84013e-7 0 1 5.95989e-7 0 1 -5.93771e-7 0 1 5.95032e-7 0 1 5.95387e-7 0 1 -5.97036e-7 0 1 -1.19957e-6 0 1 7.46792e-7 0 1 -1.13119e-6 0 1 -1.19244e-6 0 1 -4.21233e-7 0 1 1.41624e-7 0 1 -8.45911e-7 0 1 1.19588e-6 0 1 2.83867e-7 0 1 5.65686e-7 0 1 5.68637e-7 0 1 5.93737e-7 0 1 5.91003e-7 0 1 -5.92829e-7 0 1 2.96084e-7 0 1 -1.48163e-7 0 1 1.49128e-7 0 1 6.69608e-7 0 1 4.66962e-7 0 1 1.12879e-6 0 1 -1.13143e-6 0 1 5.66749e-7 0 1 -1.18765e-6 0 1 -2.84411e-7 0 0 0.7071077 0.7071059 0 0.7070724 0.7071412 0 -0.7070714 -0.7071422 0 -0.7071059 -0.7071077 0 -0.7071059 0.7071077 0 -0.7071848 0.7070288 0 0.7070724 -0.7071412 0 0.7071077 -0.7071059 0 -1 0 0 1 0 0 -0.7071077 -0.7071059 0 -0.7070724 -0.7071412 0 0.7071848 0.7070288 0 0.707106 0.7071077 0 0.707106 -0.7071077 0 0.7070714 -0.7071422 0 -0.7070724 0.7071412 0 1 0 -0.0122078 0.8432856 -0.5373271 0.003082394 0.8854543 -0.4647163 0.0032655 0.8384455 -0.5449758 -0.01336711 0 0.9999107 -0.01736503 -0.1116675 0.993594 -0.01416063 -0.1765198 0.9841953 -2.13634e-4 -0.4760678 0.8794085 0.001190185 -0.4652014 0.8852041 -0.001068115 -0.3248757 0.9457561 0.003051877 -0.8853592 -0.4648975 0.002807676 -0.954776 -0.2973127 -0.00238043 -0.9159333 -0.4013236 -0.006714165 -0.9677923 0.2516608 -0.009308338 -0.9886094 0.1502156 0.002624571 -0.9781869 0.2077106 -0.01416063 -0.1765198 -0.9841953 -0.01736503 -0.1116675 -0.993594 0.002471983 -0.2078629 -0.978155 8.24005e-4 -0.5436294 -0.839325 -0.007293999 -0.6080591 -0.7938584 -2.4415e-4 -0.4763677 -0.8792462 -2.13632e-4 0.4762477 -0.8793112 0.001220703 0.4652014 -0.8852041 -0.001068174 0.3249397 -0.9457342 0.002014219 0.2976539 -0.9546717 -0.007294118 0.6079187 -0.7939658 7.93494e-4 0.5437572 -0.8392422 -0.01495432 0.6982764 -0.7156721 -0.01181089 0.7359387 -0.6769452 -0.01971554 0.7945732 -0.6068482 -0.002349913 0.9158127 -0.4015988 0.002807736 0.9548308 -0.2971372 0.002655088 0.9781931 -0.2076814 -0.006683647 0.96788 -0.2513241 -0.02264511 0.9997436 0 -0.01190239 0.9966009 0.0815165 -0.009186267 0.9886385 0.1500323 -0.002349913 0.9158127 0.4015988 0.002807676 0.954776 0.2973127 -0.006683647 0.96788 0.2513241 0.002655088 0.9781607 0.2078335 0.003082394 0.8853592 0.4648975 -0.009186267 0.9886385 -0.1500323 -0.01971554 0.7945732 0.6068482 0.0032655 0.8383486 0.545125 -0.0122078 0.8432856 0.5373271 8.24005e-4 0.5436294 0.839325 -2.13632e-4 0.4762477 0.8793112 0.00125122 0.4650441 0.8852867 -0.007294118 0.6079187 0.7939658 0.002014219 0.2974697 0.9547292 -0.001068174 0.3249397 0.9457342 -0.01416075 0.1764606 0.9842059 0.002471983 0.2078629 0.978155 -0.01736509 0.1116374 0.9935973 -0.01413023 0.1764606 -0.9842063 0.00250256 0.2080212 -0.9781212 0.002014219 -0.2974697 -0.9547292 -0.001373291 0.6328333 0.7742869 -0.01495432 0.6982764 0.7156721 0 0.61587 0.7878478 -0.01181089 0.7359387 0.6769452 -0.001068174 -0.325031 -0.9457029 0.00125122 -0.4650441 -0.8852867 -0.01190239 0.9966009 -0.0815165 0.003234982 -0.8383625 -0.5451035 -0.01223814 -0.8434261 -0.5371058 -0.01977646 -0.7946908 -0.6066923 0 0.61587 -0.7878478 -0.001373291 0.6328333 -0.7742869 -0.00677514 -0.9679352 -0.2511089 0.002655088 -0.9781607 -0.2078335 -0.01336711 0 -0.9999107 -0.01736509 0.1116374 -0.9935973 -0.02301114 -0.9997352 1.22075e-4 -0.0122075 -0.9966247 -0.08118021 -0.009460926 -0.9886404 -0.1500021 0.002777218 -0.9548309 0.2971372 -0.002349972 -0.9156758 0.401911 -0.001312255 -0.6325307 -0.7745343 -0.01513737 -0.6983053 -0.71564 0 -0.615442 -0.7881822 -0.01193308 -0.7360988 -0.676769 0.003051877 -0.8854544 0.4647163 -0.01236009 -0.8431745 0.5374978 0.003235042 -0.8384595 0.5449544 -0.01229929 -0.73573 0.6771634 -0.01999008 -0.7945689 0.606845 -0.01532047 -0.6982415 0.7156983 -0.01232963 -0.9965658 0.08188229 -0.007568717 -0.6076071 0.7942017 7.62975e-4 -0.5437572 0.8392423 0.002014219 -0.2976539 0.9546717 0 -0.6104192 0.7920787 -0.001647949 -0.6294169 0.7770662 0.00250256 -0.2080212 0.9781212 0 -1 0 1.52595e-4 0.9990069 -0.04455763 -1.52595e-4 0.9990069 0.04455763 0 0.9989877 0.04498541 0 -0.08978724 -0.995961 0 -3.05185e-5 -1 1.22075e-4 0.9909101 0.1345262 -3.05188e-5 0.9909762 0.1340386 -1.52594e-4 0.9749855 0.2222687 0 0.9749081 0.2226077 -6.10383e-5 0.9511294 0.3087928 9.15569e-5 0.9509713 0.3092793 0 0.919503 0.393083 -9.15566e-5 0.9195944 0.3928693 -9.15578e-5 0.8807248 0.4736284 6.10384e-5 0.880479 0.4740852 -3.05192e-5 0.8346098 0.5508419 6.1038e-5 0.8345118 0.5509902 6.10376e-5 0.781678 0.6236822 -9.15572e-5 0.7819901 0.623291 0 0.7228586 0.6909961 1.22077e-4 0.7226346 0.6912303 -1.22075e-4 0.6581697 0.7528697 6.10382e-5 0.6577784 0.7532117 1.52596e-4 0.5875545 0.8091846 0 0.5878905 0.8089407 -1.52597e-4 0.5131532 0.8582971 3.05192e-5 0.5127533 0.858536 -3.05191e-5 0.4340422 0.9008925 1.22075e-4 0.4336119 0.9010998 0 0.3512773 0.9362715 -1.52596e-4 0.3516117 0.936146 -6.10381e-5 0.2662175 0.9639131 9.15582e-5 0.2657324 0.9640468 -1.22076e-4 0.1787189 0.9839002 -3.0519e-5 0.1785363 0.9839334 0 0.08975696 0.9959637 -3.0519e-5 0.08981752 0.9959583 0 0.9989877 -0.04498541 3.05188e-5 0.9909762 -0.1340386 -1.22075e-4 0.9909101 -0.1345262 0 0.9749081 -0.2226077 1.52594e-4 0.9749855 -0.2222687 6.10383e-5 0.9511294 -0.3087928 -9.15569e-5 0.9509713 -0.3092793 9.15566e-5 0.9195944 -0.3928693 0 0.919503 -0.393083 -6.10384e-5 0.880479 -0.4740852 9.15578e-5 0.8807248 -0.4736284 3.05192e-5 0.8346098 -0.5508419 -6.1038e-5 0.8345118 -0.5509902 9.15572e-5 0.7819901 -0.623291 -6.10376e-5 0.781678 -0.6236822 -1.22077e-4 0.7226346 -0.6912303 0 0.7228586 -0.6909961 1.22075e-4 0.6581697 -0.7528697 -6.10382e-5 0.6577784 -0.7532117 0 0.5878905 -0.8089407 -1.52596e-4 0.5875545 -0.8091846 -3.05192e-5 0.5127533 -0.858536 1.52597e-4 0.5131532 -0.8582971 3.05191e-5 0.4340422 -0.9008925 -1.22075e-4 0.4336119 -0.9010998 1.52596e-4 0.3516117 -0.936146 0 0.3512773 -0.9362715 -9.15582e-5 0.2657324 -0.9640468 6.10381e-5 0.2662175 -0.9639131 1.22076e-4 0.1787189 -0.9839002 3.0519e-5 0.1785363 -0.9839334 3.0519e-5 0.08981752 -0.9959583 0 0.08975696 -0.9959637 0 -0.3513041 -0.9362614 -6.10376e-5 -0.2662459 -0.9639053 1.22078e-4 -0.2657324 -0.9640468 -6.10377e-5 -0.1785658 -0.983928 -1.22076e-4 -0.1787189 -0.9839002 -1.52597e-4 -0.5131532 -0.8582971 0 -0.5128118 -0.8585011 1.52597e-4 -0.5875001 -0.8092241 -1.52596e-4 -0.3516117 -0.936146 1.52598e-4 -0.4335623 -0.9011237 -3.05191e-5 -0.4340422 -0.9008925 1.83116e-4 -0.7225451 -0.6913238 3.05191e-5 -0.7817465 -0.6235965 0 -0.7228433 -0.691012 0 -0.6578432 -0.7531549 -1.52594e-4 -0.6581697 -0.7528697 0 -0.5878905 -0.8089407 1.83116e-4 -0.9193959 -0.3933336 -1.22076e-4 -0.8807444 -0.473592 6.10378e-5 -0.880531 -0.4739888 6.10375e-5 -0.8345957 -0.5508631 -1.22076e-4 -0.7820168 -0.6232574 2.13633e-4 -0.8343905 -0.5511738 -3.05193e-5 -0.9749707 -0.2223333 1.22075e-4 -0.9748603 -0.2228173 9.15571e-5 -0.9909222 -0.1344363 0 -0.9195676 -0.3929319 6.10379e-5 -0.9510011 -0.3091875 -1.22075e-4 -0.9511502 -0.3087286 1.22075e-4 -0.9990042 0.04461854 1.22077e-4 -0.9909884 0.1339486 -6.10383e-5 -0.9989836 0.04507678 1.22076e-4 -0.9989808 -0.0451377 -3.05189e-5 -0.9990042 -0.04461854 -9.15572e-5 -0.9909842 -0.1339786 1.52596e-4 -0.9196321 0.3927809 -3.05196e-5 -0.9509893 0.3092241 1.22075e-4 -0.9511502 0.3087286 -3.05189e-5 -0.9748949 0.2226657 -3.05189e-5 -0.9909182 0.1344662 1.52594e-4 -0.9749855 0.2222687 0 -0.8345118 0.5509902 1.52597e-4 -0.8347077 0.5506935 1.52595e-4 -0.7819901 0.623291 0 -0.9194873 0.3931199 1.52596e-4 -0.8807248 0.4736284 0 -0.880479 0.4740852 -6.10385e-5 -0.7226346 0.6912303 1.22075e-4 -0.6581372 0.752898 -3.05191e-5 -0.6577784 0.7532117 9.15567e-5 -0.7229626 0.6908873 -3.05194e-5 -0.7816929 0.6236636 -9.15574e-5 -0.5875546 0.8091846 6.1038e-5 -0.5879793 0.808876 1.22078e-4 -0.5130949 0.858332 -3.05192e-5 -0.5127533 0.858536 6.10382e-5 -0.4341037 0.9008629 -9.15566e-5 -0.4336119 0.9010998 -3.05188e-5 -0.3512405 0.9362854 1.22076e-4 -0.3515482 0.9361699 9.15583e-5 -0.2662821 0.9638953 -6.10383e-5 -0.2657608 0.964039 9.15573e-5 -0.1786894 0.9839056 0 -0.1785363 0.9839334 0 -0.08975696 0.9959637 6.10381e-5 -0.08981752 0.9959583 -1 -1.45916e-6 0 -1 4.58672e-7 0 -1 -2.73834e-7 0 -1 8.17214e-7 0 -1 1.47548e-6 0 -1 2.54815e-7 0 -1 9.20324e-7 0 -1 -8.10453e-7 0 -1 -4.07714e-7 0 -0.8882181 -0.3248775 0.3248434 -0.8882175 -0.3248612 0.3248617 -0.8882178 -0.3248438 0.324878 -1 0 0 -1 -4.60381e-7 0 -1 3.05786e-7 0 -0.8882178 -0.4594227 -1.85626e-5 -0.8882175 -0.4594234 0 -0.8882178 -0.4594227 1.85626e-5 -1 -2.73834e-7 0 -1 -3.6479e-7 0 -1 1.52595e-7 0 -1 7.3774e-7 0 -1 -2.03852e-7 0 -1 0 0 -0.8882183 -0.324842 -0.3248782 -0.8882173 -0.3248614 -0.3248618 -0.8882181 -0.3248775 -0.3248434 -1 4.65892e-7 0 -1 -1.18952e-6 0 -1 4.65912e-7 0 -1 -3.49363e-7 0 -1 -3.49494e-7 0 -1 5.493e-7 0 -0.8882178 -1.47615e-5 -0.4594227 -0.8882178 1.56316e-5 -0.4594227 -0.8882174 0 -0.4594236 -1 8.17214e-7 0 -1 -8.15417e-7 0 -1 3.56054e-7 0 -1 5.60593e-7 0 -1 7.15808e-7 0 -1 -8.10453e-7 0 -1 -4.07713e-7 0 -0.8882186 0.3248773 -0.3248422 -0.8882175 0.3248614 -0.3248614 -0.888218 0.3248426 -0.3248788 -1 -3.05786e-7 0 -1 -4.07898e-7 0 -1 1.82394e-7 0 -1 2.74251e-7 0 -1 2.552e-7 0 -1 4.60381e-7 0 -1 -4.07627e-7 0 -0.8882179 0.4594227 1.95395e-5 -0.8882175 0.4594234 0 -0.8882179 0.4594227 -1.95395e-5 -1 2.03459e-7 0 -1 -2.04303e-7 0 -1 -7.3774e-7 0 -1 2.03852e-7 0 -1 0 0 -1 4.05227e-7 0 -1 0 0 -0.8882175 0.3248441 0.3248783 -0.8882175 0.3248614 0.3248614 -0.8882186 0.3248773 0.3248422 -1 4.07714e-7 0 -1 -1.74945e-6 0 -1 7.135e-7 0 -1 -8.91315e-7 0 -1 -4.58672e-7 0 -0.8882178 2.25773e-5 0.4594227 -0.8882178 -2.34475e-5 0.4594227 -0.8882174 0 0.4594234 -1 -1.13935e-6 0 -1 -5.94176e-7 0 -1 2.84597e-7 0 -1 5.68949e-7 0 -1 -1.18813e-6 0 -1 1.49092e-7 0 -1 5.64951e-7 0 -1 -1.1366e-6 0 -1 1.41424e-7 0 -1 -8.17691e-7 0 -1 -5.68593e-7 0 -1 5.64841e-7 0 -1 7.4385e-7 0 -1 5.90852e-7 0 -1 -5.93354e-7 0 -1 -4.40754e-7 0 -1 0 0 -1 5.6658e-7 0 -1 5.66229e-7 0 -1 4.26417e-7 0 -1 1.12398e-6 0 -1 -7.45709e-7 0 -1 -5.67252e-7 0 -1 -1.19598e-6 0 -1 2.96984e-7 0 -1 1.18432e-6 0 -1 1.18707e-6 0 -1 1.48878e-7 0 -1 -2.96707e-7 0 -1 -1.13368e-6 0 -1 -6.67362e-7 0 -1 5.6552e-7 0 -1 2.83477e-7 0 -1 -1.12398e-6 0 -1 -2.83292e-7 0 -1 -5.67028e-7 0 -1 2.83597e-7 0 -1 2.96409e-7 0 -1 -2.96062e-7 0 -1 -1.48145e-7 0 -1 -1.49144e-7 0 -1 0 0 -1 2.24171e-7 0 -1 5.66209e-7 0 -1 5.65823e-7 0 -1 1.18461e-6 0 -1 1.1876e-6 0 -1 1.19016e-6 0 -1 6.67362e-7 0 -1 -2.83277e-7 0 -1 -5.67118e-7 0 -1 5.9225e-7 0 -1 -5.91025e-7 0 -1 8.89853e-7 0 -1 -2.95142e-7 0 -1 -2.97476e-7 0 -1 7.39588e-7 0 -1 -2.97858e-7 0 -1 -2.96907e-7 0 -1 1.49241e-7 0 -1 -1.30527e-7 0 -1 5.6614e-7 0 -1 -2.8393e-7 0 -1 5.6714e-7 0 -1 5.93852e-7 0 -1 1.13364e-6 0 -1 -1.18937e-6 0 0.005218803 0.09732645 0.9952389 0.002624571 0.04782307 0.9988524 0.007812976 3.96753e-4 0.9999695 -0.001068115 0.1284844 0.991711 -0.006927847 0.07498615 0.9971606 0.002349972 -0.04696905 0.9988937 -0.004242181 0.7975913 -0.6031835 0.001709043 0.8140127 -0.5808447 0.001586973 0.7550151 -0.6557055 -3.35707e-4 0.3015871 0.9534386 0.003540217 0.2902063 0.9569576 0.002197325 0.382403 0.9239931 -9.76594e-4 0.2161935 0.9763501 -0.01229906 0.7601032 -0.649686 2.44154e-4 0.6673647 -0.744731 0.003326594 0.7317593 -0.6815551 0.00564599 0.6870113 -0.7266248 0.00149542 0.6181969 -0.786022 0 0.3826816 0.9238803 0.004730463 0.1943764 0.9809156 0.001373291 -0.1893385 0.981911 -0.004364192 -0.139044 0.9902766 -0.004455745 -0.2380497 0.9712428 -0.004242122 -0.5173606 0.8557569 0.001586973 -0.4603487 0.8877369 -0.004455804 -0.4280637 0.9037376 -0.004364192 -0.3347957 0.9422807 0.001586914 -0.3733047 0.9277075 0.001342833 -0.2826684 0.9592169 0.006195306 -0.6895772 0.7241857 3.35708e-4 -0.6677836 0.7443554 0.003479182 -0.7331413 0.6800677 0.001678526 -0.6204159 0.7842711 -0.004119992 -0.6012199 0.7990731 -0.005432307 -0.6464155 0.7629663 0.001739561 -0.8675367 0.4973702 -0.004089593 -0.8546072 0.5192589 -0.003845393 -0.9028555 0.4299268 0.001678526 -0.8162057 0.5777592 0.001739561 -0.7572938 0.653072 -0.004364192 -0.7975246 0.6032707 -0.001648008 -0.971341 0.2376851 -0.001678526 -0.9903021 0.1389212 6.10384e-5 -0.9896458 0.1435317 -0.002746701 -0.9420046 0.3355888 9.76604e-4 -0.9458409 0.3246293 3.66233e-4 -0.9984425 -0.05578947 0 -0.9961029 -0.08819931 -0.001709043 -0.9902847 -0.1390451 0.001190185 -0.9987583 0.04980665 4.88307e-4 -0.9984356 0.05591112 -0.003601193 -0.9028152 -0.4300137 0.001525938 -0.9106944 -0.413078 -0.002807796 -0.941959 -0.3357163 -0.001770019 -0.9712526 -0.2380446 8.5454e-4 -0.9456403 -0.3252136 -2.74669e-4 -0.9720851 -0.2346286 -0.004242181 -0.7975655 -0.6032175 0.001617491 -0.757054 -0.6533504 0.001922667 -0.8159757 -0.5780832 -0.004089534 -0.8543871 -0.5196211 0.001678526 -0.8672919 -0.4977971 0.001586973 -0.6202777 -0.7843809 -0.004150569 -0.601132 -0.799139 0.001709103 -0.5426405 -0.8399634 3.66229e-4 -0.6678798 -0.7442691 0.006164729 -0.6892336 -0.7245131 0.00350964 -0.7326999 -0.680543 0.001464903 -0.2822701 -0.9593339 0.001525938 -0.3729473 -0.9278514 -0.004333615 -0.3344863 -0.9423907 -0.004425227 -0.4279654 -0.9037843 0.001617491 -0.4600822 -0.8878749 -0.004364192 -0.5170558 -0.8559406 0.002319455 -0.04696905 -0.9988937 0.00753808 -3.05186e-5 -0.9999716 0.001403808 -0.09424155 -0.9955485 0.001312315 -0.1891268 -0.9819519 -0.00451672 -0.13889 -0.9902976 0.001281797 0.1886684 -0.9820401 -0.004516839 0.2380208 -0.9712496 0.001312255 0.2816869 -0.9595056 0.001403868 0.0939995 -0.9955713 -0.01052904 0.07794541 -0.9969021 -0.004455804 0.1389542 -0.9902888 -0.003997981 0.6013226 -0.7989964 0.001831114 0.5411037 -0.8409539 -0.004181146 0.5173966 -0.8557355 -0.004455804 0.4280021 -0.9037668 0.001617491 0.4587604 -0.8885585 0.001586973 0.371969 -0.9282439 -0.004730522 0.6458544 -0.7634461 0.00100708 0.9086757 -0.4175013 -0.003143429 0.9030805 -0.4294599 -0.001648008 0.9422884 -0.3347985 -0.003967404 0.8547083 -0.5190936 -0.002868831 0.9903885 -0.1382839 0.001159667 0.9886062 -0.1505203 -0.001678466 0.9711629 -0.2384113 -1.22076e-4 0.9701353 -0.2425643 0.001495361 0.99839 -0.0567038 -0.009338796 0.9966607 -0.08111959 0.002960264 0.9995735 -0.02905362 0.001739561 0.9990243 0.04413115 6.10376e-5 0.9983316 0.05774158 -0.001922667 0.9903782 0.138374 -1.22076e-4 0.991046 0.1335209 0.00100708 0.9741138 0.2260562 -0.003143429 0.9710835 0.2387195 0.001403868 0.9485052 0.3167584 0.001770079 0.91421 0.4052372 -0.003967404 0.9416862 0.3364691 -0.004242122 0.9026955 0.4302591 0.001678526 0.8716135 0.4901911 -0.004394769 0.8545137 0.5194103 0.001586973 0.8209136 0.5710504 0.001525938 0.7627112 0.6467374 -0.004364252 0.7977492 0.6029738 -0.01211607 0.7595283 0.6503615 0.003174006 0.7357947 0.6771973 0.001068115 0.669743 0.7425922 0.007110893 0.6970853 0.7169531 0.004303157 0.6270461 0.7789703 -0.004425227 0.6503577 0.7596153 -0.001434385 0.6105962 0.7919408 -0.00125128 0.5379607 0.842969 0.003357112 0.5503582 0.834922 -2.13634e-4 0.4616333 0.8870709 0.002563595 0.4685928 0.8834106 1.22075e-4 0.943885 -0.3302743 0.001464903 0.8652156 -0.5013978 -0.004425287 0.3347048 -0.9423127 0.002288937 0.04687768 -0.998898 -0.01049852 -0.07794547 -0.9969024 -0.00439471 -0.2379275 -0.971273 -0.01251292 -0.7597786 -0.6500616 -0.005462825 -0.6464483 -0.7629383 1.52594e-4 -0.989544 -0.1442322 0.001068174 -0.9987431 -0.0501126 -3.05188e-5 -0.9721147 0.2345063 0.00137335 -0.9107509 0.4129539 -0.01232963 -0.7598922 0.6499323 0.001831114 -0.5430315 0.8397104 0.001464903 -0.09433513 0.9955394 -0.01049852 -0.07794547 0.9969024 0 0.9988763 0.04739546 0 0.9988573 0.04779279 0 0.9988573 -0.04779279 0 -0.09518784 -0.9954594 0 -0.0953117 -0.9954475 0 0.9898614 0.1420366 0 0.9898 0.1424638 0 0.9717821 0.2358804 0 0.9718415 0.2356358 0 0.9450837 0.3268286 0 0.9449259 0.3272845 0 0.9096943 0.4152786 0 0.9095863 0.4155153 0 0.8659009 0.5002156 0 0.866113 0.4998484 0 0.8147118 0.5798661 0 0.8144814 0.5801898 0 0.7558664 0.6547261 0 0.7556257 0.6550038 0 0.6899501 0.723857 0 0.6902783 0.723544 0 0.6182501 0.7859814 0 0.6180776 0.7861171 0 0.5408054 0.8411477 0 0.5403997 0.8414084 0 0.458094 0.8889038 0 0.4583731 0.8887599 0 0.3718169 0.9283062 0 0.3714222 0.9284641 0 0.2819647 0.9594248 0 0.2815665 0.9595417 0 0.1892209 0.9819346 0 0.1894031 0.9818994 0 0.0953117 0.9954475 0 0.09515762 0.9954622 0 -3.05185e-5 1 0 0.9898 -0.1424638 0 0.9988763 -0.04739546 0 0.9898614 -0.1420366 0 0.9717821 -0.2358804 0 0.9718415 -0.2356358 0 0.9449259 -0.3272845 0 0.9095863 -0.4155153 0 0.9450837 -0.3268286 0 0.9096943 -0.4152786 0 0.8659009 -0.5002156 0 0.866113 -0.4998484 0 0.8144814 -0.5801898 0 0.7556257 -0.6550038 0 0.8147118 -0.5798661 0 0.7558664 -0.6547261 0 0.6899661 -0.7238419 0 0.6902783 -0.723544 0 0.6180776 -0.7861171 0 0.5403997 -0.8414084 0 0.6182501 -0.7859814 0 0.5408054 -0.8411477 0 0.458094 -0.8889038 0 0.4583731 -0.8887599 0 0.3714222 -0.9284641 0 0.2815665 -0.9595417 0 0.3718169 -0.9283062 0 0.2819647 -0.9594248 0 0.1892209 -0.9819346 0 0.1894031 -0.9818994 0 0.09515762 -0.9954622 0 0.0953117 -0.9954475 0 -0.2819647 -0.9594248 0 -0.1894031 -0.9818994 0 -0.1892504 -0.9819289 0 -0.5407915 -0.8411567 0 -0.4583731 -0.8887599 0 -0.4580333 -0.8889351 0 -0.3718169 -0.9283062 0 -0.2815384 -0.9595501 0 -0.3714222 -0.9284641 0 -0.6902783 -0.723544 0 -0.6898876 -0.7239166 0 -0.7558664 -0.6547261 0 -0.5403997 -0.8414084 0 -0.6179914 -0.7861849 0 -0.6182501 -0.7859814 0 -0.8659559 -0.5001205 0 -0.9096996 -0.4152671 0 -0.866113 -0.4998484 0 -0.814432 -0.5802592 0 -0.8147118 -0.5798661 0 -0.7556257 -0.6550038 0 -0.9898572 -0.1420665 0 -0.9718485 -0.235607 0 -0.9717664 -0.235945 0 -0.9450743 -0.3268558 0 -0.9095579 -0.4155773 0 -0.9449353 -0.3272573 0 -0.9988588 0.04776233 0 -0.9988806 0.04730415 0 -0.9898 0.1424638 0 -0.9897914 -0.1425236 0 -0.9988573 -0.04779279 0 -0.9988763 -0.04739546 0 -0.9450615 0.3268925 0 -0.9095694 0.415552 0 -0.9449259 0.3272845 0 -0.9718781 0.2354847 0 -0.9717821 0.2358804 0 -0.9898572 0.1420665 0 -0.7556257 0.6550038 0 -0.8144711 0.5802042 0 -0.8146872 0.5799008 0 -0.8659086 0.5002024 0 -0.909751 0.4151546 0 -0.8660997 0.4998713 0 -0.6180776 0.7861171 0 -0.6899501 0.723857 0 -0.6902311 0.723589 0 -0.7558664 0.6547261 0 -0.6183512 0.785902 0 -0.5403997 0.8414084 0 -0.540827 0.8411339 0 -0.458094 0.8889038 0 -0.3714222 0.9284641 0 -0.4584579 0.8887162 0 -0.3718432 0.9282957 0 -0.2815665 0.9595417 0 -0.2819929 0.9594166 0 -0.1892504 0.9819289 0 -0.09515762 0.9954622 0 -0.1894326 0.9818938 0 -0.0953117 0.9954475 -1 5.68299e-7 0 -1 1.19103e-6 0 -1 5.69193e-7 0 -1 8.8803e-7 0 -1 3.87923e-7 0 -1 5.66683e-7 0 -1 -1.1355e-6 0 -1 1.12714e-6 0 -1 1.41665e-7 0 -1 5.67158e-7 0 -1 -1.13397e-6 0 -1 1.04852e-6 0 -1 -4.21233e-7 0 -1 5.96267e-7 0 -1 -1.13892e-6 0 -1 -5.66881e-7 0 -1 5.67035e-7 0 -1 -5.69372e-7 0 -1 7.51563e-7 0 -1 1.13147e-6 0 -1 5.68342e-7 0 -1 -5.69019e-7 0 -1 5.6731e-7 0 -1 2.8242e-7 0 -1 1.18581e-6 0 -1 -1.13857e-6 0 -1 -5.69436e-7 0 -1 -5.67377e-7 0 -1 1.13368e-6 0 -1 -3.16119e-7 0 -1 2.83102e-7 0 -1 1.13104e-6 0 -1 5.67101e-7 0 -1 5.6965e-7 0 -1 -8.49877e-7 0 -1 2.83514e-7 0 -1 5.90645e-7 0 -1 5.92818e-7 0 -1 -5.92148e-7 0 -1 2.96062e-7 0 -1 2.97178e-7 0 -1 -5.92581e-7 0 -1 -1.11584e-6 0 -1 -4.1098e-7 0 -1 -1.12969e-6 0 -1 -1.13642e-6 0 -1 1.18141e-6 0 -1 -4.21232e-7 0 -1 1.41757e-7 0 -1 2.82383e-7 0 -1 -8.53272e-7 0 -1 -5.97133e-7 0 -1 5.96048e-7 0 -1 -5.95047e-7 0 -1 2.9782e-7 0 -1 5.99857e-7 0 -1 -7.4671e-7 0 -1 -1.12798e-6 0 -1 1.19234e-6 0 -1 5.66664e-7 0 -1 2.84314e-7 0 -1 -5.65838e-7 0 -1 -1.13374e-6 0 -1 1.195e-6 0 1 -1.13935e-6 0 1 2.84597e-7 0 1 5.68949e-7 0 1 -1.18813e-6 0 1 -4.47277e-7 0 1 5.64951e-7 0 1 -1.1366e-6 0 1 1.41424e-7 0 1 -1.13432e-6 0 1 -5.68583e-7 0 1 4.46339e-7 0 1 1.18695e-6 0 1 5.64841e-7 0 1 7.4385e-7 0 1 -5.66818e-7 0 1 5.90666e-7 0 1 -5.94085e-7 0 1 -1.18442e-6 0 1 0 0 1 0 0 1 2.84692e-7 0 1 5.69555e-7 0 1 5.68093e-7 0 1 -2.83615e-7 0 1 -1.48985e-7 0 1 -1.19598e-6 0 1 -2.96393e-7 0 1 -1.18707e-6 0 1 4.46636e-7 0 1 -2.96708e-7 0 1 -1.13367e-6 0 1 -6.67363e-7 0 1 -5.65521e-7 0 1 -5.68831e-7 0 1 -1.12398e-6 0 1 -2.83292e-7 0 1 5.67028e-7 0 1 2.96409e-7 0 1 2.96062e-7 0 1 -1.48145e-7 0 1 -1.49144e-7 0 1 0 0 1 2.24171e-7 0 1 5.63392e-7 0 1 5.66209e-7 0 1 -5.65823e-7 0 1 1.18461e-6 0 1 1.1876e-6 0 1 1.19016e-6 0 1 -1.75514e-7 0 1 -1.41624e-7 0 1 2.8197e-7 0 1 -8.48529e-7 0 1 5.90714e-7 0 1 2.97171e-7 0 1 -2.96326e-7 0 1 2.97604e-7 0 1 0 0 1 -5.64797e-7 0 1 -5.64395e-7 0 1 5.66923e-7 0 1 -1.18447e-6 0 1 -5.66749e-7 0 1 -5.68822e-7 0 1 2.83009e-7 0 0 -3.05194e-5 -1 0 -3.05194e-5 1 3.05193e-5 -0.3512773 -0.9362715 -6.10389e-5 -0.2662821 -0.9638953 9.15582e-5 -0.2657324 -0.9640468 -3.05189e-5 -0.1785658 -0.983928 -9.15573e-5 -0.1786894 -0.9839056 0 -0.08981752 -0.9959583 -1.52598e-4 -0.5130949 -0.858332 1.22078e-4 -0.5875001 -0.8092241 -1.22076e-4 -0.3515482 -0.9361699 9.15578e-5 -0.4335871 -0.9011117 -6.10382e-5 -0.4341037 -0.9008629 1.22077e-4 -0.7225451 -0.6913238 0 -0.7817465 -0.6235965 -6.10392e-5 -0.722948 -0.6909025 -1.52594e-4 -0.6581372 -0.752898 -6.1038e-5 -0.5879793 -0.808876 1.52595e-4 -0.9193848 -0.3933594 -1.83116e-4 -0.8807571 -0.4735683 0 -0.880531 -0.4739888 -6.10379e-5 -0.8346937 -0.5507147 -1.83114e-4 -0.7820168 -0.6232574 1.52597e-4 -0.8343672 -0.5512091 1.83115e-4 -0.9748455 -0.222882 0 -0.9909304 -0.1343764 -3.05192e-5 -0.9196054 -0.3928435 0 -0.9510101 -0.3091599 -1.83116e-4 -0.9511681 -0.3086733 3.05188e-5 -0.9990015 0.04467946 1.83112e-4 -0.991001 0.1338547 -1.83114e-4 -0.9989767 0.04522907 1.83114e-4 -0.9989767 -0.04522907 -3.05188e-5 -0.9990015 -0.04467946 -1.83112e-4 -0.991001 -0.1338547 3.05192e-5 -0.9196054 0.3928435 0 -0.9510101 0.3091599 1.83116e-4 -0.9511681 0.3086733 -1.83115e-4 -0.9748455 0.222882 0 -0.9909304 0.1343764 3.05193e-5 -0.9749707 0.2223333 -1.52597e-4 -0.8343672 0.5512091 6.10379e-5 -0.8346937 0.5507147 1.83114e-4 -0.7820168 0.6232574 -1.52595e-4 -0.9193848 0.3933594 1.83116e-4 -0.8807571 0.4735683 0 -0.880531 0.4739888 -1.22077e-4 -0.7225451 0.6913238 1.52594e-4 -0.6581372 0.752898 0 -0.6578432 0.7531549 6.10392e-5 -0.722948 0.6909025 0 -0.7817465 0.6235965 -1.22078e-4 -0.5875001 0.8092241 1.52598e-4 -0.5130949 0.858332 0 -0.5128118 0.8585011 -9.15578e-5 -0.4335871 0.9011117 -3.05193e-5 -0.3512773 0.9362715 6.10389e-5 -0.2662821 0.9638953 -9.15582e-5 -0.2657324 0.9640468 3.05189e-5 -0.1785658 0.983928 0 -0.08978724 0.995961 0 -0.08981752 0.9959583 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.004499971 -0.00259757 0.007566511 0.004499971 -0.003807544 0.007035732 0.004499971 -0.00259757 0.007566511 -0.004499971 0 0.007999956 -0.004499971 -0.001316726 0.00789088 0.004499971 -0.001316726 0.00789088 0.004499971 -0.005885779 0.005418241 -0.004499971 -0.005885779 0.005418241 0.004499971 -0.006697297 0.004375576 -0.004499971 -0.004913687 0.006313085 0.004499971 -0.004913687 0.006313085 -0.004499971 -0.003807544 0.007035732 -0.004499971 -0.00775516 0.001963853 0.004499971 -0.007972657 6.60634e-4 0.004499971 -0.00775516 0.001963853 -0.004499971 -0.007326185 0.003213524 0.004499971 -0.007326185 0.003213524 -0.004499971 -0.006697297 0.004375576 0.004499971 -0.007326185 -0.003213524 0.004499971 -0.00775516 -0.001963853 -0.004499971 -0.00775516 -0.001963853 0.004499971 -0.007972657 -6.60636e-4 -0.004499971 -0.007972657 6.60634e-4 -0.004499971 -0.007972657 -6.60636e-4 0.004499971 -0.005885779 -0.005418241 -0.004499971 -0.005885779 -0.005418241 0.004499971 -0.004913687 -0.006313085 -0.004499971 -0.007326185 -0.003213524 -0.004499971 -0.006697297 -0.004375576 0.004499971 -0.006697297 -0.004375576 -0.004499971 -0.00259757 -0.007566511 0.004499971 -0.001316726 -0.00789088 0.004499971 -0.00259757 -0.007566511 -0.004499971 -0.003807544 -0.007035732 0.004499971 -0.003807544 -0.007035732 -0.004499971 -0.004913687 -0.006313085 0.004499971 0.00259757 -0.007566511 0.004499971 0.001316726 -0.00789088 -0.004499971 0.001316726 -0.00789088 0.004499971 0 -0.007999956 -0.004499971 -0.001316726 -0.00789088 -0.004499971 0 -0.007999956 0.004499971 0.004913687 -0.006313085 -0.004499971 0.004913687 -0.006313085 0.004499971 0.005885779 -0.005418241 -0.004499971 0.00259757 -0.007566511 -0.004499971 0.003807544 -0.007035732 0.004499971 0.003807544 -0.007035732 -0.004499971 0.007326185 -0.003213524 0.004499971 0.00775516 -0.001963853 0.004499971 0.007326185 -0.003213524 -0.004499971 0.006697297 -0.004375576 0.004499971 0.006697297 -0.004375576 -0.004499971 0.005885779 -0.005418241 -0.004499971 0.007972657 6.60634e-4 0.004499971 0.007972657 6.60634e-4 -0.004499971 0.007972657 -6.60636e-4 0.004499971 0.007972657 -6.60636e-4 -0.004499971 0.00775516 -0.001963853 0.004499971 0.00775516 0.001963853 -0.004499971 0.00775516 0.001963853 0.004499971 0.007326185 0.003213524 0.004499971 0.006697297 0.004375576 -0.004499971 0.007326185 0.003213524 -0.004499971 0.006697297 0.004375576 0.004499971 0.005885779 0.005418241 -0.004499971 0.005885779 0.005418241 0.004499971 0.004913687 0.006313085 0.004499971 0.003807544 0.007035732 -0.004499971 0.004913687 0.006313085 -0.004499971 0.003807544 0.007035732 0.004499971 0.00259757 0.007566511 -0.004499971 0.00259757 0.007566511 0.004499971 0.001316726 0.00789088 0.004499971 0 0.007999956 -0.004499971 0.001316726 0.00789088 -0.004499971 0.005885779 0.005418241 -0.004499971 0.006697297 0.004375576 -0.004499971 0.007279515 0.005291879 -0.004499971 0.007972657 -6.60636e-4 -0.004499971 0.008889436 -0.001405477 -0.004499971 0.008999824 2.53304e-6 -0.004499971 0.00775516 -0.001963853 -0.004499971 0.008560061 -0.002778947 -0.004499971 0.007972657 6.60634e-4 -0.004499971 0.007326185 -0.003213524 -0.004499971 0.008019864 -0.004083991 -0.004499971 0.00775516 0.001963853 -0.004499971 0.008888602 0.001410424 -0.004499971 0.006697297 -0.004375576 -0.004499971 0.007282137 -0.005288481 -0.004499971 0.008558511 0.002783536 -0.004499971 0.007326185 0.003213524 -0.004499971 0.005885779 -0.005418241 -0.004499971 0.006365001 -0.006362795 -0.004499971 0.008017718 0.004088044 -0.004499971 0.004913687 -0.006313085 -0.004499971 0.005291044 -0.007280349 -0.004499971 0.001316726 -0.00789088 -0.004499971 0.001408219 -0.008889138 -0.004499971 0.002781748 -0.008559286 -0.004499971 0.003807544 -0.007035732 -0.004499971 0.004086732 -0.008018553 -0.004499971 0.003807544 0.007035732 -0.004499971 0.004084408 0.008019626 -0.004499971 0.00259757 0.007566511 -0.004499971 0.001408219 0.008889138 -0.004499971 0 0.007999956 -0.004499971 0.001316726 0.00789088 -0.004499971 -0.005292117 0.007279455 -0.004499971 -0.003807544 0.007035732 -0.004499971 -0.004087805 0.008017957 -0.004499971 -0.006697297 -0.004375576 -0.004499971 -0.007279455 -0.005292117 -0.004499971 -0.005885779 -0.005418241 -0.004499971 -0.00775516 -0.001963853 -0.004499971 -0.007972657 -6.60636e-4 -0.004499971 -0.008889019 -0.001408636 -0.004499971 -0.008889198 0.00140649 -0.004499971 -0.00775516 0.001963853 -0.004499971 -0.008559942 0.002778887 -0.004499971 -0.007326185 0.003213524 -0.004499971 -0.008020102 0.004083216 -0.004499971 -0.008999943 0 -0.004499971 -0.007972657 6.60634e-4 -0.004499971 -0.005885779 0.005418241 -0.004499971 -0.004913687 0.006313085 -0.004499971 -0.006365895 0.006361663 -0.004499971 -0.006697297 0.004375576 -0.004499971 -0.007282733 0.005287408 -0.004499971 -0.007326185 -0.003213524 -0.004499971 -0.008558988 -0.002782583 -0.004499971 -0.002782583 0.008558988 -0.004499971 -0.00259757 0.007566511 -0.004499971 -0.001316726 0.00789088 -0.004499971 -0.008017957 -0.004087805 -0.004499971 -0.003807544 -0.007035732 -0.004499971 -0.004913687 -0.006313085 -0.004499971 -0.005287408 -0.007282733 -0.004499971 0 0.008999943 -0.004499971 -0.001408636 0.008889019 -0.004499971 0.00278002 0.008559703 -0.004499971 -0.00259757 -0.007566511 -0.004499971 -0.004083216 -0.008020102 -0.004499971 -0.001408636 -0.008889019 -0.004499971 -0.001316726 -0.00789088 -0.004499971 -0.002778887 -0.008559942 -0.004499971 0.004913687 0.006313085 -0.004499971 0.005288362 0.007282137 -0.004499971 0 -0.007999956 -0.004499971 0 -0.008999943 -0.004499971 0.00259757 -0.007566511 -0.004499971 0.006362199 0.006365358 -0.004499971 -0.006361663 -0.006365895 0.004499971 -0.008889198 -0.00140655 0.004499971 -0.00775516 -0.001963853 0.004499971 -0.008559942 -0.002778887 0.004499971 0.00259757 0.007566511 0.004499971 0.002781748 0.008559286 0.004499971 0.004086732 0.008018553 0.004499971 -0.007326185 -0.003213524 0.004499971 -0.008020102 -0.004083216 0.004499971 -0.008999943 0 0.004499971 -0.007972657 -6.60636e-4 0.004499971 -0.007282733 -0.005287408 0.004499971 -0.006697297 -0.004375576 0.004499971 -0.007972657 6.60634e-4 0.004499971 -0.008889019 0.001408636 0.004499971 -0.00775516 0.001963853 0.004499971 -0.008558988 0.002782583 0.004499971 -0.007326185 0.003213524 0.004499971 -0.004913687 -0.006313085 0.004499971 -0.006365895 -0.006361663 0.004499971 -0.005885779 -0.005418241 0.004499971 -0.008017957 0.004087805 0.004499971 -0.006697297 0.004375576 0.004499971 -0.005292117 -0.007279455 0.004499971 -0.003807544 -0.007035732 0.004499971 -0.004087805 -0.008017957 0.004499971 -0.007279455 0.005292117 0.004499971 -0.005885779 0.005418241 0.004499971 -0.001316726 -0.00789088 0.004499971 -0.002782583 -0.008558988 0.004499971 -0.00259757 -0.007566511 0.004499971 -0.00259757 0.007566511 0.004499971 -0.002778887 0.008559942 0.004499971 -0.001316726 0.00789088 0.004499971 0 -0.007999956 0.004499971 0.001316726 -0.00789088 0.004499971 0.001408219 -0.008889138 0.004499971 0.001408219 0.008889138 0.004499971 0.001316726 0.00789088 0.004499971 0.004084408 -0.008019626 0.004499971 0.00259757 -0.007566511 0.004499971 0.003807544 -0.007035732 0.004499971 0.006365001 0.006362795 0.004499971 0.004913687 0.006313085 0.004499971 0.005291044 0.007280349 0.004499971 0.005885779 -0.005418241 0.004499971 0.006697297 -0.004375576 0.004499971 0.007279515 -0.005291879 0.004499971 0.007972657 -6.60636e-4 0.004499971 0.008888602 -0.001410424 0.004499971 0.00775516 -0.001963853 0.004499971 0.008560061 0.002778947 0.004499971 0.008889436 0.001405477 0.004499971 0.00775516 0.001963853 0.004499971 0.007326185 0.003213524 0.004499971 0.008019864 0.004083991 0.004499971 0.007972657 6.60634e-4 0.004499971 0.008999824 -2.5352e-6 0.004499971 0.005885779 0.005418241 0.004499971 0.007282137 0.005288481 0.004499971 0.006697297 0.004375576 0.004499971 0.008017718 -0.004088044 0.004499971 0.007326185 -0.003213524 0.004499971 0.008558511 -0.002783536 0.004499971 0.004913687 -0.006313085 0.004499971 0.006362199 -0.006365358 0.004499971 0.003807544 0.007035732 0.004499971 0 0.007999956 0.004499971 0 0.008999943 0.004499971 0.005288362 -0.007282137 0.004499971 0.00278002 -0.008559703 0.004499971 -0.004913687 0.006313085 0.004499971 -0.005287408 0.007282733 0.004499971 -0.003807544 0.007035732 0.004499971 -0.004083216 0.008020102 0.004499971 0 -0.008999943 0.004499971 -0.001408636 -0.008889019 0.004499971 -0.006361663 0.006365895 0.004499971 -0.001408636 0.008889019 -0.004499971 0.007279515 0.005291879 -0.006999969 0.01122897 0.009945273 -0.004499971 0.006362199 0.006365358 -0.004499971 0.008999824 2.53304e-6 -0.004499971 0.008889436 -0.001405477 -0.006999969 0.01488995 -0.001811683 -0.004499971 0.005288362 0.007282137 -0.006999969 0.009948968 0.01122528 -0.006999969 0.008524894 0.01234155 -0.004499971 0.004084408 0.008019626 -0.006999969 0.006973326 0.01328039 -0.006999969 0.005320668 0.01402437 -0.004499971 0.00278002 0.008559703 -0.006999969 0.003594517 0.01456248 -0.006999969 0.001811683 0.01488995 -0.004499971 0.001408219 0.008889138 -0.006999969 0 0.01499998 -0.004499971 0 0.008999943 -0.004499971 0.008017718 0.004088044 -0.006999969 0.01234728 0.008516848 -0.006999969 0.01402556 0.005318105 -0.006999969 0.01328337 0.006966948 -0.004499971 0.008558511 0.002783536 -0.006999969 0.01456499 0.003585457 -0.004499971 0.008888602 0.001410424 -0.006999969 0.01488995 0.001811683 -0.006999969 0.01499998 0 -0.006999969 0.01402437 -0.005320668 -0.006999969 0.01456248 -0.003594517 -0.004499971 0.008560061 -0.002778947 -0.006999969 0.009945273 -0.01122897 -0.004499971 0.006365001 -0.006362795 -0.004499971 0.005291044 -0.007280349 -0.006999969 0.01234155 -0.008524894 -0.004499971 0.008019864 -0.004083991 -0.004499971 0.007282137 -0.005288481 -0.004499971 0.002781748 -0.008559286 -0.004499971 0.001408219 -0.008889138 -0.006999969 0.003585457 -0.01456499 -0.004499971 0.004086732 -0.008018553 -0.006999969 0.006966948 -0.01328337 -0.006999969 0.008516848 -0.01234728 -0.004499971 -0.002778887 -0.008559942 -0.006999969 -0.003594517 -0.01456248 -0.004499971 -0.001408636 -0.008889019 -0.006999969 0 -0.01499998 -0.006999969 0.001811683 -0.01488995 -0.004499971 0 -0.008999943 -0.006999969 -0.009948968 -0.01122528 -0.004499971 -0.005287408 -0.007282733 -0.004499971 -0.006361663 -0.006365895 -0.006999969 -0.006973326 -0.01328039 -0.004499971 -0.004083216 -0.008020102 -0.006999969 -0.008524894 -0.01234155 -0.004499971 -0.008017957 -0.004087805 -0.004499971 -0.008558988 -0.002782583 -0.006999969 -0.01402556 -0.005318105 -0.006999969 -0.01234728 -0.008516848 -0.004499971 -0.007279455 -0.005292117 -0.006999969 -0.01456248 0.003594517 -0.006999969 -0.01488995 0.001811683 -0.004499971 -0.008889198 0.00140649 -0.006999969 -0.01488995 -0.001811683 -0.004499971 -0.008889019 -0.001408636 -0.004499971 -0.008999943 0 -0.006999969 -0.01234155 0.008524894 -0.004499971 -0.008020102 0.004083216 -0.004499971 -0.007282733 0.005287408 -0.004499971 -0.008559942 0.002778887 -0.006999969 -0.01402437 0.005320668 -0.004499971 -0.006365895 0.006361663 -0.006999969 -0.01122528 0.009948968 -0.004499971 -0.005292117 0.007279455 -0.006999969 -0.009945273 0.01122897 -0.006999969 -0.008516848 0.01234728 -0.004499971 -0.004087805 0.008017957 -0.006999969 -0.005318105 0.01402556 -0.006999969 -0.006966948 0.01328337 -0.004499971 -0.002782583 0.008558988 -0.006999969 -0.003585457 0.01456499 -0.006999969 -0.001811683 0.01488995 -0.004499971 -0.001408636 0.008889019 -0.006999969 -0.01328039 0.006973326 -0.006999969 -0.01499998 0 -0.006999969 -0.01456499 -0.003585457 -0.006999969 -0.01328337 -0.006966948 -0.006999969 -0.01122897 -0.009945273 -0.006999969 -0.005320668 -0.01402437 -0.006999969 -0.001811683 -0.01488995 -0.006999969 0.005318105 -0.01402556 -0.006999969 0.01122528 -0.009948968 -0.006999969 0.01328039 -0.006973326 0.001880288 0.0117619 0.01401728 0.003089666 0.008974134 0.01554369 0.001880288 0.009149134 0.01584678 -0.004232764 0.01717036 0.003027558 -0.004232764 0.01638376 0.005963206 -0.005283236 0.01651269 0.002911627 -0.006214439 0.015953 0 -0.006214439 0.01571059 0.002770185 -0.006999969 0.01488995 0.001811683 0.003089666 0.01153689 0.01374918 0.003089666 0.01374918 0.01153689 0.004232823 0.01120716 0.01335614 -0.003089606 0.01794826 0 -0.001880228 0.01802027 0.003177464 -0.003089606 0.01767557 0.003116667 -0.004232764 0.01743525 0 -0.006999969 0.01328337 0.006966948 -0.006214439 0.01499086 0.005456209 -0.006214439 0.0138157 0.007976472 6.31218e-4 0.01600176 0.0092386 0.001880288 0.01401728 0.0117619 6.31218e-4 0.01415437 0.011877 0.001880288 0.01584678 0.009149134 -6.31142e-4 0.01415437 0.01187688 -6.31142e-4 0.01600176 0.0092386 0.006214439 0.01222068 0.01025438 0.006999969 0.01122546 0.009949088 0.006999969 0.009943902 0.01122987 0.006214439 0.01025438 0.01222068 0.005283236 0.01077789 0.01284456 0.005283236 0.01284456 0.01077789 0.006999969 0.008518934 0.01234585 0.006999969 0.01234388 0.008522093 0.006214439 0.0138157 0.007976472 0.006214439 0.007976472 0.0138157 0.006999969 0.0132811 0.006971895 0.006999969 0.01456308 0.003593087 0.006999969 0.01402366 0.005322217 0.006214439 0.01499086 0.005456209 0.005283236 0.0167675 0 0.006214439 0.01571059 0.002770185 0.005283236 0.01651269 0.002911627 0.001880288 0.01802027 0.003177464 6.31218e-4 0.01847726 0 0.001880288 0.01829826 0 -6.31142e-4 0.01736289 0.006319582 6.31218e-4 0.01736289 0.006319582 0.006214439 0.015953 0 0.006999969 0.01489025 0.001810133 0.006999969 0.01499998 0 -0.001880228 0.01584678 0.009149134 -0.006999969 0.01402556 0.005318105 -0.006999969 0.01456499 0.003585457 -0.006999969 0.01499998 0 0.004232823 0.01335614 0.01120716 0.006214439 0.005456209 0.01499086 0.006999969 0.006970167 0.01328217 0.005283236 0.008383691 0.014521 0.005283236 0.005734801 0.01575624 0.006999969 0.005316495 0.01402604 0.006999969 0.003586053 0.01456475 0.006214439 0 0.015953 0.006214439 0.002770185 0.01571059 0.006999969 0.001810133 0.01489025 0.005283236 0.002911627 0.01651269 0.005283236 0 0.0167675 0.006999969 0 0.01499998 0.006999969 -0.001811683 0.01488995 0.006214439 -0.005456209 0.01499086 0.006214439 -0.002770185 0.01571059 0.006999969 -0.003594517 0.01456248 0.005283236 -0.005734801 0.01575624 0.006214439 -0.007976472 0.0138157 0.005283236 -0.008383691 0.014521 0.001880288 -0.01176184 0.01401728 0.003089666 -0.01374918 0.01153689 0.001880288 -0.01401728 0.0117619 0.004232823 -0.008717596 0.01509934 0.004232823 -0.005963206 0.01638376 6.31218e-4 -0.01415437 0.011877 6.31218e-4 -0.011877 0.01415437 -6.31142e-4 -0.01600176 0.0092386 6.31218e-4 -0.01600176 0.0092386 6.31218e-4 -0.01736289 0.006319582 -0.001880228 -0.009149134 0.01584678 -6.31142e-4 -0.01187688 0.01415437 -0.001880228 -0.01176184 0.01401728 -0.001880228 -0.01584678 0.009149134 -6.31142e-4 -0.01736289 0.006319582 -0.001880228 -0.01401728 0.0117619 -6.31142e-4 -0.01415437 0.01187688 0.003089666 -0.008974134 0.01554369 0.004232823 -0.01120716 0.01335614 0.003089666 -0.01153689 0.01374918 -0.003089606 -0.01794826 0 -0.004232764 -0.01743525 0 -0.004232764 -0.01717036 0.003027558 -0.003089606 -0.01686584 0.006138622 -0.003089606 -0.01767557 0.003116667 -0.004232764 -0.01638376 0.005963206 -0.005283236 -0.01575624 0.005734801 -0.005283236 -0.01651269 0.002911627 0.005283236 -0.002911627 0.01651269 -0.005283236 -0.0167675 0 -0.006214439 -0.01571059 0.002770185 0.006999969 -0.005320668 0.01402437 0.006999969 -0.006973326 0.01328039 -0.006214439 -0.015953 0 -0.006999969 -0.01488995 0.001811683 0.006999969 -0.008524894 0.01234155 -0.006999969 -0.01499998 0 0.006999969 -0.009948968 0.01122528 0.006214439 -0.01025438 0.01222068 0.006999969 -0.01234728 0.008516848 0.006214439 -0.0138157 0.007976472 0.006214439 -0.01222068 0.01025438 0.006999969 -0.01122897 0.009945273 0.006214439 -0.01499086 0.005456209 0.006999969 -0.01328337 0.006966948 0.006999969 -0.01402556 0.005318105 0.006999969 -0.01456499 0.003585457 0.006214439 -0.01571059 0.002770185 0.006999969 -0.01488995 0.001811683 0.006999969 -0.01499998 0 0.006214439 -0.015953 0 0.004232823 0.01717036 0.003027558 0.004232823 0.01743525 0 0.005283236 0.01575624 0.005734801 0.005283236 0.014521 0.008383691 0.004232823 0.005963206 0.01638376 0.004232823 0.008717596 0.01509934 0.003089666 0 0.01794826 0.004232823 -0.003027558 0.01717036 0.003089666 -0.003116667 0.01767557 0.003089666 -0.006138622 0.01686584 0.005283236 -0.01077789 0.01284456 0.005283236 -0.01284456 0.01077789 0.005283236 -0.014521 0.008383691 0.005283236 -0.01575624 0.005734801 0.005283236 -0.01651269 0.002911627 0.003089666 0.01767557 0.003116667 0.003089666 0.01794826 0 0.004232823 0.01638376 0.005963206 0.004232823 0.0150994 0.008717596 0.001880288 0.006258368 0.01719474 0.003089666 0.003116667 0.01767557 0.001880288 0.003177464 0.01802027 0.004232823 0.003027558 0.01717036 0.004232823 0 0.01743525 0.004232823 -0.01335614 0.01120716 0.004232823 -0.01509934 0.008717596 0.004232823 -0.01638376 0.005963206 0.005283236 -0.0167675 0 0.004232823 -0.01717036 0.003027558 6.31218e-4 0.01819646 0.003208518 -6.31142e-4 0.0184772 0 0.003089666 0.01686584 0.006138622 0.003089666 0.01554369 0.008974134 0.003089666 0.006138622 0.01686584 6.31218e-4 -0.003208518 0.01819646 0.001880288 -0.006258368 0.01719474 6.31218e-4 -0.006319582 0.01736289 6.31218e-4 -0.0092386 0.01600176 0.003089666 -0.01554369 0.008974134 0.003089666 -0.01686584 0.006138622 0.004232823 -0.01743525 0 0.003089666 -0.01767557 0.003116667 -6.31142e-4 0.01819646 0.003208518 -0.001880228 0.01829826 0 0.001880288 0.0171948 0.006258368 -0.003089606 0.01153689 0.01374918 -0.001880228 0.0117619 0.01401728 -0.001880228 0.009149134 0.01584678 6.31218e-4 0.006319582 0.01736289 -6.31142e-4 0.006319582 0.01736289 -6.31142e-4 0.0092386 0.01600176 6.31218e-4 0 0.01847726 -6.31142e-4 0 0.0184772 -6.31142e-4 0.003208518 0.01819646 0.001880288 0 0.01829826 0.001880288 -0.003177464 0.01802027 0.001880288 -0.009149134 0.01584678 0.001880288 -0.01584678 0.009149134 0.001880288 -0.01719474 0.006258368 0.003089666 -0.01794826 0 0.001880288 -0.01802027 0.003177464 -0.005283236 0.0167675 0 6.31218e-4 0.011877 0.01415437 6.31218e-4 0.0092386 0.01600176 6.31218e-4 0.003208518 0.01819646 -0.001880228 -0.006258368 0.01719474 -6.31142e-4 -0.006319582 0.01736289 -6.31142e-4 -0.0092386 0.01600176 -0.003089606 -0.01374918 0.01153689 0.001880288 -0.01829826 0 6.31218e-4 -0.01819646 0.003208518 -6.31142e-4 0.01187688 0.01415437 -0.004232764 0.003027558 0.01717036 -0.003089606 0.003116667 0.01767557 -0.003089606 0 0.01794826 -0.005283236 -0.005734801 0.01575624 -0.004232764 -0.005963206 0.01638376 -0.004232764 -0.008717596 0.01509934 -6.31142e-4 -0.003208518 0.01819646 6.31218e-4 -0.01847726 0 -6.31142e-4 -0.01819646 0.003208518 -0.005283236 0.01575624 0.005734801 -0.006214439 0.01222068 0.01025438 -0.005283236 0.01077789 0.01284456 -0.006214439 0.01025438 0.01222068 -0.001880228 0.0171948 0.006258368 -0.001880228 0.01401728 0.0117619 -0.001880228 0.006258368 0.01719474 -0.001880228 0.003177464 0.01802027 -0.001880228 0 0.01829826 -0.001880228 -0.003177464 0.01802027 -0.005283236 -0.01284456 0.01077789 -0.006214439 -0.01222068 0.01025438 -0.006214439 -0.01025438 0.01222068 -0.001880228 -0.01719474 0.006258368 -0.003089606 -0.01554369 0.008974134 -6.31142e-4 -0.0184772 0 -0.001880228 -0.01802027 0.003177464 -0.003089606 0.01554369 0.008974134 -0.003089606 0.01686584 0.006138622 -0.003089606 0.01374918 0.01153689 -0.006214439 0.005456209 0.01499086 -0.006214439 0.007976472 0.0138157 -0.005283236 0.005734801 0.01575624 -0.003089606 0.008974134 0.01554369 -0.003089606 0.006138622 0.01686584 -0.003089606 -0.003116667 0.01767557 -0.003089606 -0.006138622 0.01686584 -0.003089606 -0.008974134 0.01554369 -0.003089606 -0.01153689 0.01374918 -0.006214439 -0.01499086 0.005456209 -0.006214439 -0.0138157 0.007976472 -0.001880228 -0.01829826 0 -0.004232764 0.0150994 0.008717596 -0.004232764 0.01335614 0.01120716 -0.004232764 0.01120716 0.01335614 -0.004232764 0.008717596 0.01509934 -0.004232764 0.005963206 0.01638376 -0.006999969 -0.001811683 0.01488995 -0.006214439 0 0.015953 -0.006214439 -0.002770185 0.01571059 -0.004232764 0 0.01743525 -0.004232764 -0.003027558 0.01717036 -0.004232764 -0.01120716 0.01335614 -0.004232764 -0.01335614 0.01120716 -0.004232764 -0.01509934 0.008717596 -0.005283236 0.014521 0.008383691 -0.005283236 0.01284456 0.01077789 -0.005283236 0.008383691 0.014521 -0.005283236 0.002911627 0.01651269 -0.005283236 0 0.0167675 -0.005283236 -0.002911627 0.01651269 -0.006999969 -0.006966948 0.01328337 -0.006214439 -0.005456209 0.01499086 -0.006214439 -0.007976472 0.0138157 -0.005283236 -0.008383691 0.014521 -0.005283236 -0.01077789 0.01284456 -0.005283236 -0.014521 0.008383691 -0.006999969 0.01122897 0.009945273 -0.006999969 0.006973326 0.01328039 -0.006214439 0.002770185 0.01571059 -0.006999969 -0.009945273 0.01122897 -0.006999969 -0.01328039 0.006973326 -0.006999969 0.01234728 0.008516848 -0.006999969 0.009948968 0.01122528 -0.006999969 0.008524894 0.01234155 -0.006999969 0.005320668 0.01402437 -0.006999969 0.003594517 0.01456248 -0.006999969 0.001811683 0.01488995 -0.006999969 0 0.01499998 -0.006999969 -0.003585457 0.01456499 -0.006999969 -0.005318105 0.01402556 -0.006999969 -0.008516848 0.01234728 -0.006999969 -0.01122528 0.009948968 -0.006999969 -0.01234155 0.008524894 -0.006999969 -0.01402437 0.005320668 -0.006999969 -0.01456248 0.003594517 0.004499971 0.007279515 -0.005291879 0.006999969 0.01122897 -0.009945273 0.004499971 0.006362199 -0.006365358 0.004499971 0.008999824 -2.5352e-6 0.004499971 0.008889436 0.001405477 0.006999969 0.01489025 0.001810133 0.004499971 0.005288362 -0.007282137 0.006999969 0.009948968 -0.01122528 0.006999969 0.008524894 -0.01234155 0.004499971 0.004084408 -0.008019626 0.006999969 0.006973326 -0.01328039 0.006999969 0.005320668 -0.01402437 0.004499971 0.00278002 -0.008559703 0.006999969 0.003594517 -0.01456248 0.006999969 0.001811683 -0.01488995 0.004499971 0.001408219 -0.008889138 0.006999969 0 -0.01499998 0.004499971 0 -0.008999943 0.004499971 0.008017718 -0.004088044 0.006999969 0.01234728 -0.008516848 0.006999969 0.01402556 -0.005318105 0.006999969 0.01328337 -0.006966948 0.004499971 0.008558511 -0.002783536 0.006999969 0.01456499 -0.003585457 0.004499971 0.008888602 -0.001410424 0.006999969 0.01488995 -0.001811683 0.006999969 0.01499998 0 0.006999969 0.01402366 0.005322217 0.006999969 0.01456308 0.003593087 0.004499971 0.008560061 0.002778947 0.006999969 0.009943902 0.01122987 0.004499971 0.006365001 0.006362795 0.004499971 0.005291044 0.007280349 0.006999969 0.01234388 0.008522093 0.004499971 0.008019864 0.004083991 0.004499971 0.007282137 0.005288481 0.004499971 0.002781748 0.008559286 0.004499971 0.001408219 0.008889138 0.006999969 0.003586053 0.01456475 0.004499971 0.004086732 0.008018553 0.006999969 0.006970167 0.01328217 0.006999969 0.008518934 0.01234585 0.004499971 -0.002778887 0.008559942 0.006999969 -0.003594517 0.01456248 0.004499971 -0.001408636 0.008889019 0.006999969 0 0.01499998 0.006999969 0.001810133 0.01489025 0.004499971 0 0.008999943 0.006999969 -0.009948968 0.01122528 0.004499971 -0.005287408 0.007282733 0.004499971 -0.006361663 0.006365895 0.006999969 -0.006973326 0.01328039 0.004499971 -0.004083216 0.008020102 0.006999969 -0.008524894 0.01234155 0.004499971 -0.008017957 0.004087805 0.004499971 -0.008558988 0.002782583 0.006999969 -0.01402556 0.005318105 0.006999969 -0.01234728 0.008516848 0.004499971 -0.007279455 0.005292117 0.006999969 -0.01456248 -0.003594517 0.006999969 -0.01488995 -0.001811683 0.004499971 -0.008889198 -0.00140655 0.006999969 -0.01488995 0.001811683 0.004499971 -0.008889019 0.001408636 0.004499971 -0.008999943 0 0.006999969 -0.01234155 -0.008524894 0.004499971 -0.008020102 -0.004083216 0.004499971 -0.007282733 -0.005287408 0.004499971 -0.008559942 -0.002778887 0.006999969 -0.01402437 -0.005320668 0.004499971 -0.006365895 -0.006361663 0.006999969 -0.01122528 -0.009948968 0.004499971 -0.005292117 -0.007279455 0.006999969 -0.009945273 -0.01122897 0.006999969 -0.008516848 -0.01234728 0.004499971 -0.004087805 -0.008017957 0.006999969 -0.005318105 -0.01402556 0.006999969 -0.006966948 -0.01328337 0.004499971 -0.002782583 -0.008558988 0.006999969 -0.003585457 -0.01456499 0.006999969 -0.001811683 -0.01488995 0.004499971 -0.001408636 -0.008889019 0.006999969 -0.01328039 -0.006973326 0.006999969 -0.01499998 0 0.006999969 -0.01456499 0.003585457 0.006999969 -0.01328337 0.006966948 0.006999969 -0.01122897 0.009945273 0.006999969 -0.005320668 0.01402437 0.006999969 -0.001811683 0.01488995 0.006999969 0.005316495 0.01402604 0.006999969 0.01122546 0.009949088 0.006999969 0.0132811 0.006971895 0.001880288 -0.01176184 -0.01401728 0.003089666 -0.008974134 -0.01554369 0.001880288 -0.009149134 -0.01584678 0.001880288 0.01401728 -0.0117619 6.31218e-4 0.01415437 -0.011877 6.31218e-4 0.011877 -0.01415437 0.001880288 -0.01401728 -0.0117619 0.001880288 -0.01584678 -0.009149134 0.003089666 -0.01374918 -0.01153689 0.004232823 -0.01120716 -0.01335614 0.003089666 -0.01153689 -0.01374918 6.31218e-4 -0.01415437 -0.011877 -6.31142e-4 -0.01415437 -0.01187688 -6.31142e-4 -0.01600176 -0.0092386 6.31218e-4 -0.01600176 -0.0092386 -0.004232764 -0.01717036 -0.003027558 -0.004232764 -0.01743525 0 -0.003089606 -0.01767557 -0.003116667 -0.001880228 -0.01584678 -0.009149134 -0.006999969 -0.01328337 -0.006966948 -0.006214439 -0.01499086 -0.005456209 -0.006214439 -0.0138157 -0.007976472 -0.004232764 -0.01638376 -0.005963206 -0.005283236 -0.01651269 -0.002911627 -0.006999969 -0.01402556 -0.005318105 -0.006999969 -0.01456499 -0.003585457 -0.006999969 -0.01488995 -0.001811683 -0.006214439 -0.015953 0 -0.006214439 -0.01571059 -0.002770185 -0.006999969 -0.01499998 0 0.004232823 -0.01335614 -0.01120716 0.005283236 -0.01077789 -0.01284456 -0.003089606 -0.01794826 0 -0.001880228 -0.01802027 -0.003177464 0.006999969 -0.005318105 -0.01402556 0.006214439 -0.005456209 -0.01499086 0.006999969 -0.006966948 -0.01328337 0.006214439 -0.007976472 -0.0138157 0.006999969 -0.008516848 -0.01234728 0.006214439 0 -0.015953 0.006999969 -0.001811683 -0.01488995 0.006999969 0 -0.01499998 0.005283236 0 -0.0167675 0.005283236 -0.002911627 -0.01651269 0.006999969 0.005320668 -0.01402437 0.006214439 0.005456209 -0.01499086 0.006999969 0.003594517 -0.01456248 0.006214439 0.002770185 -0.01571059 0.006999969 0.001811683 -0.01488995 0.006999969 0.009948968 -0.01122528 0.006999969 0.01122897 -0.009945273 0.006214439 0.01025438 -0.01222068 0.006999969 0.008524894 -0.01234155 0.006214439 0.007976472 -0.0138157 0.006999969 0.006973326 -0.01328039 0.005283236 0.008383691 -0.014521 0.005283236 0.005734801 -0.01575624 0.005283236 0.002911627 -0.01651269 0.004232823 0.01120716 -0.01335614 0.003089666 0.01153689 -0.01374918 0.003089666 0.008974134 -0.01554369 -6.31142e-4 0.01600176 -0.0092386 6.31218e-4 0.01600176 -0.0092386 6.31218e-4 0.01736289 -0.006319582 0.003089666 0.01374918 -0.01153689 0.001880288 0.0117619 -0.01401728 -6.31142e-4 0.01187688 -0.01415437 -0.001880228 0.0117619 -0.01401728 -0.001880228 0.009149134 -0.01584678 0.004232823 0.008717596 -0.01509934 0.004232823 0.005963206 -0.01638376 -0.004232764 0.01638376 -0.005963206 -0.003089606 0.01686584 -0.006138622 -0.003089606 0.01767557 -0.003116667 -6.31142e-4 0.01415437 -0.01187688 -0.001880228 0.01401728 -0.0117619 -0.005283236 0.01651269 -0.002911627 -0.005283236 0.01575624 -0.005734801 -0.004232764 0.01717036 -0.003027558 -0.003089606 0.01794826 0 -0.004232764 0.01743525 0 -0.006214439 0.01571059 -0.002770185 -0.006214439 0.015953 0 -0.006999969 0.01488995 -0.001811683 -0.005283236 0.0167675 0 -6.31142e-4 0.01736289 -0.006319582 -0.001880228 0.01584678 -0.009149134 -0.006999969 0.01499998 0 0.006999969 0.01328337 -0.006966948 0.006214439 0.01499086 -0.005456209 0.006214439 0.0138157 -0.007976472 0.006214439 0.01222068 -0.01025438 0.006999969 0.01234728 -0.008516848 0.006999969 0.01402556 -0.005318105 0.006999969 0.01488995 -0.001811683 0.006214439 0.01571059 -0.002770185 0.006999969 0.01456499 -0.003585457 0.006999969 0.01499998 0 0.006214439 0.015953 0 0.006214439 -0.002770185 -0.01571059 0.006999969 -0.003585457 -0.01456499 0.005283236 -0.005734801 -0.01575624 0.005283236 -0.008383691 -0.014521 0.005283236 -0.01284456 -0.01077789 0.006214439 -0.01025438 -0.01222068 0.006999969 -0.01488995 -0.001811683 0.006214439 -0.015953 0 0.006999969 -0.01499998 0 0.006999969 -0.009945273 -0.01122897 0.006214439 -0.01222068 -0.01025438 0.006214439 -0.0138157 -0.007976472 0.006999969 -0.01234155 -0.008524894 0.006999969 -0.01122528 -0.009948968 0.006999969 -0.01328039 -0.006973326 6.31218e-4 -0.01736289 -0.006319582 -6.31142e-4 -0.01736289 -0.006319582 0.006214439 -0.01499086 -0.005456209 0.006999969 -0.01402437 -0.005320668 0.006999969 -0.01456248 -0.003594517 0.006214439 -0.01571059 -0.002770185 0.005283236 -0.0167675 0 0.001880288 -0.01802027 -0.003177464 6.31218e-4 -0.01847726 0 0.001880288 -0.01829826 0 0.005283236 -0.01651269 -0.002911627 0.004232823 -0.01717036 -0.003027558 0.004232823 -0.01743525 0 0.005283236 -0.01575624 -0.005734801 0.005283236 -0.014521 -0.008383691 0.004232823 -0.005963206 -0.01638376 0.004232823 -0.008717596 -0.01509934 0.003089666 0 -0.01794826 0.004232823 0.003027558 -0.01717036 0.003089666 0.003116667 -0.01767557 0.003089666 0.006138622 -0.01686584 0.005283236 0.01077789 -0.01284456 0.005283236 0.01284456 -0.01077789 0.005283236 0.014521 -0.008383691 0.005283236 0.01575624 -0.005734801 0.005283236 0.01651269 -0.002911627 0.003089666 -0.01767557 -0.003116667 0.003089666 -0.01794826 0 0.004232823 -0.01638376 -0.005963206 0.004232823 -0.01509934 -0.008717596 0.001880288 -0.006258368 -0.0171948 0.003089666 -0.003116667 -0.01767557 0.001880288 -0.003177464 -0.01802027 0.004232823 -0.003027558 -0.01717036 0.004232823 0 -0.01743525 0.004232823 0.01335614 -0.01120716 0.004232823 0.0150994 -0.008717596 0.004232823 0.01638376 -0.005963206 0.005283236 0.0167675 0 0.004232823 0.01717036 -0.003027558 6.31218e-4 -0.01819646 -0.003208518 -6.31142e-4 -0.0184772 0 0.003089666 -0.01686584 -0.006138622 0.003089666 -0.01554369 -0.008974134 0.003089666 -0.006138622 -0.01686584 6.31218e-4 0.003208518 -0.01819646 0.001880288 0.006258368 -0.0171948 6.31218e-4 0.006319582 -0.01736289 6.31218e-4 0.0092386 -0.01600176 0.003089666 0.01554369 -0.008974134 0.003089666 0.01686584 -0.006138622 0.004232823 0.01743525 0 0.003089666 0.01767557 -0.003116667 -6.31142e-4 -0.01819646 -0.003208518 -0.001880228 -0.01829826 0 0.001880288 -0.01719474 -0.006258368 -0.003089606 -0.01153689 -0.01374918 -0.001880228 -0.01176184 -0.01401728 -0.001880228 -0.009149134 -0.01584678 6.31218e-4 -0.006319582 -0.01736289 -6.31142e-4 -0.006319582 -0.01736289 -6.31142e-4 -0.0092386 -0.01600176 6.31218e-4 0 -0.01847726 -6.31142e-4 0 -0.0184772 -6.31142e-4 -0.003208518 -0.01819646 0.001880288 0 -0.01829826 0.001880288 0.003177464 -0.01802027 0.001880288 0.009149134 -0.01584678 0.001880288 0.01584678 -0.009149134 0.001880288 0.0171948 -0.006258368 0.003089666 0.01794826 0 0.001880288 0.01802027 -0.003177464 -0.005283236 -0.0167675 0 6.31218e-4 -0.011877 -0.01415437 6.31218e-4 -0.0092386 -0.01600176 6.31218e-4 -0.003208518 -0.01819646 -0.001880228 0.006258368 -0.0171948 -6.31142e-4 0.006319582 -0.01736289 -6.31142e-4 0.0092386 -0.01600176 -0.003089606 0.01374918 -0.01153689 0.001880288 0.01829826 0 6.31218e-4 0.01819646 -0.003208518 -6.31142e-4 -0.01187688 -0.01415437 -0.004232764 -0.003027558 -0.01717036 -0.003089606 -0.003116667 -0.01767557 -0.003089606 0 -0.01794826 -0.005283236 0.005734801 -0.01575624 -0.004232764 0.005963206 -0.01638376 -0.004232764 0.008717596 -0.01509934 -6.31142e-4 0.003208518 -0.01819646 6.31218e-4 0.01847726 0 -6.31142e-4 0.01819646 -0.003208518 -0.005283236 -0.01575624 -0.005734801 -0.006214439 -0.01222068 -0.01025438 -0.005283236 -0.01077789 -0.01284456 -0.006214439 -0.01025438 -0.01222068 -0.001880228 -0.01719474 -0.006258368 -0.001880228 -0.01401728 -0.0117619 -0.001880228 -0.006258368 -0.0171948 -0.001880228 -0.003177464 -0.01802027 -0.001880228 0 -0.01829826 -0.001880228 0.003177464 -0.01802027 -0.005283236 0.01284456 -0.01077789 -0.006214439 0.01222068 -0.01025438 -0.006214439 0.01025438 -0.01222068 -0.001880228 0.0171948 -0.006258368 -0.003089606 0.01554369 -0.008974134 -6.31142e-4 0.0184772 0 -0.001880228 0.01802027 -0.003177464 -0.003089606 -0.01554369 -0.008974134 -0.003089606 -0.01686584 -0.006138622 -0.003089606 -0.01374918 -0.01153689 -0.006214439 -0.005456209 -0.01499086 -0.006214439 -0.007976472 -0.0138157 -0.005283236 -0.005734801 -0.01575624 -0.003089606 -0.008974134 -0.01554369 -0.003089606 -0.006138622 -0.01686584 -0.003089606 0.003116667 -0.01767557 -0.003089606 0.006138622 -0.01686584 -0.003089606 0.008974134 -0.01554369 -0.003089606 0.01153689 -0.01374918 -0.006214439 0.01499086 -0.005456209 -0.006214439 0.0138157 -0.007976472 -0.001880228 0.01829826 0 -0.004232764 -0.01509934 -0.008717596 -0.004232764 -0.01335614 -0.01120716 -0.004232764 -0.01120716 -0.01335614 -0.004232764 -0.008717596 -0.01509934 -0.004232764 -0.005963206 -0.01638376 -0.006999969 0.001811683 -0.01488995 -0.006214439 0 -0.015953 -0.006214439 0.002770185 -0.01571059 -0.004232764 0 -0.01743525 -0.004232764 0.003027558 -0.01717036 -0.004232764 0.01120716 -0.01335614 -0.004232764 0.01335614 -0.01120716 -0.004232764 0.0150994 -0.008717596 -0.005283236 -0.014521 -0.008383691 -0.005283236 -0.01284456 -0.01077789 -0.005283236 -0.008383691 -0.014521 -0.005283236 -0.002911627 -0.01651269 -0.005283236 0 -0.0167675 -0.005283236 0.002911627 -0.01651269 -0.006999969 0.006966948 -0.01328337 -0.006214439 0.005456209 -0.01499086 -0.006214439 0.007976472 -0.0138157 -0.005283236 0.008383691 -0.014521 -0.005283236 0.01077789 -0.01284456 -0.005283236 0.014521 -0.008383691 -0.006999969 -0.01122897 -0.009945273 -0.006999969 -0.006973326 -0.01328039 -0.006214439 -0.002770185 -0.01571059 -0.006999969 0.009945273 -0.01122897 -0.006999969 0.01328039 -0.006973326 -0.006999969 -0.01234728 -0.008516848 -0.006999969 -0.009948968 -0.01122528 -0.006999969 -0.008524894 -0.01234155 -0.006999969 -0.005320668 -0.01402437 -0.006999969 -0.003594517 -0.01456248 -0.006999969 -0.001811683 -0.01488995 -0.006999969 0 -0.01499998 -0.006999969 0.003585457 -0.01456499 -0.006999969 0.005318105 -0.01402556 -0.006999969 0.008516848 -0.01234728 -0.006999969 0.01122528 -0.009948968 -0.006999969 0.01234155 -0.008524894 -0.006999969 0.01402437 -0.005320668 -0.006999969 0.01456248 -0.003594517 + + + + + + + + + + 0 0.3246934 -0.9458194 0 0.4759479 -0.8794736 0 0 -1 0 0.164587 -0.9863626 0 0.7357248 -0.6772807 0 0.8371744 -0.546936 0 0.6142068 -0.7891451 0 0.9694057 -0.2454643 0 0.9965868 -0.08255296 0 0.9157767 -0.401688 0 0.9157767 0.401688 0 0.9694057 0.2454643 0 0.9965868 0.08255296 0 0.7357248 0.6772807 0 0.6142068 0.7891451 0 0.8371744 0.546936 0 0.3246934 0.9458194 0 0.164587 0.9863626 0 0.4759479 0.8794736 0 -0.3246934 0.9458194 0 -0.164587 0.9863626 0 0 1 0 -0.6142068 0.7891451 0 -0.7357248 0.6772807 0 -0.4759479 0.8794736 0 -0.9157767 0.401688 0 -0.9694057 0.2454643 0 -0.8371744 0.546936 0 -0.9965868 -0.08255296 0 -0.9965868 0.08255296 0 -0.9694057 -0.2454643 0 -0.9157767 -0.401688 0 -0.8371744 -0.546936 0 -0.7357248 -0.6772807 0 -0.6142068 -0.7891451 0 -0.4759479 -0.8794736 0 -0.3246934 -0.9458194 0 -0.164587 -0.9863626 -1 0 0 -1 -6.62389e-7 0 -1 -3.30979e-7 0 -1 3.35074e-7 0 -1 3.35174e-7 0 -1 0 0 -1 -3.35124e-7 0 -1 -6.62988e-7 0 -1 0 0 -1 1.70806e-7 0 -1 3.24933e-7 0 -1 3.25293e-7 0 -1 3.41582e-7 0 -1 -6.77401e-7 0 -1 -6.75167e-7 0 -1 6.75137e-7 0 -1 0 0 -1 -3.26204e-7 0 -1 1.63735e-7 0 -1 5.13364e-7 0 -1 0 0 -1 -1.65088e-7 0 -1 -3.30711e-7 0 -1 -3.31057e-7 0 -1 3.35173e-7 0 -1 -3.35472e-7 0 -1 2.52506e-7 0 -1 0 0 -1 -3.38702e-7 0 -1 -3.40034e-7 0 -1 3.41583e-7 0 -1 1.63744e-7 0 -1 1.64251e-7 0 -1 -3.30003e-7 0 -1 6.61988e-7 0 -1 -3.35177e-7 0 -1 0 0 -1 1.69379e-7 0 -1 6.48838e-7 0 -1 -6.51753e-7 0 1 0 0 1 6.61614e-7 0 1 6.62988e-7 0 1 -3.35124e-7 0 1 -3.35427e-7 0 1 -1.67967e-7 0 1 -5.04971e-7 0 1 -6.83224e-7 0 1 -3.41592e-7 0 1 -6.86703e-7 0 1 3.24513e-7 0 1 -3.40034e-7 0 1 6.73347e-7 0 1 -3.35074e-7 0 1 6.58516e-7 0 1 3.35472e-7 0 1 3.27223e-7 0 1 3.22919e-7 0 1 3.41582e-7 0 1 -1.69349e-7 0 1 0 0 1 1.63735e-7 0 1 0 0 1 0 0 1 -6.60351e-7 0 1 3.31057e-7 0 1 3.35173e-7 0 1 3.35472e-7 0 1 -1.67986e-7 0 1 0 0 1 -2.95386e-7 0 1 -6.86703e-7 0 1 3.25293e-7 0 1 -1.63744e-7 0 1 0 0 1 -1.64671e-7 0 1 1.65002e-7 0 1 3.30501e-7 0 1 3.3083e-7 0 1 -3.35511e-7 0 1 3.40078e-7 0 1 -1.69379e-7 0 -0.9237504 -0.3100124 -0.2248948 -0.9239338 -0.2704293 -0.2705819 -0.9228382 -0.2884365 -0.2552927 -0.9236916 -0.383137 -9.15573e-5 -0.9229633 -0.382101 0.04623663 -0.923838 -0.3781293 0.05951184 -0.9237275 -0.2247745 -0.3101676 -0.9228409 -0.2553851 -0.2883458 -0.9230647 -0.2183371 -0.3166711 -0.9236803 -0.1741704 -0.3412911 -0.9231063 -0.1789935 -0.3403471 -0.9228826 -0.1367584 -0.3599789 -0.9239112 -0.1183233 -0.3638513 -0.9228106 -0.0922597 -0.374044 -0.9229619 -0.04626709 -0.3821005 -0.9238419 -0.0596342 -0.3781004 -0.9236916 0 -0.383137 -0.9230824 0 -0.3846024 -0.923048 -0.3168485 -0.21815 -0.9236894 -0.3412029 -0.1742942 -0.9228886 -0.3599998 -0.1366632 -0.9230886 -0.340474 -0.1788434 -0.9239183 -0.363793 -0.1184464 -0.922813 -0.3740754 -0.09210729 -0.9229551 -0.3821282 -0.04617518 -0.9238476 -0.3780722 -0.05972611 -0.9230824 -0.3846024 0 -0.9228827 -0.3599789 0.1367584 -0.923911 -0.3638817 0.1182318 -0.9228106 -0.374044 0.0922597 -0.9228382 -0.2552927 0.2884365 -0.9237479 -0.2248637 0.3100421 -0.9239338 -0.2705514 0.2704598 -0.9230647 -0.3166711 0.2183371 -0.9237275 -0.3101676 0.2247745 -0.9236851 -0.3412929 0.1741408 -0.9239079 -0.1183534 0.3638499 -0.922813 -0.09210729 0.3740754 -0.9238419 -0.0596342 0.3781004 -0.9236896 -0.1742333 0.3412335 -0.923048 -0.21815 0.3168485 -0.9230836 -0.178873 0.3404721 -0.9239145 0.1182932 0.3638526 -0.9238419 0.0596342 0.3781004 -0.9228106 0.0922597 0.374044 -0.9230824 0 0.3846024 -0.9236916 0 0.383137 -0.9229551 -0.04617518 0.3821282 -0.9228409 0.2553851 0.2883458 -0.9239338 0.2703988 0.2706124 -0.9237315 0.2247145 0.3101994 -0.9231063 0.1789935 0.3403471 -0.9230647 0.2183371 0.3166711 -0.9236901 0.1741113 0.3412947 -0.9236894 0.3412029 0.1742942 -0.9228886 0.3599998 0.1366632 -0.9239115 0.3638209 0.1184149 -0.923744 0.3100103 0.2249238 -0.923048 0.3168485 0.21815 -0.9228106 0.374044 -0.0922597 -0.9238436 0.3781011 -0.05960375 -0.9229619 0.3821005 -0.04626709 -0.9229551 0.3821282 0.04617518 -0.9236916 0.383137 0 -0.9238402 0.3780997 0.0596646 -0.9230647 0.3166711 -0.2183371 -0.9237315 0.3101994 -0.2247145 -0.9236901 0.3412947 -0.1741113 -0.9239076 0.3638804 -0.1182619 -0.9228872 0.3599687 -0.1367545 -0.9239338 0.2706124 -0.2703988 -0.9228409 0.2883458 -0.2553851 -0.9228382 0.2552927 -0.2884365 -0.923744 0.2249238 -0.3100103 -0.923048 0.21815 -0.3168485 -0.9236894 0.1742942 -0.3412029 -0.9230836 0.178873 -0.3404721 -0.9228886 0.1366632 -0.3599998 -0.922813 0.09210729 -0.3740754 -0.9239115 0.1184149 -0.3638209 -0.9229551 0.04617518 -0.3821282 -0.9238402 0.0596646 -0.3780997 -0.9231063 0.3403471 -0.1789935 -0.9230824 0.3846024 0 -0.922813 0.3740754 0.09210729 -0.9230836 0.3404721 0.178873 -0.9228382 0.2884365 0.2552927 -0.9228872 0.1367545 0.3599687 -0.9229619 0.04626709 0.3821005 -0.9228886 -0.1366632 0.3599998 -0.9228327 -0.2883738 0.2553828 -0.9231063 -0.3403471 0.1789935 0.2096337 0.6285045 0.7490233 0.2096359 0.4888861 0.8467841 0.3433103 0.4695987 0.8133974 -0.472526 0.8679305 0.1530224 -0.5971353 0.7899544 0.1392888 -0.4725303 0.8281716 0.3014085 -0.710779 0.7011656 0.05621528 -0.7656107 0.6393517 0.07120186 -0.7116677 0.691861 0.121892 0.3433072 0.6037251 0.7194833 0.4725327 0.5665022 0.6751209 0.3433072 0.7194833 0.6037251 -0.3421461 0.9360723 0.08188188 -0.3433129 0.924952 0.1630957 -0.2096042 0.962934 0.1697769 -0.4711253 0.8787097 0.07687795 -0.7667806 0.572125 0.2910677 -0.7117974 0.6084292 0.3509393 -0.7119519 0.6597641 0.2404913 0.07080489 0.8638505 0.4987474 0.07080507 0.7641149 0.6411826 0.2096337 0.7490233 0.6285045 0.2096068 0.8467895 0.4888892 -0.07080507 0.7641149 0.6411826 -0.07080489 0.8638505 0.4987474 0.7120178 0.5374162 0.4519008 0.7679312 0.4310571 0.4737844 0.767794 0.473653 0.4314454 0.7120544 0.4518742 0.5373903 0.5971426 0.6144776 0.5155948 0.5971426 0.5155948 0.6144776 0.7642145 0.3675188 0.5300059 0.7641884 0.5299785 0.3676125 0.7117691 0.6084616 0.3509404 0.7117615 0.3509672 0.6084551 0.7667734 0.5720586 0.2912176 0.7647203 0.6246065 0.1583337 0.7119519 0.6597641 0.2404913 0.770773 0.5940644 0.2302095 0.5956819 0.8001634 0.07001197 0.5971353 0.7899544 0.1392888 0.71168 0.6918425 0.1219246 0.2096042 0.962934 0.1697769 0.2088713 0.974224 0.08520871 0.07049787 0.9937154 0.08694738 -0.07077443 0.9373422 0.3411458 0.07077443 0.9373422 0.3411458 0.7107651 0.701182 0.05618607 0.765609 0.6393504 0.07123219 0.7710922 0.6355575 0.03851491 -0.2096068 0.8467895 0.4888892 -0.7646861 0.6246951 0.1581498 -0.7707023 0.5942401 0.2299929 -0.7710781 0.635571 0.03857678 0.4725564 0.6751112 0.5664939 0.7119519 0.2404913 0.6597641 0.766734 0.2912142 0.572113 0.5971527 0.4010623 0.6946639 0.5971404 0.2743379 0.7537654 0.7647134 0.1581492 0.6246619 0.7707542 0.2298376 0.594233 0.7118973 0 0.7022837 0.7655975 0.07117009 0.6393712 0.71168 0.1219246 0.6918425 0.5971353 0.1392888 0.7899544 0.5971396 0 0.8021374 0.7656609 -0.0712924 0.6392816 0.7716747 -3.05191e-5 0.6360175 0.7119519 -0.2404913 0.6597641 0.7647439 -0.1583628 0.6245703 0.7117101 -0.1219246 0.6918116 0.5971404 -0.2743379 0.7537654 0.5971401 -0.4010537 0.6946796 0.7117974 -0.3509393 0.6084292 0.2096337 -0.6285045 0.7490233 0.2096337 -0.7490233 0.6285045 0.3433072 -0.7194833 0.6037251 0.4725632 -0.4406398 0.7632305 0.4725303 -0.3014085 0.8281716 0.07080507 -0.7641149 0.6411826 0.07080507 -0.6411826 0.7641149 -0.07080489 -0.8638505 0.4987474 0.07077443 -0.9373422 0.3411458 0.07080489 -0.8638505 0.4987474 -0.2096068 -0.4888892 0.8467895 -0.2096045 -0.6285085 0.7490281 -0.07080507 -0.6411826 0.7641149 -0.2096068 -0.8467895 0.4888892 -0.07077443 -0.9373422 0.3411458 -0.07080507 -0.7641149 0.6411826 -0.2096045 -0.7490281 0.6285085 0.3433103 -0.4695987 0.8133974 0.3433072 -0.6037251 0.7194833 0.4725564 -0.5664939 0.6751112 -0.3421461 -0.9360723 0.08188188 -0.472526 -0.8679305 0.1530224 -0.4711253 -0.8787097 0.07687795 -0.3433111 -0.8825863 0.3212151 -0.4725303 -0.8281716 0.3014085 -0.3433129 -0.924952 0.1630957 -0.5971404 -0.7537654 0.2743379 -0.5971497 -0.789943 0.1392922 0.5971353 -0.1392888 0.7899544 -0.5956819 -0.8001634 0.07001197 -0.7117101 -0.6918116 0.1219246 0.7707613 -0.2301144 0.5941165 0.7668057 -0.2913098 0.5719683 -0.7656609 -0.6392816 0.0712924 -0.710779 -0.7011656 0.05621528 0.7642674 -0.3676369 0.5298477 -0.7710781 -0.635571 0.03857678 0.7120428 -0.4518668 0.5374121 0.7679034 -0.4312723 0.4736335 0.7642618 -0.5300269 0.3673901 0.7120159 -0.5374454 0.4518692 0.7117974 -0.6084292 0.3509393 0.7678636 -0.4738414 0.4311145 0.7119519 -0.6597641 0.2404913 0.7667932 -0.5721117 0.2910609 0.7707023 -0.5942401 0.2299929 0.7116677 -0.691861 0.121892 0.7647007 -0.6246765 0.1581529 0.7656233 -0.6393368 0.07120019 0.7710905 -0.6355561 0.03857588 0.710779 -0.7011656 0.05621528 0.472526 0.8679305 0.1530224 0.4711253 0.8787097 0.07687795 0.5971404 0.7537654 0.2743379 0.5971401 0.6946796 0.4010537 0.4725303 0.3014085 0.8281716 0.4725632 0.4406398 0.7632305 0.3433085 0 0.9392228 0.3433129 -0.1630957 0.924952 0.472526 -0.1530224 0.8679305 0.3433111 -0.3212151 0.8825863 0.5971426 -0.5155948 0.6144776 0.5971426 -0.6144776 0.5155948 0.5971527 -0.6946638 0.4010622 0.5971404 -0.7537654 0.2743379 0.5971353 -0.7899544 0.1392888 0.3433129 0.924952 0.1630957 0.3421461 0.9360723 0.08188188 0.4725303 0.8281716 0.3014085 0.4725632 0.7632305 0.4406398 0.2096089 0.3344037 0.9188244 0.2096042 0.1697769 0.962934 0.3433129 0.1630957 0.924952 0.4725623 0.1530242 0.8679105 0.4725339 0 0.8813125 0.4725327 -0.6751209 0.5665022 0.4725632 -0.7632305 0.4406398 0.4725303 -0.8281716 0.3014085 0.5956819 -0.8001634 0.07001197 0.4725623 -0.8679105 0.1530242 -0.07053059 0.9937155 0.08691954 0.07077324 0.9823415 0.1731946 0.3433111 0.8825863 0.3212151 0.3433103 0.8133974 0.4695987 0.3433111 0.3212151 0.8825863 0.07077324 -0.1731946 0.9823415 0.07077443 -0.3411458 0.9373422 0.2096089 -0.3344037 0.9188244 0.07080489 -0.4987474 0.8638505 0.3433103 -0.8133974 0.4695987 0.3433111 -0.8825863 0.3212151 0.4711253 -0.8787097 0.07687795 0.3433129 -0.924952 0.1630957 -0.208842 0.9742302 0.08520925 -0.07077324 0.9823415 0.1731946 0.2096089 0.9188244 0.3344037 -0.3432803 0.6037314 0.7194908 -0.2096068 0.4888892 0.8467895 -0.2096045 0.6285085 0.7490281 0.07077443 0.3411458 0.9373422 -0.07080489 0.4987474 0.8638505 -0.07077443 0.3411458 0.9373422 0.07077419 0 0.9974924 -0.07077324 0.1731946 0.9823415 -0.07080459 0 0.9974903 0.2096374 0 0.9777792 0.2096042 -0.1697769 0.962934 0.2096068 -0.4888892 0.8467895 0.2096359 -0.8467841 0.4888861 0.2096089 -0.9188244 0.3344037 0.3421461 -0.9360723 0.08188188 0.2096042 -0.962934 0.1697769 -0.5956819 0.8001634 0.07001197 0.07080507 0.6411826 0.7641149 0.07080489 0.4987474 0.8638505 0.07077324 0.1731946 0.9823415 -0.2096089 -0.3344037 0.9188244 -0.07080489 -0.4987474 0.8638505 -0.07077443 -0.3411458 0.9373422 -0.3432803 -0.7194908 0.6037314 0.2088707 -0.9742214 0.08523899 0.07077324 -0.9823415 0.1731946 -0.07080507 0.6411826 0.7641149 -0.472526 0.1530224 0.8679305 -0.3433085 0 0.9392228 -0.3433129 0.1630957 0.924952 -0.5971404 -0.2743379 0.7537654 -0.4725632 -0.4406398 0.7632305 -0.4725303 -0.3014085 0.8281716 -0.07077324 -0.1731946 0.9823415 0.07053041 -0.9937129 0.08694988 -0.07077324 -0.9823415 0.1731946 -0.5971404 0.7537654 0.2743379 -0.7120159 0.5374454 0.4518692 -0.7120428 0.4518668 0.5374121 -0.5971426 0.5155948 0.6144776 -0.2096089 0.9188244 0.3344037 -0.2096045 0.7490281 0.6285085 -0.2096089 0.3344037 0.9188244 -0.2096042 0.1697769 0.962934 -0.209602 0 0.9777868 -0.2096042 -0.1697769 0.962934 -0.5971426 -0.6144776 0.5155948 -0.7120159 -0.4518692 0.5374454 -0.7120428 -0.5374121 0.4518668 -0.2096089 -0.9188244 0.3344037 -0.3433103 -0.8133974 0.4695987 -0.2096042 -0.962934 0.1697769 -0.07056093 -0.9937134 0.08691936 -0.3433103 0.8133974 0.4695987 -0.3433111 0.8825863 0.3212151 -0.3432803 0.7194908 0.6037314 -0.7119519 0.2404913 0.6597641 -0.5971404 0.2743379 0.7537654 -0.7117974 0.3509393 0.6084292 -0.3433103 0.4695987 0.8133974 -0.3433111 0.3212151 0.8825863 -0.3433129 -0.1630957 0.924952 -0.3433111 -0.3212151 0.8825863 -0.3433103 -0.4695987 0.8133974 -0.3432803 -0.6037314 0.7194908 -0.7119519 -0.6597641 0.2404913 -0.7117974 -0.6084292 0.3509393 -0.208842 -0.9742302 0.08520925 -0.4725632 0.7632305 0.4406398 -0.4725327 0.6751209 0.5665022 -0.4725327 0.5665022 0.6751209 -0.4725632 0.4406398 0.7632305 -0.4725303 0.3014085 0.8281716 -0.7656107 -0.07120186 0.6393517 -0.7116677 -0.121892 0.691861 -0.7119123 0 0.7022684 -0.4725339 0 0.8813125 -0.472526 -0.1530224 0.8679305 -0.4725327 -0.5665022 0.6751209 -0.4725327 -0.6751209 0.5665022 -0.4725632 -0.7632305 0.4406398 -0.5971527 0.6946638 0.4010622 -0.5971426 0.6144776 0.5155948 -0.5971401 0.4010537 0.6946796 -0.5971497 0.1392922 0.789943 -0.5971396 0 0.8021374 -0.5971353 -0.1392888 0.7899544 -0.7667806 -0.2910677 0.572125 -0.7117974 -0.3509393 0.6084292 -0.7119519 -0.2404913 0.6597641 -0.5971527 -0.4010623 0.6946639 -0.5971426 -0.5155948 0.6144776 -0.5971401 -0.6946796 0.4010537 -0.7678636 0.4738414 0.4311145 -0.7667923 0.2913048 0.5719889 -0.7117101 0.1219246 0.6918116 -0.7678636 -0.4311145 0.4738414 -0.7667923 -0.5719889 0.2913048 -0.7642405 0.5300333 0.3674251 -0.7679034 0.4312723 0.4736335 -0.7642464 0.3676574 0.5298637 -0.7707296 0.2301446 0.594146 -0.7647439 0.1583628 0.6245703 -0.7656609 0.0712924 0.6392816 -0.7716474 0 0.6360506 -0.7646861 -0.1581498 0.6246951 -0.7707023 -0.2299929 0.5942401 -0.7642405 -0.3674251 0.5300333 -0.7679034 -0.4736335 0.4312723 -0.7642464 -0.5298637 0.3676574 -0.7707296 -0.594146 0.2301446 -0.7647439 -0.6245703 0.1583628 0.9237504 -0.3100124 0.2248948 0.9239338 -0.2704293 0.2705819 0.9228382 -0.2884365 0.2552927 0.9237024 -0.383111 9.15584e-5 0.9229645 -0.3821015 -0.04620617 0.9238486 -0.3781031 -0.05951255 0.9237275 -0.2247745 0.3101676 0.9228409 -0.2553851 0.2883458 0.9230647 -0.2183371 0.3166711 0.9236803 -0.1741704 0.3412911 0.9231063 -0.1789935 0.3403471 0.9228826 -0.1367584 0.3599789 0.9239112 -0.1183233 0.3638513 0.9228106 -0.0922597 0.374044 0.9229619 -0.04626709 0.3821005 0.9238419 -0.0596342 0.3781004 0.9236916 0 0.383137 0.9230824 0 0.3846024 0.923048 -0.3168485 0.21815 0.9236894 -0.3412029 0.1742942 0.9228886 -0.3599998 0.1366632 0.9230886 -0.340474 0.1788434 0.9239183 -0.363793 0.1184464 0.9228156 -0.3740765 0.09207707 0.9229551 -0.3821282 0.04617518 0.9238476 -0.3780722 0.05972611 0.9230824 -0.3846024 0 0.9228789 -0.3599774 -0.1367883 0.923911 -0.3638817 -0.1182318 0.9228106 -0.374044 -0.0922597 0.92283 -0.2552905 -0.2884645 0.9237479 -0.2248637 -0.3100421 0.9239338 -0.2705514 -0.2704598 0.9230591 -0.3167303 -0.2182747 0.9237362 -0.31014 -0.2247767 0.9236901 -0.3412947 -0.1741113 0.9239045 -0.1183835 -0.3638486 0.922813 -0.09210729 -0.3740754 0.9238419 -0.0596342 -0.3781004 0.9236896 -0.1742333 -0.3412335 0.9230536 -0.2182123 -0.3167894 0.9231022 -0.1789011 -0.3404067 0.9239145 0.1182932 -0.3638526 0.9238419 0.0596342 -0.3781004 0.9228106 0.0922597 -0.374044 0.9230824 0 -0.3846024 0.9236916 0 -0.383137 0.9229563 -0.04614472 -0.3821287 0.9228409 0.2553851 -0.2883458 0.9239338 0.2703988 -0.2706124 0.9237315 0.2247145 -0.3101994 0.9231063 0.1789935 -0.3403471 0.9230647 0.2183371 -0.3166711 0.9236901 0.1741113 -0.3412947 0.9236894 0.3412029 -0.1742942 0.9228886 0.3599998 -0.1366632 0.9239115 0.3638209 -0.1184149 0.923744 0.3100103 -0.2249238 0.923048 0.3168485 -0.21815 0.9228106 0.374044 0.0922597 0.9238436 0.3781011 0.05960375 0.9229619 0.3821005 0.04626709 0.9229551 0.3821282 -0.04617518 0.9236916 0.383137 0 0.9238402 0.3780997 -0.0596646 0.9230647 0.3166711 0.2183371 0.9237315 0.3101994 0.2247145 0.9236901 0.3412947 0.1741113 0.9239076 0.3638804 0.1182619 0.9228872 0.3599687 0.1367545 0.9239338 0.2706124 0.2703988 0.9228409 0.2883458 0.2553851 0.9228382 0.2552927 0.2884365 0.923744 0.2249238 0.3100103 0.923048 0.21815 0.3168485 0.9236894 0.1742942 0.3412029 0.9230836 0.178873 0.3404721 0.9228886 0.1366632 0.3599998 0.922813 0.09210729 0.3740754 0.9239115 0.1184149 0.3638209 0.9229551 0.04617518 0.3821282 0.9238402 0.0596646 0.3780997 0.9231063 0.3403471 0.1789935 0.9230824 0.3846024 0 0.922813 0.3740754 -0.09210729 0.9230836 0.3404721 -0.178873 0.9228382 0.2884365 -0.2552927 0.9228872 0.1367545 -0.3599687 0.9229619 0.04626709 -0.3821005 0.9228823 -0.1366317 -0.3600279 0.9228418 -0.2883155 -0.2554158 0.9230927 -0.3404145 -0.1789358 0.2096337 -0.6285045 -0.7490233 0.2096359 -0.4888861 -0.8467841 0.3433103 -0.4695987 -0.8133974 0.2096337 0.7490233 -0.6285045 0.07080507 0.6411826 -0.7641149 0.07080507 0.7641149 -0.6411826 0.2096337 -0.7490233 -0.6285045 0.3433072 -0.7194833 -0.6037251 0.2096068 -0.8467895 -0.4888892 0.4725327 -0.5665022 -0.6751209 0.3433072 -0.6037251 -0.7194833 0.07080507 -0.7641149 -0.6411826 -0.07080489 -0.8638505 -0.4987474 -0.07080507 -0.7641149 -0.6411826 0.07080489 -0.8638505 -0.4987474 -0.472526 -0.8679305 -0.1530224 -0.3433129 -0.924952 -0.1630957 -0.4711253 -0.8787097 -0.07687795 -0.2096068 -0.8467895 -0.4888892 -0.7667806 -0.572125 -0.2910677 -0.7117974 -0.6084292 -0.3509393 -0.7119519 -0.6597641 -0.2404913 -0.5971353 -0.7899544 -0.1392888 -0.4725303 -0.8281716 -0.3014085 -0.7646861 -0.6246951 -0.1581498 -0.7707023 -0.5942401 -0.2299929 -0.7656107 -0.6393517 -0.07120186 -0.7116677 -0.691861 -0.121892 -0.710779 -0.7011656 -0.05621528 -0.7710781 -0.635571 -0.03857678 0.4725564 -0.6751112 -0.5664939 0.5971426 -0.5155948 -0.6144776 -0.3421461 -0.9360723 -0.08188188 -0.2096042 -0.962934 -0.1697769 0.7707077 -0.229964 -0.5942443 0.7667932 -0.2910609 -0.5721117 0.7119519 -0.2404913 -0.6597641 0.7117974 -0.3509393 -0.6084292 0.7642617 -0.3673901 -0.5300269 0.7119123 0 -0.7022684 0.7716747 0 -0.6360175 0.7656233 -0.07120019 -0.6393368 0.5971353 -0.1392888 -0.7899544 0.5971396 0 -0.8021374 0.7707613 0.2301144 -0.5941165 0.7647439 0.1583628 -0.6245703 0.7119519 0.2404913 -0.6597641 0.7656609 0.0712924 -0.6392816 0.7117101 0.1219246 -0.6918116 0.7679034 0.4312723 -0.4736335 0.7120428 0.4518668 -0.5374121 0.7678636 0.4738414 -0.4311145 0.7642674 0.3676369 -0.5298477 0.7668057 0.2913098 -0.5719683 0.7117974 0.3509393 -0.6084292 0.5971404 0.2743379 -0.7537654 0.5971401 0.4010537 -0.6946796 0.5971353 0.1392888 -0.7899544 0.4725564 0.5664939 -0.6751112 0.3433103 0.4695987 -0.8133974 0.3433072 0.6037251 -0.7194833 -0.07080489 0.8638505 -0.4987474 0.07077443 0.9373422 -0.3411458 0.07080489 0.8638505 -0.4987474 0.3433072 0.7194833 -0.6037251 0.2096337 0.6285045 -0.7490233 -0.07080507 0.6411826 -0.7641149 -0.2096068 0.4888892 -0.8467895 -0.2096045 0.6285085 -0.7490281 0.4725303 0.3014085 -0.8281716 0.4725632 0.4406398 -0.7632305 -0.4725303 0.8281716 -0.3014085 -0.3433129 0.924952 -0.1630957 -0.3433111 0.8825863 -0.3212151 -0.07080507 0.7641149 -0.6411826 -0.2096045 0.7490281 -0.6285085 -0.5971497 0.789943 -0.1392922 -0.472526 0.8679305 -0.1530224 -0.5971404 0.7537654 -0.2743379 -0.4711253 0.8787097 -0.07687795 -0.3421461 0.9360723 -0.08188188 -0.7117101 0.6918116 -0.1219246 -0.7656609 0.6392816 -0.0712924 -0.710779 0.7011656 -0.05621528 -0.5956819 0.8001634 -0.07001197 -0.2096068 0.8467895 -0.4888892 -0.07077443 0.9373422 -0.3411458 -0.7710781 0.635571 -0.03857678 0.7667932 0.5721117 -0.2910609 0.7117974 0.6084292 -0.3509393 0.7119519 0.6597641 -0.2404913 0.7120159 0.5374454 -0.4518692 0.7642618 0.5300269 -0.3673901 0.7707077 0.5942443 -0.229964 0.7656233 0.6393368 -0.07120019 0.7647007 0.6246765 -0.1581529 0.7116677 0.691861 -0.121892 0.710779 0.7011656 -0.05621528 0.7710905 0.6355561 -0.03857588 0.7116677 -0.121892 -0.691861 0.7647007 -0.1581529 -0.6246765 0.5971404 -0.2743379 -0.7537654 0.5971527 -0.4010623 -0.6946639 0.5971426 -0.6144776 -0.5155948 0.7120159 -0.4518692 -0.5374454 0.7656609 -0.6392816 -0.0712924 0.7710905 -0.6355561 -0.03857588 0.7107942 -0.7011501 -0.05621647 0.7678636 -0.4311145 -0.4738414 0.7120428 -0.5374121 -0.4518668 0.7117974 -0.6084292 -0.3509393 0.7642674 -0.5298477 -0.3676369 0.7679034 -0.4736335 -0.4312723 0.7668057 -0.5719683 -0.2913098 0.07077443 -0.9373422 -0.3411458 -0.07077443 -0.9373422 -0.3411458 0.7119519 -0.6597641 -0.2404913 0.7707613 -0.5941165 -0.2301144 0.7647439 -0.6245703 -0.1583628 0.7117101 -0.6918116 -0.1219246 0.5956819 -0.8001634 -0.07001197 0.2096042 -0.962934 -0.1697769 0.2088713 -0.974224 -0.08520871 0.07049787 -0.9937154 -0.08694738 0.5971353 -0.7899544 -0.1392888 0.472526 -0.8679305 -0.1530224 0.4711253 -0.8787097 -0.07687795 0.5971404 -0.7537654 -0.2743379 0.5971401 -0.6946796 -0.4010537 0.4725303 -0.3014085 -0.8281716 0.4725632 -0.4406398 -0.7632305 0.3433085 0 -0.9392228 0.3433129 0.1630957 -0.924952 0.472526 0.1530224 -0.8679305 0.3433111 0.3212151 -0.8825863 0.5971426 0.5155948 -0.6144776 0.5971426 0.6144776 -0.5155948 0.5971527 0.6946638 -0.4010622 0.5971404 0.7537654 -0.2743379 0.5971353 0.7899544 -0.1392888 0.3433129 -0.924952 -0.1630957 0.3421461 -0.9360723 -0.08188188 0.4725303 -0.8281716 -0.3014085 0.4725632 -0.7632305 -0.4406398 0.2096089 -0.3344037 -0.9188244 0.2096042 -0.1697769 -0.962934 0.3433129 -0.1630957 -0.924952 0.4725623 -0.1530242 -0.8679105 0.4725339 0 -0.8813125 0.4725327 0.6751209 -0.5665022 0.4725632 0.7632305 -0.4406398 0.4725303 0.8281716 -0.3014085 0.5956819 0.8001634 -0.07001197 0.4725623 0.8679105 -0.1530242 -0.07053059 -0.9937155 -0.08691954 0.07077324 -0.9823415 -0.1731946 0.3433111 -0.8825863 -0.3212151 0.3433103 -0.8133974 -0.4695987 0.3433111 -0.3212151 -0.8825863 0.07077324 0.1731946 -0.9823415 0.07077443 0.3411458 -0.9373422 0.2096089 0.3344037 -0.9188244 0.07080489 0.4987474 -0.8638505 0.3433103 0.8133974 -0.4695987 0.3433111 0.8825863 -0.3212151 0.4711253 0.8787097 -0.07687795 0.3433129 0.924952 -0.1630957 -0.208842 -0.9742302 -0.08520925 -0.07077324 -0.9823415 -0.1731946 0.2096089 -0.9188244 -0.3344037 -0.3432803 -0.6037314 -0.7194908 -0.2096068 -0.4888892 -0.8467895 -0.2096045 -0.6285085 -0.7490281 0.07077443 -0.3411458 -0.9373422 -0.07080489 -0.4987474 -0.8638505 -0.07077443 -0.3411458 -0.9373422 0.07077419 0 -0.9974924 -0.07077324 -0.1731946 -0.9823415 -0.07080459 0 -0.9974903 0.2096374 0 -0.9777792 0.2096042 0.1697769 -0.962934 0.2096068 0.4888892 -0.8467895 0.2096359 0.8467841 -0.4888861 0.2096089 0.9188244 -0.3344037 0.3421461 0.9360723 -0.08188188 0.2096042 0.962934 -0.1697769 -0.5956819 -0.8001634 -0.07001197 0.07080507 -0.6411826 -0.7641149 0.07080489 -0.4987474 -0.8638505 0.07077324 -0.1731946 -0.9823415 -0.2096089 0.3344037 -0.9188244 -0.07080489 0.4987474 -0.8638505 -0.07077443 0.3411458 -0.9373422 -0.3432803 0.7194908 -0.6037314 0.2088707 0.9742214 -0.08523899 0.07077324 0.9823415 -0.1731946 -0.07080507 -0.6411826 -0.7641149 -0.472526 -0.1530224 -0.8679305 -0.3433085 0 -0.9392228 -0.3433129 -0.1630957 -0.924952 -0.5971404 0.2743379 -0.7537654 -0.4725632 0.4406398 -0.7632305 -0.4725303 0.3014085 -0.8281716 -0.07077324 0.1731946 -0.9823415 0.07053041 0.9937129 -0.08694988 -0.07077324 0.9823415 -0.1731946 -0.5971404 -0.7537654 -0.2743379 -0.7120159 -0.5374454 -0.4518692 -0.7120428 -0.4518668 -0.5374121 -0.5971426 -0.5155948 -0.6144776 -0.2096089 -0.9188244 -0.3344037 -0.2096045 -0.7490281 -0.6285085 -0.2096089 -0.3344037 -0.9188244 -0.2096042 -0.1697769 -0.962934 -0.209602 0 -0.9777868 -0.2096042 0.1697769 -0.962934 -0.5971426 0.6144776 -0.5155948 -0.7120159 0.4518692 -0.5374454 -0.7120428 0.5374121 -0.4518668 -0.2096089 0.9188244 -0.3344037 -0.3433103 0.8133974 -0.4695987 -0.2096042 0.962934 -0.1697769 -0.07056093 0.9937134 -0.08691936 -0.3433103 -0.8133974 -0.4695987 -0.3433111 -0.8825863 -0.3212151 -0.3432803 -0.7194908 -0.6037314 -0.7119519 -0.2404913 -0.6597641 -0.5971404 -0.2743379 -0.7537654 -0.7117974 -0.3509393 -0.6084292 -0.3433103 -0.4695987 -0.8133974 -0.3433111 -0.3212151 -0.8825863 -0.3433129 0.1630957 -0.924952 -0.3433111 0.3212151 -0.8825863 -0.3433103 0.4695987 -0.8133974 -0.3432803 0.6037314 -0.7194908 -0.7119519 0.6597641 -0.2404913 -0.7117974 0.6084292 -0.3509393 -0.2088415 0.9742277 -0.08523952 -0.4725632 -0.7632305 -0.4406398 -0.4725327 -0.6751209 -0.5665022 -0.4725327 -0.5665022 -0.6751209 -0.4725632 -0.4406398 -0.7632305 -0.4725303 -0.3014085 -0.8281716 -0.7656107 0.07120186 -0.6393517 -0.7116677 0.121892 -0.691861 -0.7119123 0 -0.7022684 -0.4725339 0 -0.8813125 -0.472526 0.1530224 -0.8679305 -0.4725327 0.5665022 -0.6751209 -0.4725327 0.6751209 -0.5665022 -0.4725632 0.7632305 -0.4406398 -0.5971527 -0.6946638 -0.4010622 -0.5971426 -0.6144776 -0.5155948 -0.5971401 -0.4010537 -0.6946796 -0.5971497 -0.1392922 -0.789943 -0.5971396 0 -0.8021374 -0.5971353 0.1392888 -0.7899544 -0.7667806 0.2910677 -0.572125 -0.7117974 0.3509393 -0.6084292 -0.7119519 0.2404913 -0.6597641 -0.5971527 0.4010623 -0.6946639 -0.5971426 0.5155948 -0.6144776 -0.5971401 0.6946796 -0.4010537 -0.7678636 -0.4738414 -0.4311145 -0.7667923 -0.2913048 -0.5719889 -0.7117101 -0.1219246 -0.6918116 -0.7678636 0.4311145 -0.4738414 -0.7667923 0.5719889 -0.2913048 -0.7642405 -0.5300333 -0.3674251 -0.7679034 -0.4312723 -0.4736335 -0.7642464 -0.3676574 -0.5298637 -0.7707296 -0.2301446 -0.594146 -0.7647439 -0.1583628 -0.6245703 -0.7656609 -0.0712924 -0.6392816 -0.7716474 0 -0.6360506 -0.7646861 0.1581498 -0.6246951 -0.7707023 0.2299929 -0.5942401 -0.7642405 0.3674251 -0.5300333 -0.7679034 0.4736335 -0.4312723 -0.7642464 0.5298637 -0.3676574 -0.7707296 0.594146 -0.2301446 -0.7647439 0.6245703 -0.1583628 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + 7.54979e-8 0 0.9999999 0 0 0.9999999 0 0 -1 0 7.54979e-8 0 0 0 0 1 + + + + + + + + + + -4.37114e-8 0 1 0 0 1 0 0 -1 0 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_main_wheel_collision.stl b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_main_wheel_collision.stl new file mode 100644 index 0000000000000000000000000000000000000000..ff3c9e359afea3e464e815346aaab08adacaeab2 GIT binary patch literal 69284 zcmbWAcbHX0^7mUYprD`#DvB6Z!GtJL=FT~Y1O-%#Bwawk1W1-30?GmgL|p~NEGS?? zlqhrO9L1af6RT@j(_+B5DyCK6Pn~m{`S!TKe_o%5XV1><>Z0-}&1*xAX7|)6*V!IWq7kzxlCjQsIz_ zbo32n{<~uI4HcKo+*mgEit!cp?OfA+C#RP+zOURMM($dp&}*xgn;XR1pqzdw;deDLsh(at44=9Q?jzG@G+w!)9D|ITsTbI7>(kp7osbN=i%KUUbB zTVMX$aI8OWtD?=OeLFX_#~Ja@+vM{xZRW-bTMY)`sj_eX_Z(tAI1cN7Nn-q4zgHCw zDf9idyy?Mq24OhtJBK)Q-^uZN`{e6t^sY6EA71lPbNj`AdkCY-zMUJ!SRH@%;i=&; zN)D)TcZS2p=gxN@&%XWNa|l*@%xVv)vR{n$d#@OuLHO?+Vq!k$=|1saTH5H|SofPU z8%3Lc`?h(uIq%>2_w3ubFAI(0R@-*XsIqZCdCc1xgr~~-^?wgmNd{r7;k`SzE*K75 zCH~viu6^eapU-R>?Q{9W48qox|3x8eRT@?KoCA?~2*siOnyggu0p|&;J>y(|F`4k3 zo1|6Y_*8J{FN#ll%4M+5fdkS@9GX1(kyd=jM~SMZmTq3EIJA{QJNFIR z=cv+rcpNq+{@d`G_OTU{>yo$747)&;tt)NizYRLXF}hbFJ+`zGwJ+0AwkoY(|My(O z{RCBqm8jBR6o>zNPE|=KW>lFTwDoGgcpP3QdVJ3PFRH4yQs^z#Ad?S|!yx>(;WNu% z(wtK@3{8z@_!CtgLh;$Rb7+RtYXgfI z9G8}~&qG)o)jq0mLOK6fG=u)45Fu5YuphNbt6lYyYB>M*T$dmpk;%sgHy+SJe^Cgf zc8gWZR*BbxrrZ6u>BLY|BOkGs58uilJU)|J|My%|vl7ilWjK6a2BG@gf7{=kJ0A$Q z?Vlk$wDs#DavcB5s@X5zlG(RfyG)|CSRCJ%VfU^63}JTgU;EsbtrE3;{@b8EzMKzM zdyGexLHJ*+Uk{-a<`Dmv2Vl_N>ichl&epEsD7Q7QzxZ$K*W=4^lx%He5XQOr4EBq9 z8UF7%j{gN=zbJ(N&LK)3Kx{Z{*1U)0zpa(667!;R2%GaiN}h~wWmI`e?A!l6hxm?_ z*u3Pu`o64{twi&$OeXwyZk@3>F%~DIN+JBW_3I&WiNdO7o~8FPyf3PrrFxvseOU7P z=3obXUxr;hzz||JnxS#YLpB{{zNleWzcln-R|XNb z+q~I-xreO3D1=hzT*)tq8LMULpR1>@{`?l7A-;8J&oinNyKiOC{yT@b56k&>zkD}g7Si;GwesKA%Hzu+ z&_1c(fB0V%LMhB4O7=X{K58xfx3yAy`KoF-_r7Jew!9x@{oZokLuHe%{3`Q`Z9cqr z?%daFA8DDxO^I!Vd(Zn0cS!3!M%T+c@^Nift={q8U9#`It%uNG+Ba@p@o-!_hX}mz zDwrv;t@i(gLvdHNH$JrAj;~Ft*y`LG8II7_{`zf;R-P*LkS~94Rl95N&S_WN&Yg5v z73bRTux<}k47@WRE7LJmV^u}hlvr`7S3GD)>#{mW=cC}<6HhH^+4JZ7TmJFK;kn-ZYrkd8o^u9q(ht+hUOhACR&j(gcv;6KTV_!EZG7EV6@T=9 zDC^gByLretj-+j~#|mH?F=H+yU)(e zA&hfvwfUuKWzU~mBZE*4UPYCyk_OX9EqQ!&y{wh3a8F4{)gC_`nT?e}Xe)(QYO8Q~ zUE;O=A7j>+oj7-WHo9I{=A+yBm?}P$_7NQ(Dm&<&d_+TQuyVI$TV_ygc#|_*SL|Gt zkCl$Pa}S=|CRr;iJ4y)puv+@yDe7Y8#>$RcP7OK35 zWUKm6co^Q{p$hvBy``$rni4;O*7T=?x?YFbnr78ht;8HETQ~!h5p0)ZTk`n@lsT%dQuJSSzhyJ4eL+CRog#M!5KtJIMFz&A47-@Jy*5Jp{B(8i$a82RB@=TRZXoLysEwD!=Lsm^#2W^{i=-$t-;r4 zHqT_xaA+&lc7N7z_s-7cTwAG!r24Un50hGLrFJ*8wGR%nRP83zTT%}x^x@9jx8)WMr@yE__rHBO<3oQ@&nfhljE`pP zb2-;v)MltHsp8vksIR8hM?GgwSZ)aYcE5L4pE~rfs<4DOwBOJRZ#nU6Y=`|fCGg?Y zL-PCD+-KOQO^q#@S}9QvFr@0Gq33SFp%z*DRea9jx1&Kb`;qQ+=Bm}^x7%69U_2%B z+wD6%_gVP+7XK>sR@nCB7xu4Fuw9XTcPZ2^*q$oi(XXrW^iw^jQXIeF%bC}2_>7+X zKjb5zN>7Joov|d_0fZ2YZaM~U)jV(e#mk+2|KB*YFU6rJQ=TUK-zlm7qGwCb%wN^c zc1Sr@D|gG~!yvSko)qEBmzmf9XFj}MvJ*(JaqPRs#p^3Vci`eto4$}Jijuy6qv~RCPt8kQdkg4|T<<92$`3oK@vmIoP? z%j2+WPft*S=eG(qcY*zOG(BeO0!04Z_=~3`fbowr_7A za~yuOj4JQFdK~^fDqOoB!f-r4utw2#?$(#L?HN9~^LFmCj?KLcraMnwUuGvBhGVbm zzACem3H$b*WzNSAk1uOkI=@Q2Ut;~OGu4&!DYW^T_NMz4^KEy;ZC2 z4Cv1gtsA#4vokCE#a5-i2R^s$s&;nbl|!t%WXnlWYU|4111og<*QS-($<&{5n0$Du zl)?`WJY3;D(p1M`qewHa6bOkFh9RC9NKEwkk%D;E@sd=H{7w5FW<6Cyk}{1 zzT(F96}DHiZ(R!^AF6BpzNY#btAeoA?yZ5f(v|P`YWYg6f|-))3g79@uPSU`Yg8$< z&Yd-K@fJBhEUI0!UA(nYx$}Oh{k;lb|8G7N!h6UDq0m)0jPsM`t}nCQwo#>8RQUs9ee>m| zy>qHsU#)>!yAX$tqUtUk^$746Y2qCnUuHA5z7))vJoN6o8aQ}O?+k9v%mB&y9 zJzWN&tyBh8Hhp{h-zllKQq37kZ57OvR9mUOQf=qli{G~JK3t&TRI8~DcJA$lEw@1E zFRFJ{A3JwPzbY?7e^G50YB=Mgw0F+zxz~NF6IHu9*Sfq_=IPs5=`X5lL#w7^rN5{h zRNYn8-f-wIs_oR{bZ%+Y$z9-!stxz2c%f!69QupuMAelcRjMt$A8q~q-w@hLy%+Ur zoWpP5;>l=V3LQdJ(KRL2epTCr8gBk8M{JovZKax1H7d7cXExum61A1;u25g~L0^^j z&Vhzg-%zz(6&EJ8+DbiE^*A{Tui87O+DiRs^@FQ$*qm!C_0>(%EUq*6OR8X|q}odN z3AzKQYHv7n2cdhaa3AGijC1`(cSX8e^6m4zn*O5u8r|>Y5T(6ys=uhsP+Q_$*Dh6a zuKN$QKDuY9qRKeeU4!l>)awr+6o>Y!JvsOMp^N=#RI0lMwY9p-z`y!_@fL|vN)$Sz ziW9G;Ic?!?Li<&G&fWIaq~zs8W+y8~4~g}BS5Jpme7k?)Uq81gbnO3c?(S|~`$J*D zS5GF>&KVNxdFve)f4TbTA4U~A(MnHMox7lXc5?5!Ny$5-hQxYK-ShJ{g?d{ZkoBwh zocqfQS10cItCLp`91<&bZKcr8ef9FfWZN50NRB*XNIart*TP{B*2?--e0r+x+%BVU zO=hedl@yzWR4H_bqs%Q!de_}QIiuB(xXzs3g-@q^TxMgU{oeV^pu&E=7iWKWZrOE< zlE?qsExGCV5JGV%v~!zR7L(bhY^t1o(2!W~4Q{yUqQcF8ADs0Y;^=(d@?_J|4U#v9 z4vF;_?N@tpu2a7?Nt0J+RUUuvkhnE7cJIYswlh8yhqop9DbBfRl6>2GW#wBJhg4}R zg?8@R_nt}~X`dFmMj;MweXQS`){M#S+wyg_`HLr$ouAuWyp46Gt&~E==iFOMPe?{p zEKDkUhHJOeRkaFdb?=(ZzurJN*LTLK3P@o)Cw8-3d{h^$U}&&?SdHSgSZ1ePR%LE2DQhNNq8R7Pnbh zc^YG-cOJXWyQp{!GiT6#=at`>Ja+%0Xbmf+E2~8BRnF|*wRjxs*B}s>sNwPoMV z)k>4-)56N~H<3ZTUGVzc`kj5#Ma7wLpF>>n-c!+zB^jK%W=wWRYrps%ok6tyVN}uN zKZoehVRkg}sY%hBXzJddw<*@y>VTsCqIU>-1L55D*Di{V{k2>4J{oS9IlYS?PWd>) zKB{HcVpGP>p!Jr+xgF1J5WU}jd9;ePtM>*Aj$K@_@Wnwzn>D>1;52H*3DF)E3!_EI zxkBhYMVG5;6?-#wIUnDxpH=zJS!<#>toB)G&A&4)*00_I*cxjE_xUQh^MlQWE5CR$ zddRFAmdyX6Hw}6N;oRWqCnWP;T^Q}oDmfTyGaQahlj)hh-Uv9?`LG7br{^z^cD-mw z5G~ROdvV7zIp-n7gr_DYCo(5CAA0hyIO<|S&tR@{E&BY5QOR|qZjIhS!zoqTN}-*b z)MR#2ck`rZHS(c2-ofH8|91bZU%e4Y!gV^Ksoit}uLy(BAV{ zXZcuth?ZWTbc;G5gWA_U0--%QcV}fW*|z4U@>ysf?W-=Dxz#ThX8r2ThI8-sU!Hv0 zw?Xunt#*le(SEfj=h_Zfll*(ktnxJ_>wGn<(dhO2D6^c3&$;_5lH}pzR+gWQ_E8+# zN}-*biI#r2eOfpUOV;ys=ttSu}t-*H+rE;v@2G!{%Zoa(*v- zs0L8YpfbFiU6DkCpi1?UYR;GySqBT0)RsZ>`qnFTE+OJwQwRX<+K_6byWOlS1ov5u8TB+roD3;*H z=_h2?Ky9B|%g_$qfRzDh{PY zdvfk7R(dUD#P$a2muSE0qX2=#-t^(-f>~#!L|ZAeb4Rh#|9bJPO4Fk1d8tPh`abMG zBESF8eib@|_>`4?X3b5Nli*yvzWecF7O_{b@lkxv-H5IlSbP6uIP;;c)B_B?zR~9_ zk6ND8AX$z5&{hhqxScDz>eguP6{C{9SXb)rs%NRbFVTjNFN`j^?}X$Gth4^25Q^Km z|GY9Ox{O`@Blsn|;v@E9C!cXE(b4KHb2^CpeZ#K)Mr2SSl)}&p|LwosqK)jIufl$) z7p|W7M!d~k*@@>XarvrI(d+E$r^C78P)f8X=gv61K{WG%<;f?EuI?aoXQB9>3%8Lg~|DhbC*v#KJL5wPVtT#u1Wr}Xi#CBngIsTnW7uyffDi)I$aFTJYl=vSh$`#Q}i zv~K)RS?%+lEbG~3dSM)Y=e+&y3(L=%(+}8kq<6;wh3?yyXV`yxtxsY29c>DCF1@Pac>Z=Kzs=03+Iso} z z&MV*i%K7oWKdg_mRm*tnlF6^n%6L-#ocnp)HBsTw-Q!o69uw=%eZ#|B7mn+DcHu2} z>hi*)Wf$ExCi`}7>Y2O5&E}pI4_j3?nSa*qg?0_57W$1laP`wSbtruN$$5nVd~d~w z|C5nFlaY3AAagN+IjO~bT*&wz$~^St7i|@C{^*8XJ6=|`hKF57x;?>|wc)UvN#)joP;WW%`bpw4OA34_b_y5*um#2j=g zttG>^-MNd)9({69_IGgHHog4TF74w-4{e$jUs$$en=`L0G-DLolw{DpFDOaW@7a93 zUt>nJ=BN7cCCxgf+Lz)`YMncJ`I7RUV<*NVR@P0t8t zb9exC_bFctRf7k0$~=94_NMw#wYGB`zStvvhktwhS~DGr4s@^g$@HM=#89F-tlB-U zoODf8XYn!VV02P9)|0KJ+ive&C_DG#GLv&%)6TuQ_dfBHgWru#MQXLLshoHkw1N51R)4K`Sz+%@6=f#dircxDkJ%wU>W6!yPo{SXBuc4L>2mHE zM)usn?W4>4bPo79`tFMgi?$h@@$vY}g9?S#i?eU^)sOY#_r91O9nqp=s{JY@A;cc6 z!fjZMm8`@Muut}m!NzJlE3Z2%(8g*8_Gt`KWq)_>r`iX^D;{qaop*8jRDV&b6d&@z zx}A;W+S*-+r92jCZO-^?jr1Bm`&QiS=r1KF#}^yRZ%VraIFu^Ihvj5Vt**0A1H?zj$WF+I_N$bH5c|OS6=}1i#n|@Qe4s-rY)tIr-%cI zt?kuuKr#0+#%$Fw{^`XP$zWt~$~j{TBVOORXugP2bvk~}zUMtzaTkAwj}|TB$6K^W zpMI=vVix)RPtGfPtM74qfG6-_R%qp7ZG>vM1 zH($cJx_B5P&e|ny{9xV4{I-4@>lcThqs*T(o`&*mIC_EO;LHQKw8e(#+$Dq3?U&Sz zOsfG^G_B@wnATR@&MibIetz>w>0aQ_UrY}gPv&v>al43~oNGBEj>qh@U0Uad^@(|q zr`D`jG!N4Jx#PAi&%RA}4Y{LDHiphM#v^;>mGjdl@W|fBhdZt24Mp?e%nSQ&(afTG znMdKBUHba0?3;b`khQD-O_IKz0 z{XxH|?I%6b1MyyWM?bN)immWi&3i>Ai{`y5KJE>MwTp+m+$H%IsWo}_tKB3Rds|^r zt1FcI4`h75F74Cku%>Zx=Y>m<@2p?NVg4>!qiB9G=ZRS67q^>{?2dJ|yF1&_n-nQN zyJ@sj^;~Mp@u|Sg<<{YrMw zpSSBNSIEZ?-G7VDzxJ8rsy(`-+OK(G^|x-CX#=~jwL6P^te(7V$GF>%Pb9_G?K5B0 zw^Hbkj}bpT5zW4Q$Mo%1czxW$*o}hqWqxAsqmRpQn3vhH@7X2oGi>io(OC^QB`-YK zAyw>3mE9=XSyoQfSauWlKeBszCZlU!*oC)^$@=1qy39`1tW}6(=%{C+wv&EK-mJsu z3RT*#Qs~?b+suge`lWt)`r#c@&b!O(Ud4PL#i6)4xqJEEX!i~~q@T{}k}CE9LU21b z_K9ZEx}6S47mZ=8gb(w=Y=xUY$C-GUoj@9HvTD4&vHY1yjnZwfYWj;p%q-o?viqn~aTP2c5!xbw*NflqBXY@cbZj9S~P<@Tdq zvroz|8QUoC^kkP*Td7AL`iUp4ol`!3WY2ikFE!JprJe8{XnpmSNu&_`$=?bmcyf9zsr2LnFl+;N{Qmoo}4=#%Xtj{hE_W@(7n3uSUFpQsuZfusfI)Q4XNr@ zqhq|`zgeGu#<_B<`?C;7pW*G|g=@P+ zi`hr1N2dOq;v)+bJUk6Ae*=g1tKM?xAt#(MwEb~j<(`|@Cs?%1(=$7WO)8vyO!o@= z#<~?)K_#Ezim#i+{STZUH3f(ErT%s3S>BCjIsUfkl@FHq@OH`gU@d1}n0lG`iL9xk z*LR72DOokYH&AYM6r4MK-Kp__E1ypO`%`Go)epk{7JfhI`HUy$7D3fj?AIQKD)sKP zUmbPlmNU9n41PD60p~WNYiBplJU!K->TB^@7997@onCn%d?<&?x#D(iPgcl&6Kkdu z!J*nx@!9G*eB>z^ZtNhd-uko27@shiYn*sLMYan$fQM*tusI-R~J)+uiAiDvoe; z2e3l+AJ#7Y463}hWV%E(b%-y&8?9_GHp)KN~z9N_#bLCsd2-*@<%lXnj0ToqQ%#`-0CPeH<>lHaowEq&zV7XSDB469I8KtuavtIs$ml-4`%lR)KdEJf&H7TUrrM5u?baRR_t&pTOwP4m9qG`19LHFl##o(DT8ZACYpZaq z>NDS$f7&D61sqC=$vJp33RQ#i>KAKpGuGhmSOc{(Y7Nvr=A--Z7ki|2p-M+oA#^s; zyZDF$hqp`bMN=zPN=c~OuSfn`Ha#-!4h|hfoi!bG=U&0rJ*P&;)Yh)z&{jGMWb9?# z_8!?YozI+Ca0|d1%B-4FWjdG@U(EL(_=x4Tu!Coy+qIQKtL-8xjPsK3SzEV)!yxR2 z&n&0vcB9tsMV#9ni?aZWGYyNQc1f*_LUW2U^U?A#+f9y#_rJTX-YD#U?Db2gal6ox zv!(u>PbvFn-Pwgc*@@S~>sLf~uo_#G#>!(?YoJ=2oiHaw$0q~g-am(S@DEOn`s1~l zO;l*^qjuUZZpRtcAKXEn#_eY<&amthP;cKtO?~c_PeYDX^>o>v2-_()=f{P4XYF1bm`T(saP-+cuhM2v zcd3TYTj~%;V^&DL4hNM6zFLmH6GSa<2He`C;~YtvfZ{ zjj^&7zWoD}vXgk#gQ_1nnPAS3WtVzlwb4~8qxgu~Mw&X*-Y(q%2yLZj)@mil*!taw zs4=I`oq$kEOy-%G`gVuIXK7E5oi9z;*zvnv6msIgmdzP-^;0XHZ8v9Nn(WM;qp2R<-$1&UHk{ zV$K=atWiDFH__B;Wt1wV7B3uMcjd+&>6ntm!E4E^n)a*EjMeueq8C|P2f?}hVi753 z?{vRo&=!%B?>`P8T4V;%A~(EoO`>*5@3s{h-{;XK<-3oY7c{du^(Ee4^pepoJJ8T zataY6gWtF&@|yEA?mz4n=p62K{4J10_1G;CH@u&%i~jQUU*q55T;ogBekeZYPUc4c zAa3^UJ(=mjx!gmU9yI-N8~0F6;nx4XNyhnUP&5U~4&roBZHD4d+|Jd2qWht2UpUvu zBi&P}Ms=0<;R)nCJdBkSA1%LO!h*JsSj`%dXMKxn^e2SY7-KAczHJ1MczRSuQ&5XUHH@7S;Z zn!X7R)q|=jPt6L6 zYmG@KL)AD=otVXYX)H-(pzV7FE0Oyq~j<@vMuR=RFgZUW7+8R)r55MQI zRu-RVK7;Cf=T4lOja6I(LhX{aQfTM)csXwg@qQx9uY~iF;+N zY&BLeRz|z0N-cnDZIXB#F*PzTx!&D%6K&;fpY6}W7_SNLZWKjIwk}zsgZAOS=9RBV?VlAgUocp`JU$apQuu%^B(RwJ0;9UFlw$JYk{23r)1=k7xz9;rWIn;hNN|PC6WZ!0l z*Dt7>XusY@nY{|N=u&uS2`{JP=_?K$-H`KE#PrQsv!wiR;`+2-wTY@x$$|awp!mqv z8=_;F57SYeL+w{b#JLy1F=Ne=%6H*I`_(;_YF8p<;r!}mQ=|9Tc`1jAPe+9FE9T>= z78{cL?yehIt0UQynZIL{+|0hl`z5w-%l(pXq3Q^t8efDe#4;>$cP<+na%S!*x*oo;dR*CYV z{hHQh1r_sCwQHG=&aACt7KXarAS`a)EVAl(_8;hxb*%W)!J#L2+Df6h6NakIK-5@3 z=bVKFYqmy&{VBja}nymYp1b_4VM^Y9|z5h~slkac1Mq^dN%HPEzcyXe=>s-dnc4 zq4&t`8;`8Sc@H+cd@B+N785Flw4i%q{ z2yp6zc-VWe`%R+PU@dwWI17C5e+`Do=IBNw#w zRM|`^J{=Km6j{6XZP+#a_qq8D`hIQJd{n7@S4FY@2hNvF4LSF_Z5vUeJ>|$46-oAwFWhzwA6VwHfq! z*K~&I62>mmoc{0mn}!13*n>pM&cGv6E2Dgb)}SPV={LiNwAEHhRmgc;^llq;dtJN? z)4R-E(cWOFo>vO7wP>F6mY$q8`gU+@joH;$-q3z5#}7Ra>wFWsU2TSP8{#PG#6OLd zLMT4xe&yze6`w&UAKI_~&QH}!^YMS`cC%y#VRuD2#A?obOxA4%_2f=l`S08gHsZGL zOX8!BB7WE3ZTT2s|H3VNulC#}HRGrFx8tErW4nX27ghEe%pzUvO_Y86+kWebECtxw z3E0}&c&|s5&i97n>DgHMcQc_KJg{Yp_)z}6d4Ju=R)e=os-11U*;}$a0=piT^F@63 zCZ#BEdrM|f-fA-xw{xH3!`;XF-G?Y|lLK#;6rbN^7+PxO-N@tL3K&o7-j7_R@qzwIBW8!2|BN^$4+I2&2NZ{AfmQf;aD z%zJIa$lIO)8wC$1z{@{)^P|{x6cjf;HD1i`k1Q!a5>H08rQ-8Di@_O=E^vM+bJDN0 zWAWIPD#cAiJSWcEEL~FBeO}Io*PM#a?<{g0wl`SH+Uf*Vie0G+IX?u5hq?2LfKbh8 z5FVf3P2@Q29Q;@OxK2=|IFu5lko_RC@x&!H(^|-fzyB~f@R499AO7y%zPXiQbiZA; zq_Rbc4?Ed3>`Im5bM7P7?hN)HA25TeEmhCk==#?Y)Rlqr&)G+9V3pXI_#LEq7U zr21U-ymPbIbKb@2_Fl}n?u7IuvqEzQz)tuUPK7H%^(0**<#o^Y(D2_P1Y3!q*O=s9X!CoAiUhz@Wxh}C2mPZ(? zI^a-B0t#i^$i0)_O+@X1P>pP7@7-x>dnc1xufe$`gX_Nhd!ZT*e>Y_iA?H^zveUTn zJBhJUEvo(6?Z8)zO1@XS6&_-Ec?%p$iBhQe$Y{-)s=?aYR1Jsj0Yfc{=82m!Cv$;N z97>5&=-kcVSiyZ%Z>Umjsr~BylRXZcf63bV4ID~|j)LNIZVV8Ib076}i4SiL44U(k z3O^rSgFAN}RQP}ZeP2e&r^K`y4%OhC+=1g*?xTz< zr9?+T@sUG_8ANi^c~GT&*+?J9`#8T!{Hr}~e&D<#oc9KYQlbnd1vUi5_X>i^d2*sgPDYd+P-G6?xk?80N$e_J=Osk9 zO@RBt_v-^Ks{Q(?x195jxqaOLR2v|a617)~kBCMndJxK1LX~Q2AKhmChFY{eT({-l z06141N{Ld)Eg2)bn8?Yy8C}()+OM6%?Lu@-ehzmuJPd}HB~YdPDpg7?E0N4F=ihx{ z-Ol0-)}^dn)t0KAeRNyS z$0j(RPh8O`AhcgSRn-x3Zm)De{NA@ClF>k@7FB!(O@vbE%<==MT1Q;p3?Q^$r9>$t zdn=q@O?2BeaIQG?EL1hBb9N&92626Tz@hyrB}yTu&PZ%+-fiE;45~)fe)SyIIg`J^ z-;GFCK$Z5ZR4KLOreYPgB)V-9D^YRy=r&uss==MR2hLB1^Yu`r{VF9&AzlXZH;{OS zbC4+2&f2d@fkoEkGWaHI_e~-JdjO%7D20j-dv2?cc(}KqN^O+l^Dz@Sj&^X4_DQcV zX&=iiU^Yteg;d>u-u;H?gjUR;zKU1-5x!U-gZvfX{CcQTO0?gQs%G$UF?`Hp2K5(x zN3Z;m(}@VWTd-=|VF%R~DOF0Xb5G&%nLXc7vN(82McbcgzY6W#Lqu6LK&q~TbJgvt z&qIsTaZR&m*v<#U^~SUh^04S>o#tfWZQr^T(KozhY4~f+;H=L_kDDhG>fKR{RX)MuLGg| z`WHjShiY)L$^-G2J${O&0ik^ z+JWSjMOBp%0|@!q8<r-;y~oj@pfr4qpN#BwI7Plxkkv}b6a&x zKLdyUq7WgD;do=4iMcxwYoK;QAwoMi2l=~#w`Aj>N`FxZrIzz6r0GdsRP6;-nrTL% zHH!;%0eF%7C{ksbL2Z=A+^L>-t{!i&rgv^{?`wl>h}ue_*+=ox`v7tREI1_JZTtL! z{uQoCk?MKpw&HEyTJ+)|I5%#6E=IL7Y9)wO1II~7)p zlaFI%lljq$P^CDOLbWAu&W+`EyeMzNy7CzoY-Ol52ywiBQM>rHm%2n_m~(BV{e}>8 zS+|pTOaC!AbWf%hKyg#MhWrfuS@ErbP#oGyp?S9r!~iln98%(gca;^M4{xIsH?|h4 z#*zJk94Q$N-%9%pAs&SDzpv|(Tmt86C)5Jy{*$+sjBbmyU6LcK;m}qJ?Oc5%b{lNe za%NC*s2x8S*W4Kn4|u=7`s`OfnTBf9HMGEKQ+GaVT_XKWZU=>&cg~ z7pp|=g!Zf1x_JAF{C#jyyVPzov@eCwo`^!i;ylTVs`K#3)JAD5%{qoIL1GU>sw^Lw z=9ko6ky;<;3h!(zA3V8Hd}-1p$WEzyCxzyv-nKKMM}DavKYduoAUCesj4%V{tLwT% zcOZv=4wb(wb4BHTda--=eN$qTOnb zF0r=KYEU7>8*O%o$M3WtT7E^BpsJPH548+f=gW7Dzx(lts8#Fs0fe>+akT!qe%yWg z8PUwcI|fy)w3bw84eC#57=LzW`{B1j#36O}sWb>} zrKgc0L|4u%$B=<<*V37#r(Ihqh0YB{n%cdyvGNimO8eE?9BNDO$jExS&CvGA&*YTV zR$3)Q?Ftz-IQiINO|zsvrymNTtwJ1+BC-2#J0p1>snxxjLMT2mc_M#f*WR1-Mg|o^ z>!yVEqa69$cl0xf$)L7U`=OQrpBnl5%g;|Frz3+3p{+t37b1U6u~8k6LG4$o&xF>X z5%Tx>3BM(EkU?#w6-q*gk;vc6ZFWd2kwI;x_CqZLUN~6oHH)hPWZGN{=i)h;PCyKUre zX>Bt6A%ogV`wbypym@;0jLz-TU$Ho9ixfJ{>NxnTNzpp$4?Z?}NKhkJE9_d;4fFcT zvn+z{gQ->Xu=<16uj13n#Q2G$Z;hr?e{glPkSc`^akQm+ zM5+E@Y85=J{-EK|eyswB)gR2qYWa1GqKBwIIQRG=0fgdE=&b%=l;rgXQ?0#h6+BG0 zTfZTWW6xV2mFf?s`iu6fJ>fG@W8@U-4|Y3vNa`zUSig$HSKY7*)Xq_VFe>Kt2Lr0K zl|pZ+F=F)x1024xhxO}gkK|+ZpD&(_>QI01cGi`)QVJCx`DB)!5S>qDtF&jhcC8Z4 zS>3y4^RHE$x!ayGDjG&*tCN{?ZKc(rb-g+F%Z~d;A5eerwN^t?YKl}?{Xxrssr^zT zuEOdM=6w8x`Zy<0*=o>nLxLL8iZ6s1zTKvBt3UY4K|_KX(u$8Nb`@5CFwe``w||4^ zc*j)hW~;{10=kece;4N@4wKHEQQx9k{amUwQq(piZ^o(4M#} zqNdCwDqD4D&Nbt^Y6-1$xb_y3A@iYmRVVJ2S5#z38?@$&K%IOB$dVv^KS7VAl-lS^dGJRDUq2*6gc( zS-)W(;hUI?LH|yQeV7mLUs-lrUo*@gH1jwoMIB}*lc_)WPc*e=)75ItTE&?RP1i0; zj-meGyYQhIhBe2pR*H7+wZ09Kcc?!|MV(Y@FKZ4$t+0&tS#d&gU|xSPfY4gcnwOW? zHS1@Uznj+|OwpPZR)5e|xK>iOHD+0lbBWsP{msRhXdo&arJ6ZVt2JvCXLdzYo4T8- zQw>-pR@KJp51Izhy2x5pIjcVyeMk+ddKV2zwL&xYqQdGA8YLk_7v|z5>JQp{X!T^p zVU>2Q{$Q?s?xv!Z)gOEh4X0FTD~0CW9d))2rrwr$0E)vZ16ln+>sPBPJJ*m}LM^e- zFJPUul|m~%qP&^CQvJcysv24SLF-qmDu*~erzY8+)FwL;KJ*vGr#)r$2cuH`!BqRT zdQMh<(C}H+CaXV~j}`R?qf-6BfGUO1p2(U_#i@6wu||EhRQs|jQ&xY_`qk>t&b`h` z|BU*Bw%YX>a1zMq0e=t~yy2A0GDy;rsJ|A~d#q1QS znLWVhs?@4{sN9f&hT3Yi@ygD|I%_NKSMi~*Uf*0O!VC2WQ`G>f8C2%k(brvBUh#Mm z)n;^+Dy2lBfjA~DPNT+}jjr~kdPTEobLWNSGzjVs22?3@2=VA~D=QZ;?*pMq^^$7N zFnenqs>e=t=_v{i_M`h!WS z{$Q&5T(k6sx_tvxdtX9wJL6xe{m@oQAr*C~dsZv2KbUI2YSq-*F@u}QM1o#ig-+B~ z3a!*;^#_wu{lOqRzFN!B4&FZM*5om?_1kDTwU$bWLOb{I`OA}Cs6W^M`=QkXwBOco z?LxnOT36&=2K5J%QvJaILM^pI6W>m4@>2c5RJ{rHGW0pgURN+{$PMZDbb#? zy@Ayx&$N&FCEBn0C_qsC^hv6pnsru6w3R}$67h8pxNKJCYF4{?Uh0vBzRx3@o=nC) zv$^;IIJ94d4k7+aHQEzd@snBY>h)=b8^uR1y=|5yhi~35xdnZtt<(byy}n@smnS>) zXpmfv{m@nlt+<_gbn30ig*S~#+Oe+G-&N02eP632urN8}{u7esJ%^>#`O zT?@05U6Bv1+ogWAddtoow&CieeR_2=9-l!WltP6j59GVulDBVJl#Io*)Vf{jd51as zKUp#=x#r?qlN8Pshf<JCD87K)D?*gNf?^xbM%(vBHa?Al79 zdCl?AtjdXhU6Z`XO4M@^JueA&EPHHTQThDiNzw=1u2d;>2vPB2QtU#x?j>= znBpTh6|vMki3@K|2Aa2s(Y9#yQ^_;HdzPYQfjWin9m)D4E${WOI0ttPV$! z(V+&d?Y-k^wEBoDG?w?}1YUqXOQjpjGjkH(+<(wN`N-0*$>?AZ77K0=-Kaui@po6y z?+|bi<6b(@a;lc`I{F;m*DjL;29&Q6~k$>ey)!8Ku#}IR;lqiLG$VBc$kM5qX zC3;7z=e|juC98JwHn%dzQ}4+l{_UF+FCurgp`yI_td{dWq`b6*) zCuDE+9jDrFlkxp)PPVl#tq81@f~ho4eDKLsyV;5J_B%@ZC97sUio0P>w6h8~;d$ci zoae8kV#qn1>1!<+g$^Oe%$<^VIVBP>9mafH%#F>t&VO@i0$A+N;bg$&?rz!xmEDPf zJdDVGjdj%dIEZ(P7U?)Di|pTxS}cpUnUVCS9*cV0>gf+==Vy@> zSRr`pT(rCN!{Ca&Wcwh~PbT83cLIHrB9Dr&BM zYLfrKDlb~iFq3DiGin;=W^y0dYw}akE2d-Y@1|q2{D~>K+hSfjC8pKvb)M-#)4`T4 z(sZzDSN1sQs`GiFxg#&VP1oA{^B5easqL-yI99la9-FQ9k;HfHMx56LNR*Bu(MUzB z=5iZ6T~5|<%gk^5IrkxXanB)|{B>e$O=no#lIaYSD9e&&8tzNpV%aM}`*!X&G~Bnm z{A~tRrqxXAn|}4QUkoKWBD_T=OZu_Ib2cPq!gQ2>(QmrTXGYtL7(%;`ZbNJww*ctf zw~3>lThhC}mA-t@7cpD(Rc!jobd;}bYue|3ReEIajQkzI9ev@jrm;qUDTUgTbHm6> zbw2Mo|KMe@a%g(qUW1yR_w#>rW^o=vCobZyb0|7d;{cSZu;%1=s((F5>{4Iq73o>A zSp%zhYf^-aS6D<^E>Tp@N~oL_Tji`hsK#ZP5bPI)&=Y7*w!8n9jJWohXgc-0RH9Uh zRQ|b39ra9d$fVz*cc_Dwqg_2fa#K+!r7QJP=20s}Eso+)%i!GoKy;*nGv?ucK=9aVEET>va?Kh6<}NimVe!poi?o$#SF4Jd+o)FfR?(35$wVsZC{^ll zD716$5lQt7QDG-w2emJyD)fCCQRAmE|E#|AE9Md585wqMWfE+)_HxZIlbi6-XovUE z4El@W2tApnSXa9gea$` zrTL@gi|Q|mLwn*C9eSh!eR3_jMEliq*l=C7CmyvPUUDyFP$9IHW;f?XkxH}!@p=D> zzpD^RiQ;2-N7hKPN2ZpS)9)I3;)Q8WC(V&WO+9>u*-*8bsw8-l*>1~fb11%$s&>@h zIg9xA3UaHH8!p>HTBdY`4zsaeMdj1e@L)fMb8TfF5>cj^%02NUWKrdEGY zacI9GRj2ZvVcp9sk^{+HZyu}FW-yOcb+CD_Bd7tKd#}_VOsPMZTKz%gR`o}SV*oW} z5~7N&u8i)s)Mh9?PQ2jZad^2B9NMqyUDc?Z6mep(gg1m%7vK!?E!%$3b`AK`MXO6? z-*~h|%N1z+Q4NZ!a_1Ad+zcGrms*C(1 zY=3yZEArM-xz$l{&gwv%$=kahsaBvnA>Bc+FDP0~lYCe7FjT#ScbJS=z%}}*BF!}p0quUz@rAl#xqk9%B zq%M*7ws-b>GV9kg92{q!Wr(9BgINtw9Z}_6apSk+DRm;&ayZ_S?hUkG^_;W%g9-Hq zW2--?oa?OVC}i~qD{o_WXY~h7i`t&k*B@kcWPB)3+`i)Rt>Hb+8*r|aXumoloN{8- zs6QC{`h&h-^~ggUbEs)~ENkm}sIp(YeN{bgxU1~>bgGyQB=-D|YSlc{W+-%)HKLOG zgJ})4585U>r@Ru4qt-_=>r&rS5Skau4DLY1~s90!(8 zAahO4o7AK?FWhQzGBFzcZMDzr7d`h=4Ni^qmsTWHe^1W=LT!fjt35e)EdBo-JVyhe zc0#qNo-H~zn%1WRbtDjqUGarDs6Uu)Lw1~C)Gw*Iahqdp0h&u7dHooYBj}YtHj=) z=MuG8NM*2NUWK z##Vn&acCeQ?BGf0c5S85dTN9Wa$36; zw@XvOVGwqsWR_EPyHV@+BJ5H*tzC-6>4C*jyQEe|p*evh7qVrcy{KAFK+U~$Avuf5 zJy|>>J3W7lDwq$l8uu)XmB+5uK()4Wb2!;Pn%B#BPz_4$V2vivSCAW}Xf{!y$st4z zmS)@p9K$WZ8Qgwa?K3-}*E`5iQx79QN)No`?ZKh_Ds*T+CR6?ECo-OVQSzz%Evsr# z-BUSt60Ns}sssq_OL2r$QGYO<1ZAC}N^f$_SGQV1W|vf>I=2fquXY35m)lqEOF36t z;@p22+3U%@Q((^3-l;}aeAo|ocmiH_D&4X88(!sBM;9Zu2m@_F7c;hTOO#O&iG}v>TjjU&^hH0L&q*kG! zil~~Ch_1PiEKpu^e$BnC-3eQsWq&7ZQ9b#c@W073c_x9!VRZ=F!>#}OF&XElm*RaIm+rQGjE~|_+(f-V(Htn-lYNv%9_gM+ zHLBI^J3Kv>f0uy6b8ePQZB%#yNe=qd>P_r2YC+oy@)6q}$8@{tdCRli0oti{oc-Ot zv-*Q6^#@a{Kd3nL#51%XQ(04er{)#%dXi7laM&JD&;4|7$f+}&Ukm4(nGfYq`_&Q2 z>JO$B)Hs~LSSb$c*J|GTJ*U^MS^dG3`h$tpA5rM>I8BnFIloB0jUNy2pT9dW+X{ge=uS$vCy)g0xyL)l25ArvH z+_mJu4x$ZpM0KROcV<4eWj;O!LR%^4IwD#9!O91)oWA~`x136qQtMoIeBCec0M5me zQCp<_Dm1Tzn2(XHtsbTM@OutxWwC?iGw7|8bH|}a%2@HQ0-<(ETPd`2hj4=P3MV-i zRm)7FFMu^dkXuW}iaMa__cpq+6H*JHTASB^R4Os4z*t$5ptMm-#e)e&gu`Q)E_KAmeExX6`zg>_iAXkyU=ih@ZmIe%vOoTR$By}*REe> zF?ZA$Nv~-(HF_C7bVO|w{LWNy^TwUodz?xb`%-^U^`PpNeK579JI;%gJjHgb+^pY;2zsxR~Y%|(f)MRK4%p04V0XK=1msRd9CP82J3&%P+t4AWMM&;LD-%%t{NO8vpC_L;`!+lsOJY8Gd! z8kKh}?1-q$p8iI}ui6al*P=rG+XHT8c%ASluN0mELi;sY@%t$I_VxsQ;JVVWXsx(-=qGZ_G`1|dZu3+^CRnIGhS^dG3`h#(A>JRGZYUFxoKUUy}QhzYE`h%vC@hGxA znQ|NAXpa0@O;(!^-^#|yf7|#dzAZOD8HCvn&xiKwzw=WyszD{Twmc3WHEFH<{gD68 zA&L_pt(;$~arnP(l&qD9$nD_1-1dD%d{lGZ0{FWv(?0s5N?$%@_0>{eU(H9D+3PHe zbg>9r`}Vi}`J0B9v9*)1wKq{Staa&pZ*=L!fbnGG7TUohsQ%TMf3Hw~&{l)DORAl1 zz1izJ^BJAn2FtnDs!mgXP+y;^%~0IrHpGX!gY|n7uQ^N(yj@a!ewUG-C!Ry=M(n{@yKQXwgLpIV@ovH-)y@;Wql>>Fq01-A(p>tG#`=r zgXJwteAvmRVOOdYpL6f9cCTmu@jNrA+EVqrjjn$yMZR!2w_1(wuu5!9{0>q_A>{lZ zR-x4ZO^`v=qKeP&CUW_B9{D?nebm2L?TTHgQrubn!Q=?eukK+#Xwu2A1=9?=H|$or z3(NO||6rx}MN?l^(j^{3HK*6XxxZ`P7+zUCnfiljag?Xf8c=yLwHk!AOLFdarV0^q zPNmJHGdq?}tajx?DN&xt4~P8yhUIL+Sb587noL`T_Tx(A?`Q1bL{^D%>+O~8AhhPJ zb5x_Pv}&}z{$O>BW7Z&qC|R7$MtL0ml#7)Tcmuh`S;c%%e=wa;qRQ-&{i6EZM#1ZO z@*1$`r2b&KCv&blA$`@V(A)yB6TY5PVeSnA-EJ$xA{A_9ggWtabnb^}pzh3vVpj{G zmch9VoLOGMndNO%46#>#c4ld>{uDyr+7g|>iEuCe{R^rTyY1EO7Raaywdhn%AgO}iJAMZaunL^%L9|dhX!}baGHpldekDAVPNe{+~`e*6!;802e3T52# zTba+HY!VQvk?ri=>crXJ$)wh6aLz2@+PMF3H5~rl$RI+_uV!RBa}L1id7wqLU%MT! z+IRV0?M8U$4lf(Pp_C|viZ81_m~O|~`lcEV-2;YN^l;{40Gv+;LUAZ1N?}%iFs1%r zc`v9^ZK?h0{*$vlIRB2d^)on>6163YFRMS8QhzYAN`H#OpgBJ&^Yh^~cvgQfrT$>$ z8BnD-loF+oY*ui-m|Gcc6a#BulvoW&!=W0SIY(lT<38#?B|bbQN}=K-nu;0Zb~LLX zseRc_=eNT7 z1RxZLQl->#)`$FA9Z;)3Xc+`7#@uAh$E}$R`k1?12JeIO&Tu}p8dZuzDWsw&vT-?Q zWL6JS-yExMSG$tcA572SK8pLnOwR31wbz4N>{aRAwv7U}0Ic+*v9*U)!=e3#w$}9S zJ)A&ZSq+D_QhS9AB7Z$NPwYmP0;OHwRBO#yA{z0n_Myh}8)#~^MG754Jb=g76%WAb z4|*GA7DxF|Xf!pWOZ~yr>JQp4K1YJ;bJg>_cjjDa1LsRte^Bj`X1q{nZuN;Vn2rRVqNdHG~XMb>*iCY@Upt4h zYCicnTuXQu2QT+PmG-MtDYd+`Ag{~D20m8 zx!J73*~G)W0#$0G6rYco$Z?dzIsfARaITanzL2Ub(YxOgozR*Y)GQZjKQwoSbC)20 zo#4DLR4FCeZ%EaF@G%%Z-e(5&7tH~p{5f|75p=g=)vW%Y+9IV&sderj`EDY(lDC$4(Ui9n zgUOMil-Svcz4SM#RD)Az6o|1vyaq5%4Hm7fTH38Z zXkQ8)LRb=VmeA{XgxOjA72TFNF>v zs6Uuef3WgGqIa}k|1!vMs0PpK52n-~tlSf-v@eAYAr|o3>Au(JlphL&_Um5;c|M3~ zD&4D5e=w!~V7XPhQQfZnYENX@BzxJunHO)NHta$(q}9>JO&W zAB?ss@!_#6RjTueq2~;sl8R|owa33DvbAKRYwx`5JH+uR^YM4;fDSIrhrc;g916{i z2`ljx-Y!`cKE+`x(cUE+4%OQ1Qh~6_q0a)Lc0!>;h+T3SjBf@)`_(g2)!MlXB8Txk zKxkhI9YQ3?-%Mi9p8`Vr_3`G$hwA*S{$N7=!Pq$0z7#ry*aP{a{$PALqpN#BwI7O) zST*GD4XS6o1`hp2AwnE8@y5O<=I&&yf!Ya$2<_k$$*zDZ{Y4>^TC#E>P0M*v z)eNdy#$&S>`tkT83auHToU6f$-1$hAL8y(=m^;<;&K=4dtcBF(c!Ap`&48z^6q=ic zzsyglKbYQ69W1qK{uQoCk?MKw)ySKWpcgNNbK}YM&_%%N6w@xvz~6J2k$D&JRiIVDKi_TxY-Fq)p)XBd{DySTWP-`#2h$(gZgLJz`5E9wE(*R zbZ#S~8?EgU9bFBFwo+*4_CR85V562YgNj4#pjrmb;aFEK$ZS5FB*dkDpi&}=`ren+S(28?o9sp7n=+! z4uw`*lGPtfs6QB6{Xso9RLc&d0p8W~g^8XKL;&{3>J?MorFCn{lL zan|sn>RdcBwNctiGZ>;vkl2HfDw8O+IJzrR>qAv`Dy5x2xlwu<)zUO$tL~i?no}IA zm_0~#)fcE_rg>}CW`sFqU#I@(;!@>BwKCeTLUUS6-LpH$$9f*M&lHE{2khOwYi12X z`_Y!VXNAeXC8tpPOk1h_P|JXgqV8FPsXL}8Q2R_Fv{i_s3-ZxxuT4oz?KADyawgWH zCdZ#`6!iy_Bd&WUsY&fKZDrXPn^HmK&k!$>i)`>t3zCG|XWB~bhgt?a8M3|AB->jv zYM&{DwhC=j3+kSA-F`-L9ktK2U(0j27nMo=Y@?_@m{NZ*vHFAB%CZ*Dq}s}#A$}(# z*RTPfRDMY9Gi_z(ewGi{Ak;FDua8`0LmzLJJVfm?h0s=^jk<@7b-$5ma|Bs7wO^l6 z&~Sv-U_KDPQn7G25ZX#lBSVPJoLN3ezL)x?GfPjqwo(eo4udq!p{nQQNR;+#`2opp zlkJcU!dp9TU&$i)+K~3qPh@GuvZ5866VrWYJ z!N{am_i75E__F$gX)o%4o{bDDgk}3X?y6du77gvkk;vaM)B!aa)K+Rg)G|=v2>EMF z9njv$ph9S?5Jz|9uLCyfSY%N9wM=|{K5vsz6LoI`IKar`h6S-KAL&_6?rME)ihXF$65w literal 0 HcmV?d00001 diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_aileron.dae b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_aileron.dae new file mode 100644 index 00000000..31aaf457 --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_aileron.dae @@ -0,0 +1,151 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-05T12:13:49 + 2023-07-05T12:13:49 + + Z_UP + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.498039 0.498039 0.498039 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + -0.001739084 -0.001946091 0.001782715 -0.01573908 -0.001946091 -0.002717196 -0.001739084 -0.001946091 -0.002717196 -0.01573908 -0.001946091 0.001782715 -0.01573908 5.38668e-5 -0.002717196 -0.001739084 5.38668e-5 -0.002717196 -0.001739084 -0.001946091 -0.002717196 -0.01573908 -0.001946091 -0.002717196 -0.001739084 5.38668e-5 -0.003717243 -0.01573908 5.38668e-5 -0.002717196 -0.01573908 5.38668e-5 -0.003717243 -0.001739084 5.38668e-5 -0.002717196 -0.001739084 5.38668e-5 -0.003717243 -0.01573908 5.38668e-5 -0.003717243 -0.01573908 -0.001946091 -0.003717243 -0.001739084 -0.001946091 -0.003717243 -0.01573908 -0.001946091 -0.008217275 -0.001739084 -0.001946091 -0.008217275 -0.001739084 -0.001946091 -0.003717243 -0.01573908 -0.001946091 -0.003717243 -0.01573908 -0.001946091 0.001782715 -0.001739084 -0.001946091 0.001782715 -0.001739084 -0.003601491 0.001782715 -0.01573908 -0.004033148 0.001782715 -0.001739084 -0.001946091 -0.003717243 -0.001739084 -0.001946091 -0.008217275 -0.001739084 -0.00347656 -0.008217275 -0.001739084 5.38668e-5 -0.002717196 -0.001739084 5.38668e-5 -0.003717243 -0.001739084 -0.001946091 -0.002717196 -0.001739084 -0.003601491 0.001782715 -0.001739084 -0.001946091 0.001782715 -0.01573908 -0.001946091 -0.008217275 -0.01573908 -0.003908157 -0.008217275 -0.001739084 -0.00347656 -0.008217275 -0.001739084 -0.001946091 -0.008217275 -0.01573908 -0.001946091 -0.002717196 -0.01573908 -0.001946091 0.001782715 -0.01573908 -0.004033148 0.001782715 -0.01573908 5.38668e-5 -0.003717243 -0.01573908 5.38668e-5 -0.002717196 -0.01573908 -0.001946091 -0.003717243 -0.01573908 -0.003908157 -0.008217275 -0.01573908 -0.001946091 -0.008217275 -0.01573908 -0.003712832 -0.1232172 -0.01873707 -8.89933e-4 -0.1232172 -3.63097e-4 -0.003237903 -0.1232172 -3.82096e-4 0.002756297 -0.1232172 -0.01873707 0.002835869 -0.1232172 -0.01577007 0.00504297 -0.1232172 0.01500487 4.36397e-4 -0.1232172 0.01501488 -0.002700328 -0.1232172 0.03037387 -0.001946091 -0.1232172 -0.01577007 0.00504297 -0.1232172 -0.01873707 0.002835869 -0.1232172 -0.01873707 0.003397345 -0.04423022 -0.01577007 0.005858898 0.0348457 -0.01577007 0.005601108 -0.04415422 -0.01873707 0.003656327 0.03476971 -0.01577007 0.005816459 0.1137827 -0.01873707 0.003612875 0.1137827 8.22902e-4 0.003136277 -0.04427325 -0.01577007 0.005601108 -0.04415422 -0.01577007 0.005858898 0.0348457 0.01758486 6.09057e-4 -0.04427325 7.72908e-4 0.003401041 0.03472673 0.0183919 7.44697e-4 0.03472673 -3.82096e-4 0.002756297 -0.1232172 -0.01577007 0.00504297 -0.1232172 0.03484386 -0.001989245 -0.02847725 0.002221882 0.003139436 0.1137827 -0.01577007 0.005816459 0.1137827 0.03601288 -0.001970052 0.06634271 0.03584086 -0.001987457 0.01892274 0.0184859 6.77177e-4 0.1137827 0.0353589 -0.001937031 0.1137827 0.01500487 4.36397e-4 -0.1232172 0.03302186 -0.001975476 -0.07585722 0.03037387 -0.001946091 -0.1232172 0.01501488 -0.002700328 -0.1232172 0.03037387 -0.001946091 -0.1232172 0.03302186 -0.001975476 -0.07585722 -0.01573908 -0.002990841 -0.08592724 -3.63097e-4 -0.003237903 -0.1232172 8.43897e-4 -0.00339365 -0.04427325 -0.01573908 -0.003712832 -0.1232172 0.03484386 -0.001989245 -0.02847725 0.01759588 -0.002807974 -0.04427325 0.001455903 -0.003382861 0.1137827 0.01840287 -0.002846956 0.03472673 0.01850289 -0.002769589 0.1137827 -0.001739084 -0.00347656 -0.008217275 -0.01573908 -0.00305593 -0.04759424 0.03601288 -0.001970052 0.06634271 0.0353589 -0.001937031 0.1137827 7.94902e-4 -0.003462553 0.03472673 -0.001739084 -0.003601491 0.001782715 -0.01573908 -0.004187762 0.05779975 -0.01573908 -0.004033148 0.001782715 -0.01573908 -0.003915607 0.1137827 -0.01573908 -0.003908157 -0.008217275 0.03584086 -0.001987457 0.01892274 -0.01873707 -0.001135826 -0.004729211 -0.01573908 -0.004033148 0.001782715 -0.01573908 -0.004187762 0.05779975 -0.01573908 -0.003712832 -0.1232172 -0.01573908 -0.002990841 -0.08592724 -0.01873707 -8.89933e-4 -0.1232172 -0.01573908 -0.00305593 -0.04759424 -0.01573908 -0.003908157 -0.008217275 -0.01873707 -0.001095592 0.1137827 -0.01573908 -0.003915607 0.1137827 -0.01873707 -8.89933e-4 -0.1232172 -0.01873707 -0.001135826 -0.004729211 -0.01873707 0.003397345 -0.04423022 -0.01873707 0.002835869 -0.1232172 -0.01873707 0.003656327 0.03476971 -0.01873707 -0.001095592 0.1137827 -0.01873707 0.003612875 0.1137827 -0.01173704 0.001258611 0.1087827 -0.01298308 0.002228021 0.1087827 -0.01313906 0.002174377 0.1087827 -0.01233607 0.002174377 0.1087827 -0.01194804 0.001872837 0.1087827 -0.01206004 0.001994311 0.1087827 -0.01219004 0.002095758 0.1087827 -0.01249206 0.002228021 0.1087827 -0.01185804 0.001734554 0.1087827 -0.01179206 0.001583278 0.1087827 -0.01265507 0.002255201 0.1087827 -0.01282006 0.002255201 0.1087827 -0.01175105 0.00142318 0.1087827 -0.01185804 7.82577e-4 0.1087827 -0.01179206 9.33857e-4 0.1087827 -0.01341509 0.001994311 0.1087827 -0.01328408 0.002095758 0.1087827 -0.01175105 0.001093983 0.1087827 -0.01352608 0.001872837 0.1087827 -0.01361709 0.001734554 0.1087827 -0.01194804 6.44287e-4 0.1087827 -0.01233607 3.42767e-4 0.1087827 -0.01372408 0.00142318 0.1087827 -0.01373708 0.001258611 0.1087827 -0.01206004 5.22777e-4 0.1087827 -0.01368308 0.001583278 0.1087827 -0.01219105 4.21347e-4 0.1087827 -0.01368308 9.34097e-4 0.1087827 -0.01361709 7.82897e-4 0.1087827 -0.01282006 2.62107e-4 0.1087827 -0.01372408 0.001093983 0.1087827 -0.01265507 2.62047e-4 0.1087827 -0.01249206 2.89177e-4 0.1087827 -0.01341509 5.23137e-4 0.1087827 -0.0132851 4.21677e-4 0.1087827 -0.01313906 3.43027e-4 0.1087827 -0.01298308 2.89347e-4 0.1087827 -0.01352709 6.44647e-4 0.1087827 0.0184859 6.77177e-4 0.1137827 0.01850289 -0.002769589 0.1137827 0.0353589 -0.001937031 0.1137827 -0.01873707 0.003612875 0.1137827 0.002221882 0.003139436 0.1137827 -0.01577007 0.005816459 0.1137827 -0.01233506 3.43027e-4 0.1137827 -0.01249206 2.89347e-4 0.1137827 0.001455903 -0.003382861 0.1137827 -0.01282006 2.62047e-4 0.1137827 -0.01873707 -0.001095592 0.1137827 -0.01265406 2.62107e-4 0.1137827 -0.01573908 -0.003915607 0.1137827 -0.01298308 0.002228021 0.1137827 -0.01282006 0.002255201 0.1137827 -0.01352608 0.001872837 0.1137827 -0.01341509 0.001994311 0.1137827 -0.01179206 0.001583278 0.1137827 -0.01175105 0.00142318 0.1137827 -0.01173704 0.001258611 0.1137827 -0.01265507 0.002255201 0.1137827 -0.01194804 0.001872837 0.1137827 -0.01185804 0.001734554 0.1137827 -0.01219004 0.002095758 0.1137827 -0.01206004 0.001994311 0.1137827 -0.01249206 0.002228021 0.1137827 -0.01233607 0.002174377 0.1137827 -0.01328408 0.002095758 0.1137827 -0.01313906 0.002174377 0.1137827 -0.01368308 0.001583278 0.1137827 -0.01361709 0.001734554 0.1137827 -0.01373708 0.001258611 0.1137827 -0.01372408 0.00142318 0.1137827 -0.01368308 9.33857e-4 0.1137827 -0.01372408 0.001093983 0.1137827 -0.01219004 4.21677e-4 0.1137827 -0.01352608 6.44287e-4 0.1137827 -0.01361709 7.82577e-4 0.1137827 -0.01328408 4.21347e-4 0.1137827 -0.01341408 5.22777e-4 0.1137827 -0.01298308 2.89177e-4 0.1137827 -0.01313906 3.42767e-4 0.1137827 -0.01194804 6.44647e-4 0.1137827 -0.01206004 5.23137e-4 0.1137827 -0.01185804 7.82897e-4 0.1137827 -0.01175105 0.001093983 0.1137827 -0.01179105 9.34097e-4 0.1137827 -0.01175105 0.00142318 0.1087827 -0.01173704 0.001258611 0.1087827 -0.01173704 0.001258611 0.1137827 -0.01194804 0.001872837 0.1087827 -0.01185804 0.001734554 0.1087827 -0.01185804 0.001734554 0.1137827 -0.01179206 0.001583278 0.1087827 -0.01175105 0.00142318 0.1137827 -0.01179206 0.001583278 0.1137827 -0.01219004 0.002095758 0.1137827 -0.01233607 0.002174377 0.1087827 -0.01219004 0.002095758 0.1087827 -0.01194804 0.001872837 0.1137827 -0.01206004 0.001994311 0.1137827 -0.01206004 0.001994311 0.1087827 -0.01265507 0.002255201 0.1087827 -0.01265507 0.002255201 0.1137827 -0.01282006 0.002255201 0.1087827 -0.01249206 0.002228021 0.1087827 -0.01233607 0.002174377 0.1137827 -0.01249206 0.002228021 0.1137827 -0.01328408 0.002095758 0.1087827 -0.01313906 0.002174377 0.1087827 -0.01313906 0.002174377 0.1137827 -0.01298308 0.002228021 0.1137827 -0.01298308 0.002228021 0.1087827 -0.01282006 0.002255201 0.1137827 -0.01352608 0.001872837 0.1137827 -0.01361709 0.001734554 0.1087827 -0.01352608 0.001872837 0.1087827 -0.01328408 0.002095758 0.1137827 -0.01341509 0.001994311 0.1137827 -0.01341509 0.001994311 0.1087827 -0.01372408 0.00142318 0.1087827 -0.01372408 0.00142318 0.1137827 -0.01373708 0.001258611 0.1087827 -0.01368308 0.001583278 0.1087827 -0.01361709 0.001734554 0.1137827 -0.01368308 0.001583278 0.1137827 -0.01361709 7.82897e-4 0.1087827 -0.01368308 9.34097e-4 0.1087827 -0.01368308 9.33857e-4 0.1137827 -0.01372408 0.001093983 0.1137827 -0.01372408 0.001093983 0.1087827 -0.01373708 0.001258611 0.1137827 -0.01341408 5.22777e-4 0.1137827 -0.0132851 4.21677e-4 0.1087827 -0.01341509 5.23137e-4 0.1087827 -0.01361709 7.82577e-4 0.1137827 -0.01352608 6.44287e-4 0.1137827 -0.01352709 6.44647e-4 0.1087827 -0.01298308 2.89347e-4 0.1087827 -0.01298308 2.89177e-4 0.1137827 -0.01282006 2.62107e-4 0.1087827 -0.01313906 3.43027e-4 0.1087827 -0.01328408 4.21347e-4 0.1137827 -0.01313906 3.42767e-4 0.1137827 -0.01265507 2.62047e-4 0.1087827 -0.01265406 2.62107e-4 0.1137827 -0.01249206 2.89177e-4 0.1087827 -0.01282006 2.62047e-4 0.1137827 -0.01249206 2.89347e-4 0.1137827 -0.01233607 3.42767e-4 0.1087827 -0.01219105 4.21347e-4 0.1087827 -0.01233506 3.43027e-4 0.1137827 -0.01219004 4.21677e-4 0.1137827 -0.01206004 5.22777e-4 0.1087827 -0.01206004 5.23137e-4 0.1137827 -0.01194804 6.44287e-4 0.1087827 -0.01185804 7.82577e-4 0.1087827 -0.01194804 6.44647e-4 0.1137827 -0.01185804 7.82897e-4 0.1137827 -0.01179206 9.33857e-4 0.1087827 -0.01179105 9.34097e-4 0.1137827 -0.01175105 0.001093983 0.1087827 -0.01175105 0.001093983 0.1137827 + + + + + + + + + + 0 -1 0 0 0 -1 0 0 1 0 0 -1 -1 0 0 -1 0 0 0 0 1 1 0 0 1 -7.20995e-7 0 6.31392e-7 0 -1 1.20658e-6 0 -1 -1.20801e-6 0 -1 -0.5968313 0.8023468 -0.005676507 -0.5962037 0.8028225 -0.004150688 -0.5960371 0.8029562 -0.001068115 -0.5961892 0.8028335 -0.004120051 -0.5960371 0.8029562 -0.001098632 -0.5962338 0.8028109 4.32025e-4 -0.5960718 0.8029311 4.41549e-4 0.1479878 0.9889761 -0.005096673 0.1468863 0.9891403 -0.005096614 0.1469478 0.9891434 -0.001312255 0.1509795 0.9885235 -0.005157768 0.148015 0.9889842 -0.001342773 0.1509768 0.9885365 -0.001281738 0.1480159 0.9889603 -0.006988763 0.1469786 0.9891152 -0.006958246 0.1523197 0.9883238 -0.003845334 0.1471671 0.9891115 5.75748e-4 0.1517705 0.9884157 4.88302e-4 0.15238 0.9883186 -0.002594053 0.1511604 0.9885089 9.46088e-4 0.1530843 0.9882122 0.001403868 0.1508535 0.9885286 -0.007385492 0.1516476 0.9884104 -0.006927728 0.1531738 0.9881675 -0.007934868 0.146964 0.9891417 5.32303e-4 0.1483822 0.9889299 6.10375e-4 0.04171919 -0.9991254 -0.002868711 0.04904377 -0.998791 -0.003357052 0.04825079 -0.9988313 -0.002838253 -0.01373368 -0.9999054 9.461e-4 0.02627652 -0.999638 0.005798518 0.008301198 -0.9999638 -0.001922667 0.03085446 -0.9993366 0.01934885 0.04858583 -0.9988182 -0.001281738 0.04184114 -0.9991227 -0.001800596 0.03466922 -0.9993959 0.002471983 0.0422995 -0.999105 3.35711e-4 0.04248225 -0.9990966 0.001098632 -0.01962023 -0.9998008 -0.003703713 0.04843366 -0.9988261 8.24013e-4 0.04931801 -0.9987822 0.001373291 0.03976565 -0.9992087 9.15557e-4 0.03430348 -0.9994096 -0.002014219 0.04232996 -0.9991034 7.62977e-4 0.03079348 -0.9995221 -0.002746641 0.03096872 -0.9995086 0.004858672 0.0308088 -0.9992913 -0.02162772 0.04861634 -0.9988174 -6.40894e-4 -0.01434379 -0.999887 -0.00451678 0.0157476 -0.9997919 -0.01297038 0.04470175 -0.9990002 6.33388e-4 -0.6844309 -0.7290199 -0.009186327 -0.6912578 -0.7226009 -0.003234982 -0.7146201 -0.6995128 2.44158e-4 -0.6854606 -0.7279738 0.01406931 -0.5666504 -0.823958 -8.54538e-4 -0.6782205 -0.7347415 0.01312309 -0.5610284 -0.8277938 -0.00213629 -0.6886305 -0.7249428 -0.01568996 -0.6866735 -0.7269583 0.003357052 -0.6845998 -0.7288622 -0.009110033 -0.6851483 -0.7283951 0.003540754 -1 -2.20727e-7 0 -1 -2.05554e-7 0 2.50277e-5 0 1 -1.36016e-4 0 1 3.96059e-4 0 1 4.61205e-5 0 1 -5.47561e-5 0 1 3.00018e-5 0 1 -5.52506e-5 0 1 -1.15161e-4 0 1 1.06352e-4 0 1 -1.89117e-5 0 1 -5.47568e-5 0 1 -4.47874e-5 0 1 9.22544e-5 0 1 -3.31935e-5 0 1 -3.80861e-5 0 1 4.79349e-5 0 1 5.00813e-7 0 1 1.29339e-4 0 1 2.90532e-7 0 1 1.54679e-5 0 1 4.40257e-6 0 1 1.5654e-6 0 1 -1.63702e-6 0 1 1.82168e-5 0 1 -1.95207e-6 0 1 -2.8304e-6 0 1 1.57483e-5 0 1 -2.08054e-5 0 1 -1.93532e-5 0 1 4.04955e-6 0 1 -3.83562e-5 0 1 2.47241e-6 0 1 -1.27824e-5 0 1 -1.81604e-7 0 1 3.31115e-5 0 1 -2.42934e-5 0 1 3.87882e-5 0 1 -3.07538e-5 0 1 -8.4155e-6 0 1 -7.14569e-6 0 1 1.11954e-5 0 1 -1.40835e-6 0 1 3.58216e-5 0 1 -4.92365e-7 0 1 7.38294e-6 0 1 -0.9859617 -0.1669719 0 -0.789464 -0.613797 0 -0.8803299 -0.4743618 0 -0.9457033 -0.3250312 0 -0.5465461 -0.8374291 0 -0.4008733 -0.9161336 0 -0.5465675 -0.837415 0 -0.7894788 -0.6137779 0 -0.6775027 -0.7355203 0 -0.08252263 -0.9965893 0 0.08252263 -0.9965893 0 -0.2456509 -0.9693583 0 0.5461989 -0.8376556 0 0.4022129 -0.9155463 0 0.245615 -0.9693675 0 0.7892915 -0.6140188 0 0.8791418 -0.4765604 0 0.6777729 -0.7352713 0 0.9864591 -0.164008 0 0.9457033 -0.3250312 0 0.879129 -0.476584 0 0.8802976 0.4744219 0 0.9456406 0.3252137 0 0.9457254 0.3249672 0 0.986464 0.1639783 0 0.9864335 0.1641614 0 0.677471 0.7355495 -6.10389e-5 0.5467164 0.8373178 -3.05189e-5 0.677551 0.735476 -6.10379e-5 0.879194 0.476464 -3.05191e-5 0.7879402 0.6157519 -9.15571e-5 0.7894229 0.6138498 -3.05185e-5 0.2459235 0.9692893 3.05192e-5 0.245371 0.9694292 0 0.08285856 0.9965614 0 0.4011742 0.9160017 0 0.5476374 0.8367158 0 0.4020625 0.9156123 3.05194e-5 -0.08215636 0.9966195 0 -0.08334857 0.9965205 0 -0.245407 0.9694202 0 0.08218669 0.996617 0 -0.245493 0.9693984 0 -0.4020001 0.9156397 0 -0.5461068 0.8377156 3.0519e-5 -0.4015744 0.9158264 0 -0.5478783 0.8365581 0 -0.6761516 0.7367626 0 -0.677551 0.735476 -3.05189e-5 -0.7894903 0.6137632 -3.05188e-5 -0.8803623 0.4743018 -3.05194e-5 -0.7894525 0.6138117 -3.05197e-5 -0.8790117 0.4768002 6.10382e-5 -0.9457033 0.3250312 6.10387e-5 -0.945672 0.3251224 6.10387e-5 -0.9859776 0.1668779 6.1038e-5 -0.9864236 0.1642208 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.000999987 -0.004499971 5e-4 0.000999987 -0.004499971 -5e-4 1.98119e-4 -8.91535e-4 -5e-4 1.98119e-4 -8.91535e-4 5e-4 0.0139994 -0.002500057 5e-4 0.000999987 -0.004499971 -5e-4 0.000999987 -0.004499971 5e-4 0.0139994 -0.002500057 -5e-4 -2.05869e-4 -5.07125e-4 -5e-4 0.01349997 -5e-4 -5e-4 -2.89975e-4 -5e-4 -5e-4 1.98119e-4 -8.91535e-4 -5e-4 0.01395899 -0.002202689 -5e-4 0.01390826 -0.001907825 -5e-4 -4.71754e-5 -5.62909e-4 -5e-4 -1.24159e-4 -5.28295e-4 -5e-4 2.2889e-5 -6.09979e-4 -5e-4 8.40373e-5 -6.68164e-4 -5e-4 1.34527e-4 -7.35806e-4 -5e-4 1.72919e-4 -8.10977e-4 -5e-4 0.000999987 -0.004499971 -5e-4 0.0139994 -0.002500057 -5e-4 0.01384729 -0.001615524 -5e-4 0.013776 -0.001325726 -5e-4 0.01369446 -0.001038491 -5e-4 0.01360255 -7.53803e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 -4.71754e-5 -5.62909e-4 5e-4 -1.24159e-4 -5.28295e-4 5e-4 0.01349997 -5e-4 5e-4 1.72919e-4 -8.10977e-4 5e-4 1.34527e-4 -7.35806e-4 5e-4 1.98119e-4 -8.91535e-4 5e-4 0.01360255 -7.53803e-4 5e-4 0.01369446 -0.001038491 5e-4 2.2889e-5 -6.09979e-4 5e-4 8.40373e-5 -6.68164e-4 5e-4 -2.05869e-4 -5.07125e-4 5e-4 0.01350045 -4.71615e-4 5e-4 -2.89975e-4 -5e-4 5e-4 0.013776 -0.001325726 5e-4 0.01384729 -0.001615524 5e-4 0.01390826 -0.001907825 5e-4 0.01395899 -0.002202689 5e-4 0.000999987 -0.004499971 5e-4 0.0139994 -0.002500057 5e-4 1.34527e-4 -7.35806e-4 -5e-4 1.34527e-4 -7.35806e-4 5e-4 1.72919e-4 -8.10977e-4 5e-4 1.98119e-4 -8.91535e-4 5e-4 1.98119e-4 -8.91535e-4 -5e-4 1.72919e-4 -8.10977e-4 -5e-4 2.2889e-5 -6.09979e-4 5e-4 -4.71754e-5 -5.62909e-4 -5e-4 -4.71754e-5 -5.62909e-4 5e-4 2.2889e-5 -6.09979e-4 -5e-4 8.40373e-5 -6.68164e-4 5e-4 8.40373e-5 -6.68164e-4 -5e-4 -1.24159e-4 -5.28295e-4 5e-4 -2.05869e-4 -5.07125e-4 -5e-4 -2.05869e-4 -5.07125e-4 5e-4 -1.24159e-4 -5.28295e-4 -5e-4 -2.89975e-4 -5e-4 5e-4 -2.89975e-4 -5e-4 -5e-4 0.01384729 -0.001615524 5e-4 0.013776 -0.001325726 -5e-4 0.01384729 -0.001615524 -5e-4 0.01390826 -0.001907825 -5e-4 0.01390826 -0.001907825 5e-4 0.01395899 -0.002202689 -5e-4 0.01395899 -0.002202689 5e-4 0.0139994 -0.002500057 5e-4 0.0139994 -0.002500057 -5e-4 0.013776 -0.001325726 5e-4 0.01369446 -0.001038491 -5e-4 0.01369446 -0.001038491 5e-4 0.01360255 -7.53803e-4 5e-4 0.01360255 -7.53803e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 0.01350045 -4.71615e-4 5e-4 0.01349997 -5e-4 0.004999995 -2.89975e-4 -5e-4 5e-4 -5e-4 -5e-4 0.004999995 -5e-4 -5e-4 -0.004999995 -2.89975e-4 -5e-4 -5e-4 0.01349997 -5e-4 -5e-4 0.01349997 -5e-4 -0.004999995 0.01349997 -5e-4 5e-4 0.01349997 5e-4 0.004999995 0.01349997 5e-4 -0.004999995 0.01350045 -4.71615e-4 5e-4 0.01349997 -5e-4 0.004999995 0.01349997 -5e-4 -0.004999995 0.01349997 -5e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 0.01349997 -5e-4 5e-4 -5e-4 -5e-4 0.004999995 -5e-4 5e-4 0.004999995 0.01349997 5e-4 0.004999995 0.01349997 -5e-4 0.004999995 -5e-4 -5e-4 -0.004999995 -5e-4 5e-4 -0.004999995 -5e-4 5e-4 0.004999995 -5e-4 -5e-4 0.004999995 0.01349997 5e-4 -0.004999995 -5e-4 5e-4 -0.004999995 -5e-4 -5e-4 -0.004999995 0.01349997 -5e-4 -0.004999995 -5e-4 5e-4 0.004999995 -5e-4 5e-4 -0.004999995 0 5e-4 7e-4 0 5e-4 -7e-4 0.01349997 5e-4 -0.004999995 0.01304668 5e-4 -7e-4 0.01349997 5e-4 0.004999995 0.01304668 5e-4 7e-4 0.01304525 5.02356e-4 6.69369e-4 0 5e-4 7e-4 0 5.02462e-4 6.68713e-4 0 5.38197e-4 5.82443e-4 0.01302689 5.35564e-4 5.86251e-4 0 5.21799e-4 6.09202e-4 0 5.09789e-4 6.38197e-4 0.01303517 5.20529e-4 6.11725e-4 0.01304137 5.0931e-4 6.39671e-4 0.01299178 5.97314e-4 5.28303e-4 0 5.82443e-4 5.38197e-4 0 6.09202e-4 5.21799e-4 0.0130167 5.53746e-4 5.63605e-4 0 5.58579e-4 5.58579e-4 0.01300495 5.74514e-4 5.4422e-4 0.01296305 6.47245e-4 5.07011e-4 0 6.38197e-4 5.09789e-4 0 6.68713e-4 5.02462e-4 0.01297777 6.21703e-4 5.1589e-4 0 7e-4 5e-4 0.01294785 6.73484e-4 5.01805e-4 0.01293236 7e-4 5e-4 0.01304668 5e-4 7e-4 2.21952e-4 0.01132625 5e-4 0.0115 0.002499997 -5e-4 0.0115 0.002499997 5e-4 2.21952e-4 0.01132625 -5e-4 2.90924e-7 0.01156806 -5e-4 2.90924e-7 0.01156806 5e-4 -5.45318e-5 0.01166325 5e-4 -9.8578e-5 0.01176398 5e-4 -9.8578e-5 0.01176398 -5e-4 -5.45318e-5 0.01166325 -5e-4 1.39249e-4 0.01139867 5e-4 1.39249e-4 0.01139867 -5e-4 2.21952e-4 0.01132625 -5e-4 6.52065e-5 0.01147949 5e-4 6.52065e-5 0.01147949 -5e-4 2.21952e-4 0.01132625 5e-4 -0.002154469 0.01727068 5e-4 -9.8578e-5 0.01176398 -5e-4 -9.8578e-5 0.01176398 5e-4 -0.002154469 0.01727068 -5e-4 -0.005992531 0.01667195 5e-4 -0.005999982 0.01649999 5e-4 -0.005999982 0.01649999 -5e-4 -0.005883276 0.01717305 5e-4 -0.00593388 0.01700979 5e-4 -0.00593388 0.01700979 -5e-4 -0.005970597 0.01684159 5e-4 -0.005992531 0.01667195 -5e-4 -0.005970597 0.01684159 -5e-4 -0.005740702 0.01748478 -5e-4 -0.005649507 0.01763087 5e-4 -0.005740702 0.01748478 5e-4 -0.005883276 0.01717305 -5e-4 -0.005818367 0.01733255 -5e-4 -0.005818367 0.01733255 5e-4 -0.005432128 0.01789599 5e-4 -0.005432128 0.01789599 -5e-4 -0.005307674 0.01801317 5e-4 -0.005546927 0.01776766 5e-4 -0.005649507 0.01763087 -5e-4 -0.005546927 0.01776766 -5e-4 -0.004878759 0.01829659 5e-4 -0.005030035 0.01821428 5e-4 -0.005030035 0.01821428 -5e-4 -0.005172669 0.01812005 -5e-4 -0.005172669 0.01812005 5e-4 -0.005307674 0.01801317 -5e-4 -0.00455904 0.01842015 -5e-4 -0.004392981 0.01846098 5e-4 -0.00455904 0.01842015 5e-4 -0.004878759 0.01829659 -5e-4 -0.004722118 0.01836508 -5e-4 -0.004722118 0.01836508 5e-4 -0.00405234 0.01849925 5e-4 -0.00405234 0.01849925 -5e-4 -0.003880143 0.01849639 5e-4 -0.004222869 0.01848745 5e-4 -0.004392981 0.01846098 -5e-4 -0.004222869 0.01848745 -5e-4 -0.003376424 0.01840025 5e-4 -0.003540933 0.01844656 5e-4 -0.003540933 0.01844656 -5e-4 -0.003710091 0.01847887 -5e-4 -0.003710091 0.01847887 5e-4 -0.003880143 0.01849639 -5e-4 -0.003061056 0.0182659 -5e-4 -0.00291264 0.01817846 5e-4 -0.003061056 0.0182659 5e-4 -0.003376424 0.01840025 -5e-4 -0.003215253 0.01833957 -5e-4 -0.003215253 0.01833957 5e-4 -0.002773225 0.01807957 5e-4 -0.00291264 0.01817846 -5e-4 -0.002773225 0.01807957 -5e-4 -0.002641916 0.01796817 5e-4 -0.002641916 0.01796817 -5e-4 -0.002521514 0.01784688 5e-4 -0.002411127 0.01771467 5e-4 -0.002521514 0.01784688 -5e-4 -0.002411127 0.01771467 -5e-4 -0.002313196 0.01757454 5e-4 -0.002313196 0.01757454 -5e-4 -0.002227604 0.01742655 5e-4 -0.002154469 0.01727068 5e-4 -0.002227604 0.01742655 -5e-4 -0.002154469 0.01727068 -5e-4 -0.005999982 0.008914172 5e-4 -0.005999982 0.01649999 -5e-4 -0.005999982 0.01649999 5e-4 -0.005999982 0.008914172 -5e-4 -0.005781888 0.008290827 5e-4 -0.005707085 0.008207082 5e-4 -0.005707085 0.008207082 -5e-4 -0.005943894 0.008583962 5e-4 -0.005900979 0.008480429 5e-4 -0.005900979 0.008480429 -5e-4 -0.005846798 0.00838238 5e-4 -0.005781888 0.008290827 -5e-4 -0.005846798 0.00838238 -5e-4 -0.005993664 0.008802056 -5e-4 -0.005993664 0.008802056 5e-4 -0.005974948 0.008691906 -5e-4 -0.005943894 0.008583962 -5e-4 -0.005974948 0.008691906 5e-4 -0.005999982 0.008914172 5e-4 -0.005999982 0.008914172 -5e-4 -2.92893e-4 0.002792835 5e-4 -0.005707085 0.008207082 -5e-4 -0.005707085 0.008207082 5e-4 -2.92893e-4 0.002792835 -5e-4 -2.51435e-5 0.002308547 -5e-4 -2.51435e-5 0.002308547 5e-4 -6.31239e-6 0.002197861 5e-4 0 0.002085745 5e-4 0 0.002085745 -5e-4 -6.31239e-6 0.002197861 -5e-4 -9.90717e-5 0.002519726 5e-4 -1.53405e-4 0.002617955 -5e-4 -1.53405e-4 0.002617955 5e-4 -9.90717e-5 0.002519726 -5e-4 -5.61788e-5 0.002416193 5e-4 -5.61788e-5 0.002416193 -5e-4 -2.18067e-4 0.00270909 5e-4 -2.18067e-4 0.00270909 -5e-4 -2.92893e-4 0.002792835 -5e-4 -2.92893e-4 0.002792835 5e-4 0 5.09789e-4 6.38197e-4 0 5.02462e-4 -6.68713e-4 0 5.09789e-4 -6.38197e-4 0 5e-4 -7e-4 0 5.02462e-4 6.68713e-4 0 5.38197e-4 -5.82443e-4 0 5.58579e-4 -5.58579e-4 0 5.58579e-4 5.58579e-4 0 5.21799e-4 -6.09202e-4 0 5.38197e-4 5.82443e-4 0 5.21799e-4 6.09202e-4 0 6.38197e-4 -5.09789e-4 0 6.38197e-4 5.09789e-4 0 6.09202e-4 -5.21799e-4 0 6.09202e-4 5.21799e-4 0 5.82443e-4 5.38197e-4 0 5.82443e-4 -5.38197e-4 0 6.68713e-4 -5.02462e-4 0 6.68713e-4 5.02462e-4 0 7e-4 5e-4 0 7e-4 -5e-4 0 0.002085745 -5e-4 0 0.002085745 5e-4 0 5e-4 7e-4 0 6.38197e-4 -5.09789e-4 0.01297765 6.21724e-4 -5.16018e-4 0.01296305 6.47241e-4 -5.07144e-4 0 7e-4 -5e-4 0 6.68713e-4 -5.02462e-4 0.01294785 6.73474e-4 -5.01807e-4 0.01300495 5.74515e-4 -5.44227e-4 0 5.58579e-4 -5.58579e-4 0.0130167 5.53722e-4 -5.63585e-4 0 5.82443e-4 -5.38197e-4 0.01299178 5.9735e-4 -5.28409e-4 0 6.09202e-4 -5.21799e-4 0 5.09789e-4 -6.38197e-4 0.01304137 5.09316e-4 -6.39685e-4 0.01303517 5.20533e-4 -6.11742e-4 0 5.21799e-4 -6.09202e-4 0.01302689 5.35529e-4 -5.86212e-4 0 5.38197e-4 -5.82443e-4 0 5.02462e-4 -6.68713e-4 0.01304525 5.02361e-4 -6.69377e-4 0.01304668 5e-4 -7e-4 0 5e-4 -7e-4 0.01293236 7e-4 -5e-4 0.01297765 6.21724e-4 -5.16018e-4 0.01299178 5.9735e-4 -5.28409e-4 0.01297777 6.21703e-4 5.1589e-4 0.01304137 5.0931e-4 6.39671e-4 0.01304137 5.09316e-4 -6.39685e-4 0.01304525 5.02361e-4 -6.69377e-4 0.01304668 5e-4 -7e-4 0.01304668 5e-4 7e-4 0.01304525 5.02356e-4 6.69369e-4 0.01302689 5.35564e-4 5.86251e-4 0.01302689 5.35529e-4 -5.86212e-4 0.01303517 5.20533e-4 -6.11742e-4 0.01303517 5.20529e-4 6.11725e-4 0.01299178 5.97314e-4 5.28303e-4 0.01300495 5.74515e-4 -5.44227e-4 0.01300495 5.74514e-4 5.4422e-4 0.0130167 5.53722e-4 -5.63585e-4 0.0130167 5.53746e-4 5.63605e-4 0.01296305 6.47241e-4 -5.07144e-4 0.01294785 6.73484e-4 5.01805e-4 0.01294785 6.73474e-4 -5.01807e-4 0.01296305 6.47245e-4 5.07011e-4 0.01293236 7e-4 -5e-4 0.01293236 7e-4 5e-4 0.01258188 0.001242518 -5e-4 0.01258188 0.001242518 5e-4 0.012389 0.001505315 5e-4 0.01276296 9.74095e-4 5e-4 0.01276296 9.74095e-4 -5e-4 0.01196795 0.002013921 5e-4 0.01173985 0.00225979 5e-4 0.01196795 0.002013921 -5e-4 0.01218438 0.001762449 5e-4 0.01218438 0.001762449 -5e-4 0.012389 0.001505315 -5e-4 0.01173985 0.00225979 -5e-4 0.0115 0.002499997 5e-4 0.0115 0.002499997 -5e-4 -0.004992663 0.01312065 5e-4 -0.004999995 0.01299995 -5e-4 -0.004999995 0.01299995 5e-4 -0.004885435 0.01346457 5e-4 -0.004935026 0.01335448 -5e-4 -0.004935026 0.01335448 5e-4 -0.004970967 0.01323896 5e-4 -0.004970967 0.01323896 -5e-4 -0.004992663 0.01312065 -5e-4 -0.004748642 0.01366287 -5e-4 -0.004748642 0.01366287 5e-4 -0.004663169 0.01374846 5e-4 -0.004885435 0.01346457 -5e-4 -0.004823088 0.01356774 5e-4 -0.004823088 0.01356774 -5e-4 -0.004464924 0.01388525 5e-4 -0.004354774 0.01393485 5e-4 -0.004464924 0.01388525 -5e-4 -0.004568159 0.01382285 5e-4 -0.004568159 0.01382285 -5e-4 -0.004663169 0.01374846 -5e-4 -0.004000246 0.01399999 5e-4 -0.004120767 0.01399266 -5e-4 -0.004120767 0.01399266 5e-4 -0.00423932 0.01397085 -5e-4 -0.004354774 0.01393485 -5e-4 -0.00423932 0.01397085 5e-4 -0.003760695 0.01397085 -5e-4 -0.003760695 0.01397085 5e-4 -0.003645658 0.01393508 5e-4 -0.004000246 0.01399999 -5e-4 -0.003879606 0.01399266 5e-4 -0.003879606 0.01399266 -5e-4 -0.003431975 0.01382297 5e-4 -0.003336966 0.01374858 5e-4 -0.003431975 0.01382297 -5e-4 -0.003535509 0.01388555 5e-4 -0.003535509 0.01388555 -5e-4 -0.003645658 0.01393508 -5e-4 -0.003114521 0.01346474 5e-4 -0.003177106 0.01356816 -5e-4 -0.003177106 0.01356816 5e-4 -0.003251671 0.01366329 -5e-4 -0.003336966 0.01374858 -5e-4 -0.003251671 0.01366329 5e-4 -0.003029108 0.01323956 -5e-4 -0.003029108 0.01323956 5e-4 -0.003007292 0.01312065 5e-4 -0.003114521 0.01346474 -5e-4 -0.003065049 0.01335477 5e-4 -0.003065049 0.01335477 -5e-4 -0.003007292 0.01287925 5e-4 -0.003028988 0.01276099 5e-4 -0.003007292 0.01287925 -5e-4 -0.002999961 0.01299995 5e-4 -0.002999961 0.01299995 -5e-4 -0.003007292 0.01312065 -5e-4 -0.003176867 0.01243215 5e-4 -0.003114461 0.01253539 -5e-4 -0.003114461 0.01253539 5e-4 -0.00306493 0.01264548 -5e-4 -0.003028988 0.01276099 -5e-4 -0.00306493 0.01264548 5e-4 -0.003336787 0.01225149 -5e-4 -0.003336787 0.01225149 5e-4 -0.003431797 0.01217705 5e-4 -0.003176867 0.01243215 -5e-4 -0.003251314 0.01233708 5e-4 -0.003251314 0.01233708 -5e-4 -0.003645181 0.01206505 5e-4 -0.003760635 0.01202905 5e-4 -0.003645181 0.01206505 -5e-4 -0.003534972 0.0121147 5e-4 -0.003534972 0.0121147 -5e-4 -0.003431797 0.01217705 -5e-4 -0.003879189 0.01200729 -5e-4 -0.003760635 0.01202905 -5e-4 -0.003879189 0.01200729 5e-4 -0.004120349 0.01200729 5e-4 -0.004120349 0.01200729 -5e-4 -0.00399971 0.01199996 -5e-4 -0.00399971 0.01199996 5e-4 -0.004239201 0.01202905 5e-4 -0.004239201 0.01202905 -5e-4 -0.004354298 0.01206487 -5e-4 -0.004354298 0.01206487 5e-4 -0.004464447 0.01211434 5e-4 -0.004464447 0.01211434 -5e-4 -0.004567921 0.01217699 5e-4 -0.004567921 0.01217699 -5e-4 -0.00466299 0.01225137 -5e-4 -0.00466299 0.01225137 5e-4 -0.004748284 0.01233667 5e-4 -0.004748284 0.01233667 -5e-4 -0.00482285 0.0124318 5e-4 -0.00482285 0.0124318 -5e-4 -0.004885375 0.01253515 -5e-4 -0.004885375 0.01253515 5e-4 -0.004934906 0.01264518 5e-4 -0.004934906 0.01264518 -5e-4 -0.004970848 0.0127604 5e-4 -0.004970848 0.0127604 -5e-4 -0.004992663 0.01287925 -5e-4 -0.004992663 0.01287925 5e-4 -0.004992663 0.01662069 5e-4 -0.004999995 0.01649999 -5e-4 -0.004999995 0.01649999 5e-4 -0.004885435 0.01696455 5e-4 -0.004935026 0.01685446 -5e-4 -0.004935026 0.01685446 5e-4 -0.004970967 0.01673895 5e-4 -0.004970967 0.01673895 -5e-4 -0.004992663 0.01662069 -5e-4 -0.004748642 0.01716285 -5e-4 -0.004748642 0.01716285 5e-4 -0.004663169 0.01724845 5e-4 -0.004885435 0.01696455 -5e-4 -0.004823088 0.01706779 5e-4 -0.004823088 0.01706779 -5e-4 -0.004464924 0.0173853 5e-4 -0.004354774 0.01743489 5e-4 -0.004464924 0.0173853 -5e-4 -0.004568159 0.01732289 5e-4 -0.004568159 0.01732289 -5e-4 -0.004663169 0.01724845 -5e-4 -0.004000246 0.01749998 5e-4 -0.004120767 0.01749265 -5e-4 -0.004120767 0.01749265 5e-4 -0.00423932 0.01747089 -5e-4 -0.004354774 0.01743489 -5e-4 -0.00423932 0.01747089 5e-4 -0.003760695 0.01747089 -5e-4 -0.003760695 0.01747089 5e-4 -0.003645658 0.01743507 5e-4 -0.004000246 0.01749998 -5e-4 -0.003879606 0.01749265 5e-4 -0.003879606 0.01749265 -5e-4 -0.003431975 0.01732295 5e-4 -0.003336966 0.01724857 5e-4 -0.003431975 0.01732295 -5e-4 -0.003535509 0.0173856 5e-4 -0.003535509 0.0173856 -5e-4 -0.003645658 0.01743507 -5e-4 -0.003114521 0.01696479 5e-4 -0.003177106 0.01706814 -5e-4 -0.003177106 0.01706814 5e-4 -0.003251671 0.01716327 -5e-4 -0.003336966 0.01724857 -5e-4 -0.003251671 0.01716327 5e-4 -0.003029108 0.01673954 -5e-4 -0.003029108 0.01673954 5e-4 -0.003007292 0.01662069 5e-4 -0.003114521 0.01696479 -5e-4 -0.003065049 0.01685476 5e-4 -0.003065049 0.01685476 -5e-4 -0.003007292 0.01637929 5e-4 -0.003028988 0.01626098 5e-4 -0.003007292 0.01637929 -5e-4 -0.002999961 0.01649999 5e-4 -0.002999961 0.01649999 -5e-4 -0.003007292 0.01662069 -5e-4 -0.003176867 0.0159322 5e-4 -0.003114461 0.01603537 -5e-4 -0.003114461 0.01603537 5e-4 -0.00306493 0.01614546 -5e-4 -0.003028988 0.01626098 -5e-4 -0.00306493 0.01614546 5e-4 -0.003336787 0.01575148 -5e-4 -0.003336787 0.01575148 5e-4 -0.003431797 0.01567709 5e-4 -0.003176867 0.0159322 -5e-4 -0.003251314 0.01583707 5e-4 -0.003251314 0.01583707 -5e-4 -0.003645181 0.01556509 5e-4 -0.003760635 0.01552909 5e-4 -0.003645181 0.01556509 -5e-4 -0.003534972 0.01561468 5e-4 -0.003534972 0.01561468 -5e-4 -0.003431797 0.01567709 -5e-4 -0.003879189 0.01550728 -5e-4 -0.003760635 0.01552909 -5e-4 -0.003879189 0.01550728 5e-4 -0.004120349 0.01550728 5e-4 -0.004120349 0.01550728 -5e-4 -0.00399971 0.01549994 -5e-4 -0.00399971 0.01549994 5e-4 -0.004239201 0.01552909 5e-4 -0.004239201 0.01552909 -5e-4 -0.004354298 0.01556485 -5e-4 -0.004354298 0.01556485 5e-4 -0.004464447 0.01561439 5e-4 -0.004464447 0.01561439 -5e-4 -0.004567921 0.01567697 5e-4 -0.004567921 0.01567697 -5e-4 -0.00466299 0.01575136 -5e-4 -0.00466299 0.01575136 5e-4 -0.004748284 0.01583665 5e-4 -0.004748284 0.01583665 -5e-4 -0.00482285 0.01593178 5e-4 -0.00482285 0.01593178 -5e-4 -0.004885375 0.01603519 -5e-4 -0.004885375 0.01603519 5e-4 -0.004934906 0.01614516 5e-4 -0.004934906 0.01614516 -5e-4 -0.004970848 0.01626038 5e-4 -0.004970848 0.01626038 -5e-4 -0.004992663 0.01637929 -5e-4 -0.004992663 0.01637929 5e-4 -0.003999948 0.008499979 5e-4 -0.005707085 0.008207082 5e-4 -0.004120171 0.008507251 5e-4 0 0.002085745 5e-4 -6.31239e-6 0.002197861 5e-4 0.0115 0.002499997 5e-4 -0.005030035 0.01821428 5e-4 -0.004464924 0.0173853 5e-4 -0.005172669 0.01812005 5e-4 0 7e-4 5e-4 0.01173985 0.00225979 5e-4 0.01218438 0.001762449 5e-4 0.01196795 0.002013921 5e-4 0.012389 0.001505315 5e-4 0.01258188 0.001242518 5e-4 0.01276296 9.74095e-4 5e-4 0.01293236 7e-4 5e-4 -2.51435e-5 0.002308547 5e-4 -5.61788e-5 0.002416193 5e-4 -9.90717e-5 0.002519726 5e-4 -1.53405e-4 0.002617955 5e-4 -2.18067e-4 0.00270909 5e-4 2.21952e-4 0.01132625 5e-4 -2.92893e-4 0.002792835 5e-4 6.52065e-5 0.01147949 5e-4 -0.003114521 0.009964764 5e-4 2.90924e-7 0.01156806 5e-4 -0.003065049 0.009854733 5e-4 1.39249e-4 0.01139867 5e-4 -0.003029108 0.009739577 5e-4 -0.003114461 0.01253539 5e-4 -0.00306493 0.01264548 5e-4 -9.8578e-5 0.01176398 5e-4 -0.003431797 0.01217705 5e-4 -0.003336787 0.01225149 5e-4 -0.003336966 0.0102486 5e-4 -0.003028988 0.01276099 5e-4 -0.003007292 0.01287925 5e-4 -0.002999961 0.01299995 5e-4 -0.004354774 0.01743489 5e-4 -0.004722118 0.01836508 5e-4 -0.00423932 0.01747089 5e-4 -0.004970967 0.01673895 5e-4 -0.00593388 0.01700979 5e-4 -0.004935026 0.01685446 5e-4 -0.00455904 0.01842015 5e-4 -0.004392981 0.01846098 5e-4 -0.004878759 0.01829659 5e-4 -0.004568159 0.01732289 5e-4 -0.004120767 0.01749265 5e-4 -0.004000246 0.01749998 5e-4 -0.004222869 0.01848745 5e-4 -0.004663169 0.01724845 5e-4 -0.005307674 0.01801317 5e-4 -0.003880143 0.01849639 5e-4 -0.00405234 0.01849925 5e-4 -0.004748642 0.01716285 5e-4 -0.005432128 0.01789599 5e-4 -0.003879606 0.01749265 5e-4 -0.005546927 0.01776766 5e-4 -0.003710091 0.01847887 5e-4 -0.003540933 0.01844656 5e-4 -0.005649507 0.01763087 5e-4 -0.004823088 0.01706779 5e-4 -0.003760695 0.01747089 5e-4 -0.003376424 0.01840025 5e-4 -0.003645658 0.01743507 5e-4 -0.004885435 0.01696455 5e-4 -0.005740702 0.01748478 5e-4 -0.003061056 0.0182659 5e-4 -0.003215253 0.01833957 5e-4 -0.005818367 0.01733255 5e-4 -0.003535509 0.0173856 5e-4 -0.00291264 0.01817846 5e-4 -0.003431975 0.01732295 5e-4 -0.005883276 0.01717305 5e-4 -0.002641916 0.01796817 5e-4 -0.002773225 0.01807957 5e-4 -0.003336966 0.01724857 5e-4 -0.002521514 0.01784688 5e-4 -0.003251671 0.01716327 5e-4 -0.004992663 0.01662069 5e-4 -0.005970597 0.01684159 5e-4 -0.004999995 0.01649999 5e-4 -0.005999982 0.01649999 5e-4 -0.005992531 0.01667195 5e-4 -0.004934906 0.01614516 5e-4 -0.004885375 0.01603519 5e-4 -0.004992663 0.01637929 5e-4 -0.004970848 0.01626038 5e-4 -0.004748284 0.01583665 5e-4 -0.004748642 0.01366287 5e-4 -0.00482285 0.01593178 5e-4 -0.00466299 0.01575136 5e-4 -0.004663169 0.01374846 5e-4 -5.45318e-5 0.01166325 5e-4 -0.003177106 0.01006817 5e-4 -0.004464447 0.00861442 5e-4 -0.004354536 0.008564949 5e-4 -0.004567742 0.008676826 5e-4 -0.004239022 0.008528947 5e-4 -0.005999982 0.008914172 5e-4 -0.004999995 0.01299995 5e-4 -0.004992663 0.01287925 5e-4 -0.003114521 0.01346474 5e-4 -0.003114461 0.01603537 5e-4 -0.003176867 0.01243215 5e-4 -0.003645181 0.01206505 5e-4 -0.003535509 0.01038557 5e-4 -0.003645658 0.0104351 5e-4 -0.003534972 0.0121147 5e-4 -0.003431975 0.01032298 5e-4 -0.003251314 0.01233708 5e-4 -0.003760695 0.01047086 5e-4 -0.003760635 0.01202905 5e-4 -0.003251671 0.01016324 5e-4 -0.004000246 0.01049995 5e-4 -0.004120767 0.01049268 5e-4 -0.004120349 0.01200729 5e-4 -0.003879189 0.01200729 5e-4 -0.003879606 0.01049268 5e-4 -0.00399971 0.01199996 5e-4 -0.004567921 0.01217699 5e-4 -0.004464924 0.01038527 5e-4 -0.004568159 0.01032286 5e-4 -0.004354298 0.01206487 5e-4 -0.00423932 0.01047086 5e-4 -0.004354774 0.01043486 5e-4 -0.00466299 0.01225137 5e-4 -0.004748344 0.008836686 5e-4 -0.004822731 0.008931636 5e-4 -0.004663169 0.01024848 5e-4 -0.004885315 0.00903511 5e-4 -0.005900979 0.008480429 5e-4 -0.004970788 0.009260356 5e-4 -0.004934906 0.009145259 5e-4 -0.004999995 0.009499967 5e-4 -0.004992663 0.009620666 5e-4 -0.004934906 0.01264518 5e-4 -0.004885375 0.01253515 5e-4 -0.004885435 0.009964585 5e-4 -0.004935026 0.009854435 5e-4 -0.004970848 0.0127604 5e-4 -0.004970967 0.01323896 5e-4 -0.004992663 0.01312065 5e-4 -0.004567921 0.01567697 5e-4 -0.004568159 0.01382285 5e-4 -0.004885435 0.01346457 5e-4 -0.004935026 0.01335448 5e-4 -0.004823088 0.01356774 5e-4 -0.00423932 0.01397085 5e-4 -0.004239201 0.01552909 5e-4 -0.004120767 0.01399266 5e-4 -0.004464924 0.01388525 5e-4 -0.004464447 0.01561439 5e-4 -0.004354774 0.01393485 5e-4 -0.003760635 0.01552909 5e-4 -0.003760695 0.01397085 5e-4 -0.003879189 0.01550728 5e-4 -0.00399971 0.01549994 5e-4 -0.004000246 0.01399999 5e-4 -0.004120349 0.01550728 5e-4 -0.003431797 0.01567709 5e-4 -0.003431975 0.01382297 5e-4 -0.003534972 0.01561468 5e-4 -0.003535509 0.01388555 5e-4 -0.003645181 0.01556509 5e-4 -0.003336966 0.01374858 5e-4 -0.003336787 0.01575148 5e-4 -0.002313196 0.01757454 5e-4 -0.003177106 0.01706814 5e-4 -0.002411127 0.01771467 5e-4 -0.003251314 0.01583707 5e-4 -0.003177106 0.01356816 5e-4 -0.003251671 0.01366329 5e-4 -0.003176867 0.0159322 5e-4 -0.00306493 0.01614546 5e-4 -0.002154469 0.01727068 5e-4 -0.003007292 0.01637929 5e-4 -0.002999961 0.01649999 5e-4 -0.003028988 0.01626098 5e-4 -0.003065049 0.01335477 5e-4 -0.003007292 0.01312065 5e-4 -0.003029108 0.01323956 5e-4 -0.003645658 0.01393508 5e-4 -0.003879606 0.01399266 5e-4 -0.004354298 0.01556485 5e-4 -0.002227604 0.01742655 5e-4 -0.003114521 0.01696479 5e-4 -0.003029108 0.01673954 5e-4 -0.003065049 0.01685476 5e-4 -0.003007292 0.01662069 5e-4 -0.003028988 0.009260952 5e-4 -0.003007292 0.009379208 5e-4 -0.002999961 0.009499967 5e-4 -0.005781888 0.008290827 5e-4 -0.005846798 0.00838238 5e-4 -0.003114402 0.009035527 5e-4 -0.00306493 0.009145438 5e-4 -0.003176808 0.008932173 5e-4 -0.003336727 0.00875163 5e-4 -0.003251373 0.008836925 5e-4 -0.003535091 0.008614599 5e-4 -0.003431618 0.008677184 5e-4 -0.003760337 0.008529126 5e-4 -0.003645241 0.008565008 5e-4 -0.003879189 0.008507311 5e-4 -0.00466299 0.008751392 5e-4 -0.004464447 0.01211434 5e-4 -0.004748284 0.01233667 5e-4 -0.004748642 0.01016288 5e-4 -0.005943894 0.008583962 5e-4 -0.005974948 0.008691906 5e-4 -0.00482285 0.0124318 5e-4 -0.005993664 0.008802056 5e-4 -0.004823088 0.01006776 5e-4 -0.004992663 0.009379208 5e-4 -0.004970967 0.009739041 5e-4 -0.004239201 0.01202905 5e-4 -0.003007292 0.009620666 5e-4 -0.005707085 0.008207082 -5e-4 -0.004464864 0.008614599 -5e-4 -0.004568278 0.008677184 -5e-4 -5.61788e-5 0.002416193 -5e-4 -2.51435e-5 0.002308547 -5e-4 0.0115 0.002499997 -5e-4 -6.31239e-6 0.002197861 -5e-4 -9.90717e-5 0.002519726 -5e-4 -1.53405e-4 0.002617955 -5e-4 2.21952e-4 0.01132625 -5e-4 -2.18067e-4 0.00270909 -5e-4 -0.004120767 0.008507311 -5e-4 -0.004239618 0.008529126 -5e-4 -0.003999948 0.008499979 -5e-4 -0.00482285 0.01593178 -5e-4 -0.004885375 0.01603519 -5e-4 -0.005999982 0.01649999 -5e-4 -0.004992663 0.01287925 -5e-4 -0.004999995 0.01299995 -5e-4 -0.005999982 0.008914172 -5e-4 -0.003760695 0.01747089 -5e-4 -0.003645658 0.01743507 -5e-4 -0.003376424 0.01840025 -5e-4 -0.005970597 0.01684159 -5e-4 -0.004992663 0.01662069 -5e-4 -0.004970967 0.01673895 -5e-4 -0.004000246 0.01749998 -5e-4 -0.004222869 0.01848745 -5e-4 -0.004120767 0.01749265 -5e-4 -0.004722118 0.01836508 -5e-4 -0.004354774 0.01743489 -5e-4 -0.00423932 0.01747089 -5e-4 -0.005030035 0.01821428 -5e-4 -0.005172669 0.01812005 -5e-4 -0.004464924 0.0173853 -5e-4 -0.004392981 0.01846098 -5e-4 -0.00455904 0.01842015 -5e-4 -0.004878759 0.01829659 -5e-4 -0.004568159 0.01732289 -5e-4 -0.004663169 0.01724845 -5e-4 -0.005432128 0.01789599 -5e-4 -0.004748642 0.01716285 -5e-4 -0.005307674 0.01801317 -5e-4 -0.005546927 0.01776766 -5e-4 -0.003880143 0.01849639 -5e-4 -0.00405234 0.01849925 -5e-4 -0.005649507 0.01763087 -5e-4 -0.004823088 0.01706779 -5e-4 -0.003879606 0.01749265 -5e-4 -0.005740702 0.01748478 -5e-4 -0.004885435 0.01696455 -5e-4 -0.003710091 0.01847887 -5e-4 -0.003540933 0.01844656 -5e-4 -0.003061056 0.0182659 -5e-4 -0.003215253 0.01833957 -5e-4 -0.004935026 0.01685446 -5e-4 -0.005818367 0.01733255 -5e-4 -0.00291264 0.01817846 -5e-4 -0.003535509 0.0173856 -5e-4 -0.003431975 0.01732295 -5e-4 -0.005883276 0.01717305 -5e-4 -0.002641916 0.01796817 -5e-4 -0.002773225 0.01807957 -5e-4 -0.00593388 0.01700979 -5e-4 -0.002521514 0.01784688 -5e-4 -0.003336966 0.01724857 -5e-4 -0.003251671 0.01716327 -5e-4 -0.004999995 0.01649999 -5e-4 -0.005992531 0.01667195 -5e-4 -0.004934906 0.01614516 -5e-4 -0.004992663 0.01637929 -5e-4 -0.004970848 0.01626038 -5e-4 -0.004748642 0.01366287 -5e-4 -0.004748284 0.01583665 -5e-4 -0.003645181 0.01206505 -5e-4 -0.003760635 0.01202905 -5e-4 -0.003645181 0.01043486 -5e-4 -0.004663169 0.01374846 -5e-4 -0.00466299 0.01575136 -5e-4 -0.004934906 0.009854733 -5e-4 -0.004970848 0.009739577 -5e-4 -0.004885554 0.009035527 -5e-4 -0.005993664 0.008802056 -5e-4 -0.003251314 0.01233708 -5e-4 -0.003251314 0.01016288 -5e-4 -9.8578e-5 0.01176398 -5e-4 -0.004354655 0.008565008 -5e-4 -2.92893e-4 0.002792835 -5e-4 -5.45318e-5 0.01166325 -5e-4 -0.003176867 0.01006776 -5e-4 -0.004823148 0.008932173 -5e-4 -0.004748582 0.008836925 -5e-4 -0.005781888 0.008290827 -5e-4 -0.005846798 0.00838238 -5e-4 2.90924e-7 0.01156806 -5e-4 -0.003114461 0.009964585 -5e-4 6.52065e-5 0.01147949 -5e-4 0 0.002085745 -5e-4 0 7e-4 -5e-4 0.01196795 0.002013921 -5e-4 0.01173985 0.00225979 -5e-4 0.01218438 0.001762449 -5e-4 0.012389 0.001505315 -5e-4 0.01276296 9.74095e-4 -5e-4 0.01258188 0.001242518 -5e-4 0.01293236 7e-4 -5e-4 -0.002999961 0.009499967 -5e-4 -0.003007292 0.009379208 -5e-4 -0.003028988 0.009739041 -5e-4 1.39249e-4 0.01139867 -5e-4 -0.00306493 0.009854435 -5e-4 -0.003029167 0.009260356 -5e-4 -0.00306499 0.009145259 -5e-4 -0.003114581 0.00903511 -5e-4 -0.003251612 0.008836686 -5e-4 -0.003177225 0.008931636 -5e-4 -0.003432154 0.008676826 -5e-4 -0.003336966 0.008751392 -5e-4 -0.00364542 0.008564949 -5e-4 -0.003535509 0.00861442 -5e-4 -0.003879725 0.008507251 -5e-4 -0.003760933 0.008528947 -5e-4 -0.004663228 0.00875163 -5e-4 -0.005900979 0.008480429 -5e-4 -0.005974948 0.008691906 -5e-4 -0.005943894 0.008583962 -5e-4 -0.004992663 0.009620666 -5e-4 -0.004999995 0.009499967 -5e-4 -0.004970967 0.009260952 -5e-4 -0.004935026 0.009145438 -5e-4 -0.004992663 0.009379208 -5e-4 -0.003431797 0.01032286 -5e-4 -0.003431797 0.01217705 -5e-4 -0.003534972 0.0121147 -5e-4 -0.004748284 0.01233667 -5e-4 -0.004748284 0.01016324 -5e-4 -0.00466299 0.0102486 -5e-4 -0.004885375 0.009964764 -5e-4 -0.004464447 0.01038557 -5e-4 -0.004354298 0.0104351 -5e-4 -0.004464447 0.01211434 -5e-4 -0.004567921 0.01217699 -5e-4 -0.004567921 0.01032298 -5e-4 -0.00399971 0.01199996 -5e-4 -0.004120349 0.01200729 -5e-4 -0.00399971 0.01049995 -5e-4 -0.004239201 0.01202905 -5e-4 -0.004354298 0.01206487 -5e-4 -0.004239201 0.01047086 -5e-4 -0.003534972 0.01038527 -5e-4 -0.003879189 0.01200729 -5e-4 -0.003760635 0.01047086 -5e-4 -0.003879189 0.01049268 -5e-4 -0.003336787 0.01024848 -5e-4 -0.003336787 0.01225149 -5e-4 -0.003114461 0.01253539 -5e-4 -0.003176867 0.01243215 -5e-4 -0.003028988 0.01276099 -5e-4 -0.00306493 0.01264548 -5e-4 -0.003007292 0.009620666 -5e-4 -0.003114461 0.01603537 -5e-4 -0.003114521 0.01346474 -5e-4 -0.003007292 0.01287925 -5e-4 -0.002999961 0.01299995 -5e-4 -0.004120349 0.01049268 -5e-4 -0.00466299 0.01225137 -5e-4 -0.00482285 0.0124318 -5e-4 -0.00482285 0.01006817 -5e-4 -0.004885375 0.01253515 -5e-4 -0.004934906 0.01264518 -5e-4 -0.004970848 0.0127604 -5e-4 -0.004970967 0.01323896 -5e-4 -0.004992663 0.01312065 -5e-4 -0.004568159 0.01382285 -5e-4 -0.004567921 0.01567697 -5e-4 -0.004885435 0.01346457 -5e-4 -0.004935026 0.01335448 -5e-4 -0.004823088 0.01356774 -5e-4 -0.00423932 0.01397085 -5e-4 -0.004120767 0.01399266 -5e-4 -0.004239201 0.01552909 -5e-4 -0.004464924 0.01388525 -5e-4 -0.004354774 0.01393485 -5e-4 -0.004464447 0.01561439 -5e-4 -0.003760635 0.01552909 -5e-4 -0.003879189 0.01550728 -5e-4 -0.003760695 0.01397085 -5e-4 -0.00399971 0.01549994 -5e-4 -0.004120349 0.01550728 -5e-4 -0.004000246 0.01399999 -5e-4 -0.003431797 0.01567709 -5e-4 -0.003534972 0.01561468 -5e-4 -0.003431975 0.01382297 -5e-4 -0.003535509 0.01388555 -5e-4 -0.003645181 0.01556509 -5e-4 -0.003336966 0.01374858 -5e-4 -0.003336787 0.01575148 -5e-4 -0.003251314 0.01583707 -5e-4 -0.003251671 0.01366329 -5e-4 -0.003177106 0.01356816 -5e-4 -0.003176867 0.0159322 -5e-4 -0.003007292 0.01637929 -5e-4 -0.002154469 0.01727068 -5e-4 -0.002999961 0.01649999 -5e-4 -0.003028988 0.01626098 -5e-4 -0.00306493 0.01614546 -5e-4 -0.003065049 0.01335477 -5e-4 -0.003007292 0.01312065 -5e-4 -0.003029108 0.01323956 -5e-4 -0.003177106 0.01706814 -5e-4 -0.002313196 0.01757454 -5e-4 -0.002411127 0.01771467 -5e-4 -0.003645658 0.01393508 -5e-4 -0.003879606 0.01399266 -5e-4 -0.004354298 0.01556485 -5e-4 -0.002227604 0.01742655 -5e-4 -0.003114521 0.01696479 -5e-4 -0.003029108 0.01673954 -5e-4 -0.003065049 0.01685476 -5e-4 -0.003007292 0.01662069 -5e-4 -0.004992663 0.009620666 5e-4 -0.004999995 0.009499967 -5e-4 -0.004999995 0.009499967 5e-4 -0.004885435 0.009964585 5e-4 -0.004934906 0.009854733 -5e-4 -0.004935026 0.009854435 5e-4 -0.004970967 0.009739041 5e-4 -0.004970848 0.009739577 -5e-4 -0.004992663 0.009620666 -5e-4 -0.004748284 0.01016324 -5e-4 -0.004748642 0.01016288 5e-4 -0.004663169 0.01024848 5e-4 -0.004885375 0.009964764 -5e-4 -0.004823088 0.01006776 5e-4 -0.00482285 0.01006817 -5e-4 -0.004464924 0.01038527 5e-4 -0.004354774 0.01043486 5e-4 -0.004464447 0.01038557 -5e-4 -0.004568159 0.01032286 5e-4 -0.004567921 0.01032298 -5e-4 -0.00466299 0.0102486 -5e-4 -0.004000246 0.01049995 5e-4 -0.004120349 0.01049268 -5e-4 -0.004120767 0.01049268 5e-4 -0.004239201 0.01047086 -5e-4 -0.004354298 0.0104351 -5e-4 -0.00423932 0.01047086 5e-4 -0.003760635 0.01047086 -5e-4 -0.003760695 0.01047086 5e-4 -0.003645658 0.0104351 5e-4 -0.00399971 0.01049995 -5e-4 -0.003879606 0.01049268 5e-4 -0.003879189 0.01049268 -5e-4 -0.003431975 0.01032298 5e-4 -0.003336966 0.0102486 5e-4 -0.003431797 0.01032286 -5e-4 -0.003535509 0.01038557 5e-4 -0.003534972 0.01038527 -5e-4 -0.003645181 0.01043486 -5e-4 -0.003114521 0.009964764 5e-4 -0.003176867 0.01006776 -5e-4 -0.003177106 0.01006817 5e-4 -0.003251314 0.01016288 -5e-4 -0.003336787 0.01024848 -5e-4 -0.003251671 0.01016324 5e-4 -0.003028988 0.009739041 -5e-4 -0.003029108 0.009739577 5e-4 -0.003007292 0.009620666 5e-4 -0.003114461 0.009964585 -5e-4 -0.003065049 0.009854733 5e-4 -0.00306493 0.009854435 -5e-4 -0.003007292 0.009379208 5e-4 -0.003028988 0.009260952 5e-4 -0.003007292 0.009379208 -5e-4 -0.002999961 0.009499967 5e-4 -0.002999961 0.009499967 -5e-4 -0.003007292 0.009620666 -5e-4 -0.003176808 0.008932173 5e-4 -0.003114581 0.00903511 -5e-4 -0.003114402 0.009035527 5e-4 -0.00306499 0.009145259 -5e-4 -0.003029167 0.009260356 -5e-4 -0.00306493 0.009145438 5e-4 -0.003336966 0.008751392 -5e-4 -0.003336727 0.00875163 5e-4 -0.003431618 0.008677184 5e-4 -0.003177225 0.008931636 -5e-4 -0.003251373 0.008836925 5e-4 -0.003251612 0.008836686 -5e-4 -0.003645241 0.008565008 5e-4 -0.003760337 0.008529126 5e-4 -0.00364542 0.008564949 -5e-4 -0.003535091 0.008614599 5e-4 -0.003535509 0.00861442 -5e-4 -0.003432154 0.008676826 -5e-4 -0.003879725 0.008507251 -5e-4 -0.003760933 0.008528947 -5e-4 -0.003879189 0.008507311 5e-4 -0.004120171 0.008507251 5e-4 -0.004120767 0.008507311 -5e-4 -0.003999948 0.008499979 -5e-4 -0.003999948 0.008499979 5e-4 -0.004239022 0.008528947 5e-4 -0.004239618 0.008529126 -5e-4 -0.004354655 0.008565008 -5e-4 -0.004354536 0.008564949 5e-4 -0.004464447 0.00861442 5e-4 -0.004464864 0.008614599 -5e-4 -0.004567742 0.008676826 5e-4 -0.004568278 0.008677184 -5e-4 -0.004663228 0.00875163 -5e-4 -0.00466299 0.008751392 5e-4 -0.004748344 0.008836686 5e-4 -0.004748582 0.008836925 -5e-4 -0.004822731 0.008931636 5e-4 -0.004823148 0.008932173 -5e-4 -0.004885554 0.009035527 -5e-4 -0.004885315 0.00903511 5e-4 -0.004934906 0.009145259 5e-4 -0.004935026 0.009145438 -5e-4 -0.004970788 0.009260356 5e-4 -0.004970967 0.009260952 -5e-4 -0.004992663 0.009379208 -5e-4 -0.004992663 0.009379208 5e-4 + + + + + + + + + + -0.9761871 -0.2169305 0 0.1520573 -0.9883717 0 0.1520573 -0.9883717 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 1.16884e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.84901 -0.5283767 0 -0.9257904 -0.3780374 0 -0.9543975 -0.2985392 0 -0.6257329 -0.7800375 0 -0.4855885 -0.8741875 0 -0.7480252 -0.6636703 0 -0.3316226 -0.9434123 0 -0.1681886 -0.9857548 0 -0.08438402 -0.9964334 0 0.9751317 0.2216264 0 0.9666868 0.2559622 0 0.9823791 0.1868989 0 0.9883732 0.152048 0 0.9909014 0.1345902 0 0.9570001 0.2900879 0 0.9461448 0.3237438 0 0.9403447 0.3402234 0 0 -1 0 0 -1 0 1 5.1521e-4 0 1 0 1.11345e-4 0.9998442 -0.01765561 0 1 0 -1.11345e-4 0.9999999 5.09219e-4 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 0.9889115 0.1485061 0 0.9876874 0.1564405 0 0.9969195 0.07843267 0 0.8090303 0.587767 0 0.8910139 0.4539761 0 0.8306108 0.5568535 0 0.9510608 0.309004 0 0.9560143 0.2933201 0 0.9023097 0.4310883 -3.05192e-5 0.5316439 0.846968 3.05194e-5 0.4539761 0.8910139 3.05193e-5 0.5878015 0.8090053 0 0.7443419 0.6677988 0 0.6437109 0.7652688 3.05195e-5 0.7071068 0.7071068 0 0.2837984 0.958884 3.05192e-5 0.1564108 0.9876922 3.05189e-5 0.309004 0.9510608 0 0.4113112 0.911495 0 0.07843267 0.9969195 0 0.152658 0.9882791 0 0.06790441 0.9976919 0 0.997057 0.07666379 0.6163083 0.787505 0 0.8378868 0.5458441 0 0.8927485 0.4505554 0 0.9161881 0.4007484 0 0.6990348 0.7150877 0 0.6586904 0.7524141 0 0.7731217 0.6342577 0 0.9368384 0.3497627 0 0.9368384 0.3497627 0 -0.9963108 0.08581835 0 -0.9990646 0.04324513 0 -0.9990633 0.04327559 0 -0.9416155 0.3366902 0 -0.9670007 0.2547742 0 -0.9852818 0.170938 0 -0.8702849 0.492549 0 -0.8249403 0.5652199 0 -0.9092627 0.4162228 0 -0.7160978 0.698 0 -0.6537923 0.7566741 0 -0.7733696 0.6339555 0 -0.4396655 0.8981617 0 -0.514949 0.8572209 0 -0.5864574 0.8099802 0 -0.2795827 0.9601216 0 -0.1964507 0.9805138 0 -0.3607107 0.9326778 0 -0.02609395 0.9996595 0 0.05963438 0.9982203 0 -0.1115469 0.9937592 0 0.3119671 0.9500929 0 0.2294085 0.9733303 0 0.1450863 0.9894191 0 0.4697279 0.8828114 0 0.5435512 0.8393761 0 0.3921763 0.9198901 0 0.6133827 0.7897859 0 0.6788997 0.734231 0 0.7393571 0.6733136 0 0.7943544 0.6074547 0 0.8434202 0.5372546 0 0.8862756 0.4631583 0 0.9052313 0.4249194 0 -0.7819901 -0.623291 0 -0.7457401 -0.6662372 0 -0.9439169 -0.3301832 0 -0.9010111 -0.4337964 0 -0.8468511 -0.5318303 0 -0.7819633 -0.6233245 0 -0.9937043 -0.1120359 0 -0.9749509 -0.2224204 0 -0.9937075 -0.1120057 0 -0.9984222 -0.05615454 0 -0.9984204 -0.05618494 0 -0.707107 -0.7071066 0 -0.707107 -0.7071066 0 -0.9748736 -0.2227593 0 -0.9936906 -0.1121564 0 -0.9009222 -0.4339808 0 -0.8466618 -0.5321316 0 -0.9438531 -0.3303654 0 -0.7818831 -0.6234251 0 -0.7457113 -0.6662693 0 -1 0 0 -1 -5.41561e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -5.41562e-7 0 3.05189e-5 0.309004 -0.9510608 -3.05189e-5 0.2853817 -0.958414 -3.05192e-5 0.4110625 -0.9116073 0 0.07843267 -0.9969195 0 0.1558607 -0.987779 0 0.1564108 -0.9876922 0 0.6420677 -0.7666479 0 0.7437205 -0.6684908 3.05195e-5 0.7071068 -0.7071068 3.05193e-5 0.5878015 -0.8090053 3.05194e-5 0.4539761 -0.8910139 -3.05191e-5 0.5295984 -0.8482486 0 0.9510608 -0.309004 0 0.9026917 -0.4302877 0 0.9560058 -0.293348 0 0.8910139 -0.4539761 0 0.8090303 -0.587767 0 0.8311618 -0.5560306 0 0.9888936 -0.1486254 0 0.9876874 -0.1564405 0 0.997043 -0.07684582 0 0.9969195 -0.07843267 0 0.06793481 -0.9976898 0.8655719 0.5007848 -7.4213e-5 0.8723533 0.4888761 2.26396e-6 0.8594916 0.5111501 0 0.8748543 0.4843864 -1.44521e-5 0.8752146 0.4837348 1.61431e-6 0.8654432 0.5010073 4.33636e-7 0.8712601 0.4908216 -1.04787e-5 0.8652339 0.5013685 -4.96214e-6 0.8653305 0.5012019 -2.02175e-6 0.8634088 0.5045052 0 0.8633202 0.5046567 -5.01358e-6 0.8177208 0.5756151 0 0.7944731 0.6072995 0 0.8572209 0.514949 0 0.8399876 0.5426058 0 0.7456675 0.6663184 0 0.7204078 0.6935508 0 0.7704181 0.637539 0 0.7204225 0.6935355 0 0.707534 0.7066794 0 0.8571642 0.5150432 0 0.8679411 0.4966673 -1.96608e-6 0.8672958 0.4977932 1.70372e-5 0.8667323 0.4987738 -7.43036e-5 0.8715066 0.4903839 4.78822e-7 0.8657456 0.5004844 1.708e-5 0.8722475 0.4890647 -1.04648e-5 0.8754811 0.4832525 1.56407e-6 0.8721632 0.4892151 -1.46072e-5 0.8752697 0.4836352 2.24776e-6 0.8720739 0.4893745 1.87202e-6 0.8602439 0.5098827 1.9035e-6 0.9926961 -0.1206421 0 1 0 0 0.8854585 -0.4647185 0 0.9350855 -0.3544224 0 0.9350754 -0.354449 0 0.970991 -0.239116 0 0.7488707 -0.6627162 0 0.6633309 -0.7483264 0 0.8231229 -0.5678635 0 0.4647424 -0.885446 0 0.3547297 -0.9349689 0 0.567989 -0.8230362 0 3.05194e-5 -1 0 0.1208563 -0.99267 0 0.2396693 -0.9708546 0 0.3547195 -0.9349728 0 -0.239116 -0.970991 0 -0.3541151 -0.9352019 0 3.05185e-5 -1 0 -0.120582 -0.9927035 0 -0.5680589 -0.822988 0 -0.6629913 -0.7486271 0 -0.4645976 -0.8855219 0 -0.4646216 -0.8855094 0 -0.8853633 -0.4648997 0 -0.822762 -0.5683861 0 -0.748412 -0.6632341 0 -0.9708777 -0.2395759 0 -0.9926815 -0.1207624 0 -0.9708706 -0.2396047 0 -0.934993 -0.3546662 0 -0.9926961 0.1206421 0 -0.970991 0.239116 0 -0.8231229 0.5678635 0 -0.8854585 0.4647185 0 -0.9350754 0.354449 0 -0.9350855 0.3544224 0 -0.6633309 0.7483264 0 -0.567989 0.8230362 0 -0.7488574 0.6627313 0 -0.7488707 0.6627162 0 -0.3547297 0.9349689 0 -0.2396693 0.9708546 0 -0.4647424 0.885446 0 -0.1208563 0.99267 0 0.120582 0.9927035 0 -3.05185e-5 1 0 0.239116 0.970991 0 0.3541151 0.9352019 0 0.4645976 0.8855219 0 0.5680589 0.822988 0 0.6629913 0.7486271 0 0.748412 0.6632341 0 0.822762 0.5683861 0 0.8853633 0.4648997 0 0.934993 0.3546662 0 0.9708706 0.2396047 0 0.9926815 0.1207624 0 0.4647789 -0.8854268 0 -0.7484272 -0.6632171 0 -3.05194e-5 1 0 0.6630064 0.7486138 0 0.9708777 0.2395759 0 5.96579e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.67744e-7 0 1 0 0 1 0 0 1 -4.73643e-7 0 1 4.71371e-7 0 1 -6.61359e-7 0 1 4.69121e-7 0 1 8.36161e-7 0 1 -1.65382e-7 0 1 0 0 1 0 0 1 -9.41783e-7 0 1 3.31977e-7 0 1 4.71364e-7 0 1 2.85367e-7 0 1 0 0 1 0 0 1 -1.33073e-6 0 1 0 0 1 0 0 1 0 0 1 -2.54763e-6 0 1 0 0 1 -1.38494e-7 0 1 0 0 1 -6.04846e-7 0 1 -6.33985e-7 0 1 0 0 1 -3.20942e-7 0 1 4.12294e-7 0 1 -1.49398e-7 0 1 2.03342e-7 0 1 0 0 1 -7.5338e-7 0 1 0 0 1 1.16232e-6 0 1 4.85611e-7 0 1 6.45171e-7 0 1 -5.72002e-7 0 1 1.29102e-7 0 1 2.10126e-7 0 1 2.98435e-7 0 1 0 0 1 -2.63015e-7 0 1 -3.98877e-7 0 1 0 0 1 -6.96969e-7 0 1 -2.49682e-7 0 1 -1.38494e-7 0 1 0 0 1 -1.21133e-7 0 1 1.33073e-6 0 1 -2.38227e-7 0 1 0 0 1 -2.97181e-7 0 1 0 0 1 6.35273e-7 0 1 -2.22759e-7 0 1 4.58945e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.91421e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 4.20656e-7 0 1 -4.4755e-7 0 1 1.65372e-7 0 1 0 0 1 0 0 1 1.65176e-7 0 1 -2.37152e-7 0 1 0 0 1 1.84414e-7 0 1 0 0 1 0 0 1 2.74561e-7 0 1 4.20636e-7 0 1 0 0 1 0 0 1 3.31841e-7 0 1 -3.80845e-7 0 1 -1.22725e-7 0 1 0 0 1 -4.38375e-7 0 1 5.73681e-7 0 1 -2.18309e-7 0 1 0 0 1 -2.20393e-7 0 1 0 0 1 0 0 1 0 0 1 2.42266e-7 0 1 -1.33073e-6 0 1 3.57341e-7 0 1 3.36805e-7 0 1 1.38494e-7 0 1 2.0715e-7 0 1 0 0 1 6.04128e-7 0 1 9.56463e-7 0 1 -6.35274e-7 0 1 -2.67707e-7 0 1 0 0 1 3.04599e-7 0 1 0 0 1 0 0 -1 0 0 -1 -3.0194e-6 0 -1 -9.41783e-7 0 -1 0 0 -1 0 0 -1 -4.73643e-7 0 -1 4.69121e-7 0 -1 4.71371e-7 0 -1 -1.65382e-7 0 -1 -5.86439e-7 0 -1 0 0 -1 9.38847e-7 0 -1 2.07485e-7 0 -1 0 0 -1 1.23405e-7 0 -1 2.34991e-7 0 -1 2.35681e-7 0 -1 0 0 -1 2.85367e-7 0 -1 6.04e-7 0 -1 -1.33073e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.60528e-7 0 -1 0 0 -1 6.2238e-7 0 -1 -5.30895e-7 0 -1 -3.69968e-7 0 -1 -2.2098e-7 0 -1 2.12091e-7 0 -1 -5.007e-7 0 -1 -4.19401e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -3.71217e-7 0 -1 3.44939e-7 0 -1 3.33323e-7 0 -1 6.33996e-7 0 -1 -3.16501e-7 0 -1 1.22342e-6 0 -1 -2.67268e-7 0 -1 0 0 -1 3.04593e-7 0 -1 0 0 -1 0 0 -1 -1.35049e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.84129e-7 0 -1 -1.29054e-6 0 -1 -9.27468e-7 0 -1 -1.41351e-6 0 -1 1.5372e-6 0 -1 -7.5338e-7 0 -1 0 0 -1 1.16232e-6 0 -1 4.85611e-7 0 -1 6.45171e-7 0 -1 -5.72002e-7 0 -1 1.29102e-7 0 -1 2.10126e-7 0 -1 2.98435e-7 0 -1 0 0 -1 -6.04846e-7 0 -1 -2.63015e-7 0 -1 -3.98877e-7 0 -1 -6.96969e-7 0 -1 -2.49682e-7 0 -1 -1.38494e-7 0 -1 0 0 -1 -1.21133e-7 0 -1 1.33073e-6 0 -1 -2.38227e-7 0 -1 0 0 -1 -2.97181e-7 0 -1 0 0 -1 6.35273e-7 0 -1 -2.22759e-7 0 -1 4.58945e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.91421e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 4.20656e-7 0 -1 -4.4755e-7 0 -1 1.65372e-7 0 -1 0 0 -1 0 0 -1 1.65176e-7 0 -1 -2.37152e-7 0 -1 0 0 -1 1.84414e-7 0 -1 0.9926998 -0.1206121 0 0.8854776 -0.464682 0 0.9349829 -0.3546929 0 0.9709751 -0.2391806 0 0.9926815 -0.1207624 0 0.9708706 -0.2396047 3.0519e-5 0.7484272 -0.6632171 3.05194e-5 0.7488574 -0.6627313 0 0.8853952 -0.4648393 0 0.8228004 -0.5683305 3.05193e-5 0.8230987 -0.5678985 0 0.4646216 -0.8855094 0 0.3547195 -0.9349728 -6.10375e-5 0.567989 -0.8230362 3.0519e-5 0.6629913 -0.7486271 6.10377e-5 0.5680239 -0.8230121 0 0.120582 -0.9927035 3.05194e-5 0.2391448 -0.9709839 3.05187e-5 0.2396335 -0.9708635 0 0.3541151 -0.9352019 0 -0.2396335 -0.9708635 0 -0.2391448 -0.9709839 -3.05187e-5 -3.05185e-5 -1 0 -0.1208563 -0.99267 0 -0.120582 -0.9927035 -3.05194e-5 -0.5680239 -0.8230121 -3.05192e-5 -0.567989 -0.8230362 -3.0519e-5 -0.6629913 -0.7486271 -6.10377e-5 -0.3547195 -0.9349728 6.10375e-5 -0.4647789 -0.8854268 0 -0.8853826 -0.4648633 0 -0.8228004 -0.5683305 -3.05193e-5 -0.8230987 -0.5678985 0 -0.7488574 -0.6627313 0 -0.7484272 -0.6632171 -3.05194e-5 -0.6633309 -0.7483264 0 -0.9709751 -0.2391806 0 -0.9708706 -0.2396047 -3.0519e-5 -0.8854776 -0.464682 0 -0.9350754 -0.354449 0 -0.9349829 -0.3546929 0 -0.9926998 0.1206121 0 -0.9926736 0.1208263 0 -0.9709751 0.2391806 0 -0.9926998 -0.1206121 0 -0.8231995 0.5677523 -3.05194e-5 -0.8855411 0.4645612 0 -0.8853508 0.4649236 0 -0.9349829 0.3546929 0 -0.9350513 0.3545125 0 -0.9708706 0.2396047 3.0519e-5 -0.6630064 0.7486138 0 -0.5683305 0.8228004 -3.05193e-5 -0.6632341 0.748412 0 -0.8227763 0.5683655 3.05195e-5 -0.7484272 0.6632171 0 -0.7486271 0.6629913 0 -0.3547195 0.9349728 0 -0.3545125 0.9350513 0 -0.2396047 0.9708706 -3.0519e-5 -0.4649236 0.8853508 0 -0.5677729 0.8231853 3.05189e-5 -0.4645612 0.8855411 0 -0.1203377 0.9927331 0 -0.1207962 0.9926773 0 -0.238965 0.9710283 3.05192e-5 0.1203377 0.9927331 0 6.10389e-5 1 0 0.1208263 0.9926736 0 -6.1037e-5 1 0 0.2396047 0.9708706 3.0519e-5 0.238965 0.9710283 -3.05192e-5 0.3547195 0.9349728 0 0.3544859 0.9350615 0 0.4645612 0.8855411 0 0.4649236 0.8853508 0 0.5683305 0.8228004 3.05193e-5 0.5677729 0.8231853 -3.05189e-5 0.6632171 0.7484272 0 0.7484272 0.6632171 0 0.7486271 0.6629913 0 0.8231995 0.5677523 3.05194e-5 0.8227763 0.5683655 -3.05195e-5 0.8855411 0.4645612 0 0.8853508 0.4649236 0 0.9349829 0.3546929 0 0.9350513 0.3545125 0 0.9709839 0.2391448 0 0.9708706 0.2396047 -3.0519e-5 0.9926998 0.1206121 0 0.99267 0.1208563 0 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + -0.997824 -0.06593175 -9.558e-11 -1.82539e-7 2.78033e-9 -4.35277e-8 1 -1.80898e-6 -0.06593175 0.997824 4.36163e-8 3.83984e-5 0 0 0 1 + + + + + + + + + + -0.9999635 0.008557129 6.46045e-10 0.01617037 0 7.54979e-8 -1 -0.003076038 -0.008557129 -0.9999635 -7.54951e-8 -0.001752572 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_ruddervator.dae b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_ruddervator.dae new file mode 100644 index 00000000..9972d0ec --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_ruddervator.dae @@ -0,0 +1,151 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-05T14:01:11 + 2023-07-05T14:01:11 + + Z_UP + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.498039 0.498039 0.498039 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + 0.005037128 0.001511454 -0.005922317 0.005037128 -4.8853e-4 -0.005922317 -0.008881807 -4.8853e-4 -0.007423758 -0.008881807 0.001511454 -0.007423758 0.005037128 -4.8853e-4 -0.005922317 0.004930138 -4.8853e-4 -0.004928171 -0.008988797 -4.8853e-4 -0.006429433 -0.008881807 -4.8853e-4 -0.007423758 -0.008988797 0.001511454 -0.006429433 -0.008988797 -4.8853e-4 -0.006429433 0.004930138 -4.8853e-4 -0.004928171 0.004930138 0.001511454 -0.004928171 0.004930138 0.001511454 -0.004928171 0.004447102 0.001511454 -4.54068e-4 -0.009471833 0.001511454 -0.001955449 -0.008988797 0.001511454 -0.006429433 -0.008881807 0.001511454 -0.007423758 -0.00839883 0.001511454 -0.01189774 0.005520105 0.001511454 -0.01039642 0.005037128 0.001511454 -0.005922317 0.004447102 0.001851499 -4.54068e-4 0.004447102 0.001511454 -4.54068e-4 0.004930138 0.001511454 -0.004928171 0.005037128 0.001511454 -0.005922317 0.004930138 -4.8853e-4 -0.004928171 0.005037128 -4.8853e-4 -0.005922317 0.005520105 0.001697421 -0.01039642 0.005520105 0.001511454 -0.01039642 -0.002479851 0.00235337 -0.001201272 -0.009471833 0.002824008 -0.001955449 -0.009471833 0.001511454 -0.001955449 0.004447102 0.001511454 -4.54068e-4 0.004447102 0.001851499 -4.54068e-4 -0.00839883 0.002699375 -0.01189774 -0.00839883 0.001511454 -0.01189774 -0.008881807 0.001511454 -0.007423758 -0.009471833 0.002824008 -0.001955449 -0.008881807 -4.8853e-4 -0.007423758 -0.008988797 -4.8853e-4 -0.006429433 -0.008988797 0.001511454 -0.006429433 -0.009471833 0.001511454 -0.001955449 0.005520105 0.001697421 -0.01039642 0.005520105 0.001511454 -0.01039642 -0.00839883 0.001511454 -0.01189774 -0.001407802 0.002213835 -0.01114362 -0.00839883 0.002699375 -0.01189774 0.02745312 6.49292e-4 0.08369892 0.02745312 -6.26833e-4 0.08369892 0.02108013 -0.001149237 0.0832709 -1.01849e-4 7.25114e-4 0.08184993 0.01470512 0.001652598 0.08284288 -1.01849e-4 -7.0256e-4 0.08184993 0.001945137 0.002489924 0.0819869 0.008327126 0.002092003 0.08241492 0.03382211 8.53641e-5 0.08412593 0.03382211 -6.29048e-5 0.08412593 0.01470512 -0.001630127 0.08284288 0.02108013 0.001171708 0.0832709 0.008326113 -0.002069473 0.08241492 0.001945137 -0.002467393 0.0819869 0.03382211 -6.29048e-5 0.08412593 0.01848214 1.27358e-4 -0.06508713 0.01848214 -1.04314e-4 -0.06508713 0.03382211 8.53641e-5 0.08412593 -0.001407802 0.002213835 -0.01114362 -0.002698838 0.001919984 -0.06737184 0.005520105 0.001697421 -0.01039642 0.02745312 6.49292e-4 0.08369892 0.02108013 0.001171708 0.0832709 0.007930099 0.001057624 -0.06622534 0.01848214 1.27358e-4 -0.06508713 0.03382211 8.53641e-5 0.08412593 0.01470512 0.001652598 0.08284288 -0.002479851 0.00235337 -0.001201272 0.004447102 0.001851499 -4.54068e-4 -0.00839883 0.002699375 -0.01189774 -0.01340484 0.002714514 -0.06852656 -0.009471833 0.002824008 -0.001955449 -0.02418684 0.003441095 -0.06968957 0.001945137 0.002489924 0.0819869 0.008327126 0.002092003 0.08241492 -0.02625793 0.001677334 -0.06991297 0.001945137 0.002489924 0.0819869 -1.01849e-4 7.25114e-4 0.08184993 -0.02418684 0.003441095 -0.06968957 -0.02625793 -0.001654326 -0.06991297 -1.01849e-4 7.25114e-4 0.08184993 -1.01849e-4 -7.0256e-4 0.08184993 -0.02625793 0.001677334 -0.06991297 0.001945137 -0.002467393 0.0819869 -0.02625793 -0.001654326 -0.06991297 -1.01849e-4 -7.0256e-4 0.08184993 -0.02418684 -0.003418087 -0.06968957 0.007930099 -0.001034617 -0.06622534 -0.002699851 -0.001896977 -0.06737184 0.02108013 -0.001149237 0.0832709 -0.02418684 -0.003418087 -0.06968957 0.001945137 -0.002467393 0.0819869 0.008326113 -0.002069473 0.08241492 0.02745312 -6.26833e-4 0.08369892 0.03382211 -6.29048e-5 0.08412593 0.01848214 -1.04314e-4 -0.06508713 0.01470512 -0.001630127 0.08284288 -0.01340484 -0.002691507 -0.06852656 -0.02213382 -7.24372e-4 -0.06554996 -0.02200579 -8.25802e-4 -0.06557202 -0.0218628 -9.04381e-4 -0.06559675 -0.0218628 9.27267e-4 -0.06559675 -0.02200579 8.4866e-4 -0.06557202 -0.02049481 -1.53147e-4 -0.06583243 -0.02170884 -9.57966e-4 -0.06562322 -0.02224481 -6.02857e-4 -0.06553095 -0.02154785 -9.85098e-4 -0.06565093 -0.0223338 -4.64573e-4 -0.06551557 -0.02239882 -3.13293e-4 -0.06550437 -0.02138483 -9.8504e-4 -0.06567907 -0.02243882 -1.53147e-4 -0.06549745 -0.02122485 -9.57799e-4 -0.06570667 -0.02245181 1.14934e-5 -0.06549507 -0.02107083 -9.0412e-4 -0.06573325 -0.02092784 -8.25474e-4 -0.06575787 -0.02243882 1.76088e-4 -0.06549745 -0.02059984 -4.64253e-4 -0.06581437 -0.02224481 6.25706e-4 -0.06553095 -0.02068883 -6.02496e-4 -0.06579893 -0.0223338 4.87441e-4 -0.06551557 -0.02239882 3.36193e-4 -0.06550425 -0.0207988 -7.24009e-4 -0.06578004 -0.02048182 1.14934e-5 -0.06583476 -0.02213382 7.47217e-4 -0.06554996 -0.02053481 -3.13052e-4 -0.06582552 -0.02053481 3.36193e-4 -0.06582552 -0.02059984 4.87441e-4 -0.06581437 -0.02138584 0.001008033 -0.06567895 -0.02049481 1.76088e-4 -0.06583243 -0.02154785 0.001008033 -0.06565093 -0.02170884 9.80893e-4 -0.06562322 -0.02107083 9.27267e-4 -0.06573313 -0.02079981 7.47217e-4 -0.06577992 -0.02092784 8.4866e-4 -0.06575787 -0.02068883 6.25706e-4 -0.06579893 -0.02122485 9.80893e-4 -0.06570667 0.007930099 -0.001034617 -0.06622534 0.007930099 0.001057624 -0.06622534 -0.002698838 0.001919984 -0.06737184 -0.02625793 0.001677334 -0.06991297 -0.02220779 0.001008033 -0.06947606 -0.02203685 0.001008033 -0.06945753 0.01848214 -1.04314e-4 -0.06508713 0.01848214 1.27358e-4 -0.06508713 -0.002699851 -0.001896977 -0.06737184 -0.02155685 8.4866e-4 -0.06940585 -0.02142184 7.47217e-4 -0.06939125 -0.01340484 0.002714514 -0.06852656 -0.02418684 0.003441095 -0.06968957 -0.02625793 -0.001654326 -0.06991297 -0.0231558 1.14934e-5 -0.06957834 -0.02108782 1.14934e-5 -0.06935524 -0.02110183 1.76088e-4 -0.06935685 -0.01340484 -0.002691507 -0.06852656 -0.02418684 -0.003418087 -0.06968957 -0.02309983 3.36193e-4 -0.06957226 -0.0231418 1.76088e-4 -0.06957674 -0.02170681 9.27267e-4 -0.06942206 -0.02293783 6.25706e-4 -0.06955486 -0.02303183 4.87441e-4 -0.06956487 -0.02186781 9.80893e-4 -0.06943947 -0.02268785 8.4866e-4 -0.06952774 -0.02282279 7.47217e-4 -0.06954234 -0.02237582 9.80893e-4 -0.06949412 -0.02253782 9.27267e-4 -0.06951153 -0.02130579 6.25706e-4 -0.06937873 -0.02121281 4.87441e-4 -0.06936877 -0.02114385 3.36193e-4 -0.06936132 -0.02203685 -9.85091e-4 -0.06945753 -0.02110183 -1.53101e-4 -0.06935685 -0.02114385 -3.13206e-4 -0.06936132 -0.02121281 -4.64454e-4 -0.06936877 -0.02130579 -6.02719e-4 -0.06937873 -0.02142184 -7.24231e-4 -0.06939125 -0.02155685 -8.25673e-4 -0.06940585 -0.02170681 -9.0428e-4 -0.06942206 -0.02186781 -9.57907e-4 -0.06943947 -0.02237582 -9.57907e-4 -0.06949412 -0.02220779 -9.85091e-4 -0.06947606 -0.02268785 -8.25673e-4 -0.06952774 -0.02253782 -9.0428e-4 -0.06951153 -0.02293783 -6.02719e-4 -0.06955486 -0.02282279 -7.24231e-4 -0.06954234 -0.02309983 -3.13206e-4 -0.06957226 -0.02303183 -4.64454e-4 -0.06956487 -0.0231418 -1.53101e-4 -0.06957674 -0.02243882 1.76088e-4 -0.06549745 -0.0231558 1.14934e-5 -0.06957834 -0.02245181 1.14934e-5 -0.06549507 -0.02224481 6.25706e-4 -0.06553095 -0.02303183 4.87441e-4 -0.06956487 -0.0223338 4.87441e-4 -0.06551557 -0.02239882 3.36193e-4 -0.06550425 -0.02309983 3.36193e-4 -0.06957226 -0.0231418 1.76088e-4 -0.06957674 -0.02268785 8.4866e-4 -0.06952774 -0.02200579 8.4866e-4 -0.06557202 -0.0218628 9.27267e-4 -0.06559675 -0.02293783 6.25706e-4 -0.06955486 -0.02213382 7.47217e-4 -0.06554996 -0.02282279 7.47217e-4 -0.06954234 -0.02154785 0.001008033 -0.06565093 -0.02138584 0.001008033 -0.06567895 -0.02220779 0.001008033 -0.06947606 -0.02170884 9.80893e-4 -0.06562322 -0.02237582 9.80893e-4 -0.06949412 -0.02253782 9.27267e-4 -0.06951153 -0.02092784 8.4866e-4 -0.06575787 -0.02170681 9.27267e-4 -0.06942206 -0.02107083 9.27267e-4 -0.06573313 -0.02186781 9.80893e-4 -0.06943947 -0.02203685 0.001008033 -0.06945753 -0.02122485 9.80893e-4 -0.06570667 -0.02130579 6.25706e-4 -0.06937873 -0.02068883 6.25706e-4 -0.06579893 -0.02059984 4.87441e-4 -0.06581437 -0.02155685 8.4866e-4 -0.06940585 -0.02079981 7.47217e-4 -0.06577992 -0.02142184 7.47217e-4 -0.06939125 -0.02049481 1.76088e-4 -0.06583243 -0.02048182 1.14934e-5 -0.06583476 -0.02110183 1.76088e-4 -0.06935685 -0.02053481 3.36193e-4 -0.06582552 -0.02114385 3.36193e-4 -0.06936132 -0.02121281 4.87441e-4 -0.06936877 -0.02059984 -4.64253e-4 -0.06581437 -0.02114385 -3.13206e-4 -0.06936132 -0.02053481 -3.13052e-4 -0.06582552 -0.02110183 -1.53101e-4 -0.06935685 -0.02108782 1.14934e-5 -0.06935524 -0.02049481 -1.53147e-4 -0.06583243 -0.02142184 -7.24231e-4 -0.06939125 -0.0207988 -7.24009e-4 -0.06578004 -0.02092784 -8.25474e-4 -0.06575787 -0.02121281 -4.64454e-4 -0.06936877 -0.02068883 -6.02496e-4 -0.06579893 -0.02130579 -6.02719e-4 -0.06937873 -0.02122485 -9.57799e-4 -0.06570667 -0.02138483 -9.8504e-4 -0.06567907 -0.02186781 -9.57907e-4 -0.06943947 -0.02107083 -9.0412e-4 -0.06573325 -0.02170681 -9.0428e-4 -0.06942206 -0.02155685 -8.25673e-4 -0.06940585 -0.02154785 -9.85098e-4 -0.06565093 -0.02170884 -9.57966e-4 -0.06562322 -0.02220779 -9.85091e-4 -0.06947606 -0.02203685 -9.85091e-4 -0.06945753 -0.02237582 -9.57907e-4 -0.06949412 -0.0218628 -9.04381e-4 -0.06559675 -0.02200579 -8.25802e-4 -0.06557202 -0.02253782 -9.0428e-4 -0.06951153 -0.02213382 -7.24372e-4 -0.06554996 -0.02268785 -8.25673e-4 -0.06952774 -0.02282279 -7.24231e-4 -0.06954234 -0.02224481 -6.02857e-4 -0.06553095 -0.0223338 -4.64573e-4 -0.06551557 -0.02293783 -6.02719e-4 -0.06955486 -0.02239882 -3.13293e-4 -0.06550437 -0.02303183 -4.64454e-4 -0.06956487 -0.02309983 -3.13206e-4 -0.06957226 -0.02243882 -1.53147e-4 -0.06549745 -0.0231418 -1.53101e-4 -0.06957674 + + + + + + + + + + -0.107245 0 0.9942327 -0.1072452 0 0.9942327 0 1 0 0 1 0 0.1072377 0 -0.9942334 0.1072377 0 -0.9942335 0 1 0 0 1 0 -0.9942232 0 -0.1073324 -0.9942494 -0.004461705 -0.1069961 -0.9942594 0 -0.106997 -0.9942257 5.94176e-4 -0.1073078 -0.9942594 0 -0.1069968 -0.9942232 0 -0.1073324 0.107244 0 -0.9942327 0.1072451 -8.95092e-6 -0.9942326 0.1072462 0 -0.9942325 0.9942231 0 0.1073331 0.9942266 -1.23992e-4 0.1073006 0.9942598 0 0.1069932 0.9942591 0.001173734 0.1069931 0.9942598 0 0.1069931 0.9942232 0 0.1073332 -0.1072377 0 0.9942335 -0.1072365 -9.14786e-5 0.9942336 -0.1072455 0 0.9942326 -0.06700944 0 0.9977524 -0.06691378 0 0.9977589 -0.06690371 1.44557e-4 0.9977595 -0.06693428 3.31869e-4 0.9977574 -0.06689435 0 0.9977601 -0.06698429 0 0.997754 -0.06689584 0 0.99776 -0.06698489 0 0.997754 -0.06700909 0 0.9977524 -0.06692916 -2.52302e-4 0.9977577 -0.06691181 0 0.9977589 -0.06691265 -1.5589e-4 0.9977589 0.9947571 0 -0.102267 0.07297188 0.9973129 -0.006500601 0.07696986 0.9970074 -0.007202565 0.07766991 0.9969523 -0.007324457 0.08591139 0.996267 -0.008453786 0.08468925 0.9963729 -0.008301019 0.07941055 0.9968136 -0.007538199 0.08877921 0.9960123 -0.008819937 0.08874899 0.996015 -0.008819937 0.07297194 0.9973121 -0.006605505 0.06778186 0.9976848 -0.005554378 0.07068175 0.9974797 -0.006195306 0.06641733 0.9977777 -0.005338549 0.06762993 0.9976944 -0.005676507 0.06253343 0.9980327 -0.00451678 0.06451678 0.9979046 -0.004913508 0.06634789 0.9977827 -0.005279719 0.06776523 0.9976854 -0.005640208 0.0691204 0.9975914 -0.005815625 0.07678508 0.997022 -0.007159233 0.07782751 0.9969399 -0.007332921 0.0752896 0.9971377 -0.006927728 0.07287859 0.9973201 -0.006439387 -0.6529728 0.7482532 0.1172338 -0.6511937 0.7498549 0.116895 -0.9854709 0 0.1698443 -0.9854709 0 0.1698443 -0.6529697 -0.7482563 0.1172312 -0.6511918 -0.749857 0.1168925 0.08468919 -0.9963726 -0.008331537 0.07941055 -0.9968136 -0.007538199 0.07763957 -0.9969547 -0.007324457 0.06766033 -0.9976927 -0.005615472 0.06634789 -0.9977827 -0.005279719 0.06253343 -0.9980327 -0.00451678 0.08591139 -0.996267 -0.008453786 0.08877921 -0.996012 -0.008850455 0.08874899 -0.996015 -0.008819937 0.07287853 -0.9973196 -0.006500422 0.07065141 -0.9974822 -0.006134271 -0.1705213 -5.291e-4 -0.9853539 -0.1699811 -3.48883e-4 -0.9854473 -0.1693047 4.83333e-4 -0.9855637 -0.172683 -0.003562927 -0.9849711 -0.1695154 4.08869e-4 -0.9855275 -0.1690884 9.27667e-4 -0.9856005 -0.1697507 1.58035e-5 -0.9854871 -0.1697024 4.96051e-5 -0.9854955 -0.169937 -1.89192e-4 -0.985455 -0.1691581 0.001003265 -0.9855884 -0.1699304 -1.8278e-4 -0.9854561 -0.1696468 2.39421e-4 -0.985505 -0.1701011 -2.29123e-4 -0.9854266 -0.1699579 -3.3428e-4 -0.9854514 -0.170189 -4.98691e-4 -0.9854114 -0.1700549 -3.11596e-4 -0.9854346 -0.1699613 -1.92536e-4 -0.9854508 -0.1697242 2.63481e-5 -0.9854916 -0.1695768 3.16323e-4 -0.9855169 -0.1699974 -3.1509e-4 -0.9854444 -0.1693511 3.53966e-4 -0.9855558 -0.1690829 9.17554e-4 -0.9856015 -0.1727386 -0.003477573 -0.9849616 -0.1702697 -7.03968e-4 -0.9853972 -0.1695874 4.01866e-4 -0.9855151 -0.1695756 3.40818e-4 -0.9855172 -0.1698386 9.27356e-5 -0.9854719 -0.169931 -6.68168e-5 -0.985456 -0.16964 2.8546e-4 -0.9855061 -0.1694803 6.34098e-4 -0.9855334 -0.1698356 1.50557e-5 -0.9854724 -0.1699451 -3.3978e-4 -0.9854536 -0.1697777 1.79979e-4 -0.9854825 -0.169609 2.84494e-4 -0.9855115 -0.1705571 -8.90845e-4 -0.9853475 -0.1695122 5.21302e-4 -0.9855279 0.1072407 0 -0.9942331 0.1076377 0.001882314 -0.9941884 0.107252 0 -0.9942319 0.1072433 0 -0.9942328 0.107236 -2.80473e-5 -0.9942337 0.1072512 -3.11026e-4 -0.9942319 0.1072434 -1.76251e-7 -0.9942329 0.1072382 0 -0.9942334 0.1072828 -5.49634e-4 -0.9942285 0.1072431 1.32189e-7 -0.9942329 0.1072362 2.13306e-5 -0.9942336 0.1072061 -1.73785e-4 -0.9942369 0.1075156 5.33096e-4 -0.9942033 0.1072986 -2.2786e-4 -0.9942269 0.107025 -8.29852e-4 -0.994256 0.107391 3.44041e-4 -0.9942169 0.1068449 0.002137064 -0.9942735 0.1073412 2.82316e-4 -0.9942223 0.1073867 6.19714e-4 -0.9942172 0.1070663 -9.52127e-4 -0.9942514 0.1073252 1.09418e-4 -0.994224 0.107185 -3.33696e-4 -0.994239 0.1072483 -9.27908e-5 -0.9942323 0.1072638 -3.50374e-4 -0.9942306 0.1072195 2.18807e-4 -0.9942353 0.1072308 6.90069e-5 -0.9942342 0.1072187 1.81348e-4 -0.9942355 0.107223 2.79474e-4 -0.994235 0.1072389 -2.80848e-5 -0.9942334 0.1072491 9.2791e-5 -0.9942322 0.1072292 -1.82556e-4 -0.9942343 0.1072936 5.49665e-4 -0.9942273 0.1072332 -2.21505e-4 -0.994234 0.1072186 -2.81984e-4 -0.9942355 0.1072574 3.04012e-4 -0.9942314 0.1072351 -7.50106e-5 -0.9942337 0.1072671 2.2786e-4 -0.9942302 0.1072446 1.16232e-5 -0.9942327 0.106811 -0.002137124 -0.9942771 0.1073271 3.48825e-4 -0.9942237 0.1072065 3.33192e-4 -0.9942368 0.1075761 -0.001882314 -0.9941951 0.1073272 -1.07184e-4 -0.9942238 0.1070752 9.51238e-4 -0.9942505 0.1074372 -6.20785e-4 -0.9942117 0.107327 -2.81604e-4 -0.9942238 0.1074036 -3.43346e-4 -0.9942155 0.1069547 8.28999e-4 -0.9942637 0.1075493 -5.31785e-4 -0.9941997 0.1071902 1.74565e-4 -0.9942385 0.9722178 -0.16343 -0.1675806 0.9854665 0 -0.1698701 0.7766595 -0.6155472 -0.1337974 0.8672144 -0.4749765 -0.1494544 0.8702328 -0.4692677 -0.1499422 0.9323844 -0.3238061 -0.1606518 0.9724629 -0.1619652 -0.1675807 0.9340431 -0.3188351 -0.1609588 0.5490159 -0.8304365 -0.09464102 0.3959816 -0.9157171 -0.06827056 0.5397973 -0.8366293 -0.09311479 0.782934 -0.6072973 -0.1349244 0.6763316 -0.7272983 -0.1166741 0.6668466 -0.7362781 -0.1149356 0.08115047 -0.9966039 -0.01397776 0.09595108 -0.9952486 -0.01654118 -0.08115047 -0.9966039 0.01397776 0.2416216 -0.9694773 -0.04162836 0.4079487 -0.9102931 -0.07031595 0.2551126 -0.9659121 -0.04394805 -0.539822 -0.8366203 0.09305274 -0.3959825 -0.915719 0.06824022 -0.3844758 -0.9207521 0.0662868 -0.2284637 -0.9727562 0.03936922 -0.2416503 -0.9694702 0.04162806 -0.06686705 -0.9976956 0.0115056 -0.7721976 -0.62128 0.1331248 -0.8672266 -0.474936 0.1495123 -0.7767098 -0.6154776 0.133826 -0.5288329 -0.8438193 0.09112966 -0.6587381 -0.7437661 0.1134724 -0.6668171 -0.7363097 0.1149053 -0.9722443 -0.1634293 0.1674273 -0.9716785 -0.1668804 0.1673076 -0.9855032 -3.05194e-5 0.1696575 -0.9323667 -0.323841 0.1606844 -0.8634477 -0.4819889 0.1488113 -0.930094 -0.3305501 0.1601937 -0.8671529 0.4750983 0.1494238 -0.932335 0.3239932 0.1605622 -0.9300991 0.330491 0.1602861 -0.9716686 0.1669092 0.1673365 -0.9722185 0.1636132 0.1673976 -0.985498 -3.05193e-5 0.1696872 -0.6587313 0.7437584 0.1135628 -0.5384823 0.8375102 0.09280914 -0.6671167 0.7360288 0.1149654 -0.8633941 0.4820846 0.1488126 -0.7722515 0.6212132 0.1331236 -0.7780315 0.6137455 0.1341023 -0.2424106 0.9692764 0.04171913 -0.2284929 0.9727506 0.03933846 -0.08197385 0.9965348 0.01409971 -0.3962318 0.9156088 0.06827157 -0.528811 0.843833 0.09113115 -0.3844514 0.9207667 0.06622684 0.08081454 0.9966316 -0.01394718 0.09592092 0.9952521 -0.01651072 0.2413777 0.9695394 -0.0415979 -0.06683665 0.9976976 0.01150566 0.2551411 0.9659047 -0.04394775 0.3958067 0.9157972 -0.06821095 0.5397664 0.8366593 -0.09302318 0.4079242 0.9103064 -0.07028651 0.5490356 0.8304202 -0.09466969 0.6667485 0.7363623 -0.114965 0.6762489 0.7273994 -0.116523 0.7767479 0.6154226 -0.1338578 0.8672424 0.4749446 -0.149393 0.7830044 0.6072129 -0.1348955 0.8702204 0.4692915 -0.1499401 0.9323983 0.3237498 -0.1606847 0.9340431 0.3188351 -0.1609588 0.9722326 0.163402 -0.1675221 0.9724579 0.1619644 -0.1676104 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.000999987 -0.004499971 5e-4 0.000999987 -0.004499971 -5e-4 1.98119e-4 -8.91535e-4 -5e-4 1.98119e-4 -8.91535e-4 5e-4 0.0139994 -0.002500057 5e-4 0.000999987 -0.004499971 -5e-4 0.000999987 -0.004499971 5e-4 0.0139994 -0.002500057 -5e-4 -2.05869e-4 -5.07125e-4 -5e-4 0.01349997 -5e-4 -5e-4 -2.89975e-4 -5e-4 -5e-4 1.98119e-4 -8.91535e-4 -5e-4 0.01395899 -0.002202689 -5e-4 0.01390826 -0.001907825 -5e-4 -4.71754e-5 -5.62909e-4 -5e-4 -1.24159e-4 -5.28295e-4 -5e-4 2.2889e-5 -6.09979e-4 -5e-4 8.40373e-5 -6.68164e-4 -5e-4 1.34527e-4 -7.35806e-4 -5e-4 1.72919e-4 -8.10977e-4 -5e-4 0.000999987 -0.004499971 -5e-4 0.0139994 -0.002500057 -5e-4 0.01384729 -0.001615524 -5e-4 0.013776 -0.001325726 -5e-4 0.01369446 -0.001038491 -5e-4 0.01360255 -7.53803e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 -4.71754e-5 -5.62909e-4 5e-4 -1.24159e-4 -5.28295e-4 5e-4 0.01349997 -5e-4 5e-4 1.72919e-4 -8.10977e-4 5e-4 1.34527e-4 -7.35806e-4 5e-4 1.98119e-4 -8.91535e-4 5e-4 0.01360255 -7.53803e-4 5e-4 0.01369446 -0.001038491 5e-4 2.2889e-5 -6.09979e-4 5e-4 8.40373e-5 -6.68164e-4 5e-4 -2.05869e-4 -5.07125e-4 5e-4 0.01350045 -4.71615e-4 5e-4 -2.89975e-4 -5e-4 5e-4 0.013776 -0.001325726 5e-4 0.01384729 -0.001615524 5e-4 0.01390826 -0.001907825 5e-4 0.01395899 -0.002202689 5e-4 0.000999987 -0.004499971 5e-4 0.0139994 -0.002500057 5e-4 1.34527e-4 -7.35806e-4 -5e-4 1.34527e-4 -7.35806e-4 5e-4 1.72919e-4 -8.10977e-4 5e-4 1.98119e-4 -8.91535e-4 5e-4 1.98119e-4 -8.91535e-4 -5e-4 1.72919e-4 -8.10977e-4 -5e-4 2.2889e-5 -6.09979e-4 5e-4 -4.71754e-5 -5.62909e-4 -5e-4 -4.71754e-5 -5.62909e-4 5e-4 2.2889e-5 -6.09979e-4 -5e-4 8.40373e-5 -6.68164e-4 5e-4 8.40373e-5 -6.68164e-4 -5e-4 -1.24159e-4 -5.28295e-4 5e-4 -2.05869e-4 -5.07125e-4 -5e-4 -2.05869e-4 -5.07125e-4 5e-4 -1.24159e-4 -5.28295e-4 -5e-4 -2.89975e-4 -5e-4 5e-4 -2.89975e-4 -5e-4 -5e-4 0.01384729 -0.001615524 5e-4 0.013776 -0.001325726 -5e-4 0.01384729 -0.001615524 -5e-4 0.01390826 -0.001907825 -5e-4 0.01390826 -0.001907825 5e-4 0.01395899 -0.002202689 -5e-4 0.01395899 -0.002202689 5e-4 0.0139994 -0.002500057 5e-4 0.0139994 -0.002500057 -5e-4 0.013776 -0.001325726 5e-4 0.01369446 -0.001038491 -5e-4 0.01369446 -0.001038491 5e-4 0.01360255 -7.53803e-4 5e-4 0.01360255 -7.53803e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 0.01350045 -4.71615e-4 5e-4 0.01349997 -5e-4 0.004999995 -2.89975e-4 -5e-4 5e-4 -5e-4 -5e-4 0.004999995 -5e-4 -5e-4 -0.004999995 -2.89975e-4 -5e-4 -5e-4 0.01349997 -5e-4 -5e-4 0.01349997 -5e-4 -0.004999995 0.01349997 -5e-4 5e-4 0.01349997 5e-4 0.004999995 0.01349997 5e-4 -0.004999995 0.01350045 -4.71615e-4 5e-4 0.01349997 -5e-4 0.004999995 0.01349997 -5e-4 -0.004999995 0.01349997 -5e-4 -5e-4 0.01350045 -4.71615e-4 -5e-4 0.01349997 -5e-4 5e-4 -5e-4 -5e-4 0.004999995 -5e-4 5e-4 0.004999995 0.01349997 5e-4 0.004999995 0.01349997 -5e-4 0.004999995 -5e-4 -5e-4 -0.004999995 -5e-4 5e-4 -0.004999995 -5e-4 5e-4 0.004999995 -5e-4 -5e-4 0.004999995 0.01349997 5e-4 -0.004999995 -5e-4 5e-4 -0.004999995 -5e-4 -5e-4 -0.004999995 0.01349997 -5e-4 -0.004999995 -5e-4 5e-4 0.004999995 -5e-4 5e-4 -0.004999995 0 5e-4 7e-4 0 5e-4 -7e-4 0.01349997 5e-4 -0.004999995 0.01304668 5e-4 -7e-4 0.01349997 5e-4 0.004999995 0.01304668 5e-4 7e-4 0.01304525 5.02356e-4 6.69369e-4 0 5e-4 7e-4 0 5.02462e-4 6.68713e-4 0 5.38197e-4 5.82443e-4 0.01302689 5.35564e-4 5.86251e-4 0 5.21799e-4 6.09202e-4 0 5.09789e-4 6.38197e-4 0.01303517 5.20529e-4 6.11725e-4 0.01304137 5.0931e-4 6.39671e-4 0.01299178 5.97314e-4 5.28303e-4 0 5.82443e-4 5.38197e-4 0 6.09202e-4 5.21799e-4 0.0130167 5.53746e-4 5.63605e-4 0 5.58579e-4 5.58579e-4 0.01300495 5.74514e-4 5.4422e-4 0.01296305 6.47245e-4 5.07011e-4 0 6.38197e-4 5.09789e-4 0 6.68713e-4 5.02462e-4 0.01297777 6.21703e-4 5.1589e-4 0 7e-4 5e-4 0.01294785 6.73484e-4 5.01805e-4 0.01293236 7e-4 5e-4 0.01304668 5e-4 7e-4 2.21952e-4 0.01132625 5e-4 0.0115 0.002499997 -5e-4 0.0115 0.002499997 5e-4 2.21952e-4 0.01132625 -5e-4 2.90924e-7 0.01156806 -5e-4 2.90924e-7 0.01156806 5e-4 -5.45318e-5 0.01166325 5e-4 -9.8578e-5 0.01176398 5e-4 -9.8578e-5 0.01176398 -5e-4 -5.45318e-5 0.01166325 -5e-4 1.39249e-4 0.01139867 5e-4 1.39249e-4 0.01139867 -5e-4 2.21952e-4 0.01132625 -5e-4 6.52065e-5 0.01147949 5e-4 6.52065e-5 0.01147949 -5e-4 2.21952e-4 0.01132625 5e-4 -0.002154469 0.01727068 5e-4 -9.8578e-5 0.01176398 -5e-4 -9.8578e-5 0.01176398 5e-4 -0.002154469 0.01727068 -5e-4 -0.005992531 0.01667195 5e-4 -0.005999982 0.01649999 5e-4 -0.005999982 0.01649999 -5e-4 -0.005883276 0.01717305 5e-4 -0.00593388 0.01700979 5e-4 -0.00593388 0.01700979 -5e-4 -0.005970597 0.01684159 5e-4 -0.005992531 0.01667195 -5e-4 -0.005970597 0.01684159 -5e-4 -0.005740702 0.01748478 -5e-4 -0.005649507 0.01763087 5e-4 -0.005740702 0.01748478 5e-4 -0.005883276 0.01717305 -5e-4 -0.005818367 0.01733255 -5e-4 -0.005818367 0.01733255 5e-4 -0.005432128 0.01789599 5e-4 -0.005432128 0.01789599 -5e-4 -0.005307674 0.01801317 5e-4 -0.005546927 0.01776766 5e-4 -0.005649507 0.01763087 -5e-4 -0.005546927 0.01776766 -5e-4 -0.004878759 0.01829659 5e-4 -0.005030035 0.01821428 5e-4 -0.005030035 0.01821428 -5e-4 -0.005172669 0.01812005 -5e-4 -0.005172669 0.01812005 5e-4 -0.005307674 0.01801317 -5e-4 -0.00455904 0.01842015 -5e-4 -0.004392981 0.01846098 5e-4 -0.00455904 0.01842015 5e-4 -0.004878759 0.01829659 -5e-4 -0.004722118 0.01836508 -5e-4 -0.004722118 0.01836508 5e-4 -0.00405234 0.01849925 5e-4 -0.00405234 0.01849925 -5e-4 -0.003880143 0.01849639 5e-4 -0.004222869 0.01848745 5e-4 -0.004392981 0.01846098 -5e-4 -0.004222869 0.01848745 -5e-4 -0.003376424 0.01840025 5e-4 -0.003540933 0.01844656 5e-4 -0.003540933 0.01844656 -5e-4 -0.003710091 0.01847887 -5e-4 -0.003710091 0.01847887 5e-4 -0.003880143 0.01849639 -5e-4 -0.003061056 0.0182659 -5e-4 -0.00291264 0.01817846 5e-4 -0.003061056 0.0182659 5e-4 -0.003376424 0.01840025 -5e-4 -0.003215253 0.01833957 -5e-4 -0.003215253 0.01833957 5e-4 -0.002773225 0.01807957 5e-4 -0.00291264 0.01817846 -5e-4 -0.002773225 0.01807957 -5e-4 -0.002641916 0.01796817 5e-4 -0.002641916 0.01796817 -5e-4 -0.002521514 0.01784688 5e-4 -0.002411127 0.01771467 5e-4 -0.002521514 0.01784688 -5e-4 -0.002411127 0.01771467 -5e-4 -0.002313196 0.01757454 5e-4 -0.002313196 0.01757454 -5e-4 -0.002227604 0.01742655 5e-4 -0.002154469 0.01727068 5e-4 -0.002227604 0.01742655 -5e-4 -0.002154469 0.01727068 -5e-4 -0.005999982 0.008914172 5e-4 -0.005999982 0.01649999 -5e-4 -0.005999982 0.01649999 5e-4 -0.005999982 0.008914172 -5e-4 -0.005781888 0.008290827 5e-4 -0.005707085 0.008207082 5e-4 -0.005707085 0.008207082 -5e-4 -0.005943894 0.008583962 5e-4 -0.005900979 0.008480429 5e-4 -0.005900979 0.008480429 -5e-4 -0.005846798 0.00838238 5e-4 -0.005781888 0.008290827 -5e-4 -0.005846798 0.00838238 -5e-4 -0.005993664 0.008802056 -5e-4 -0.005993664 0.008802056 5e-4 -0.005974948 0.008691906 -5e-4 -0.005943894 0.008583962 -5e-4 -0.005974948 0.008691906 5e-4 -0.005999982 0.008914172 5e-4 -0.005999982 0.008914172 -5e-4 -2.92893e-4 0.002792835 5e-4 -0.005707085 0.008207082 -5e-4 -0.005707085 0.008207082 5e-4 -2.92893e-4 0.002792835 -5e-4 -2.51435e-5 0.002308547 -5e-4 -2.51435e-5 0.002308547 5e-4 -6.31239e-6 0.002197861 5e-4 0 0.002085745 5e-4 0 0.002085745 -5e-4 -6.31239e-6 0.002197861 -5e-4 -9.90717e-5 0.002519726 5e-4 -1.53405e-4 0.002617955 -5e-4 -1.53405e-4 0.002617955 5e-4 -9.90717e-5 0.002519726 -5e-4 -5.61788e-5 0.002416193 5e-4 -5.61788e-5 0.002416193 -5e-4 -2.18067e-4 0.00270909 5e-4 -2.18067e-4 0.00270909 -5e-4 -2.92893e-4 0.002792835 -5e-4 -2.92893e-4 0.002792835 5e-4 0 5.09789e-4 6.38197e-4 0 5.02462e-4 -6.68713e-4 0 5.09789e-4 -6.38197e-4 0 5e-4 -7e-4 0 5.02462e-4 6.68713e-4 0 5.38197e-4 -5.82443e-4 0 5.58579e-4 -5.58579e-4 0 5.58579e-4 5.58579e-4 0 5.21799e-4 -6.09202e-4 0 5.38197e-4 5.82443e-4 0 5.21799e-4 6.09202e-4 0 6.38197e-4 -5.09789e-4 0 6.38197e-4 5.09789e-4 0 6.09202e-4 -5.21799e-4 0 6.09202e-4 5.21799e-4 0 5.82443e-4 5.38197e-4 0 5.82443e-4 -5.38197e-4 0 6.68713e-4 -5.02462e-4 0 6.68713e-4 5.02462e-4 0 7e-4 5e-4 0 7e-4 -5e-4 0 0.002085745 -5e-4 0 0.002085745 5e-4 0 5e-4 7e-4 0 6.38197e-4 -5.09789e-4 0.01297765 6.21724e-4 -5.16018e-4 0.01296305 6.47241e-4 -5.07144e-4 0 7e-4 -5e-4 0 6.68713e-4 -5.02462e-4 0.01294785 6.73474e-4 -5.01807e-4 0.01300495 5.74515e-4 -5.44227e-4 0 5.58579e-4 -5.58579e-4 0.0130167 5.53722e-4 -5.63585e-4 0 5.82443e-4 -5.38197e-4 0.01299178 5.9735e-4 -5.28409e-4 0 6.09202e-4 -5.21799e-4 0 5.09789e-4 -6.38197e-4 0.01304137 5.09316e-4 -6.39685e-4 0.01303517 5.20533e-4 -6.11742e-4 0 5.21799e-4 -6.09202e-4 0.01302689 5.35529e-4 -5.86212e-4 0 5.38197e-4 -5.82443e-4 0 5.02462e-4 -6.68713e-4 0.01304525 5.02361e-4 -6.69377e-4 0.01304668 5e-4 -7e-4 0 5e-4 -7e-4 0.01293236 7e-4 -5e-4 0.01297765 6.21724e-4 -5.16018e-4 0.01299178 5.9735e-4 -5.28409e-4 0.01297777 6.21703e-4 5.1589e-4 0.01304137 5.0931e-4 6.39671e-4 0.01304137 5.09316e-4 -6.39685e-4 0.01304525 5.02361e-4 -6.69377e-4 0.01304668 5e-4 -7e-4 0.01304668 5e-4 7e-4 0.01304525 5.02356e-4 6.69369e-4 0.01302689 5.35564e-4 5.86251e-4 0.01302689 5.35529e-4 -5.86212e-4 0.01303517 5.20533e-4 -6.11742e-4 0.01303517 5.20529e-4 6.11725e-4 0.01299178 5.97314e-4 5.28303e-4 0.01300495 5.74515e-4 -5.44227e-4 0.01300495 5.74514e-4 5.4422e-4 0.0130167 5.53722e-4 -5.63585e-4 0.0130167 5.53746e-4 5.63605e-4 0.01296305 6.47241e-4 -5.07144e-4 0.01294785 6.73484e-4 5.01805e-4 0.01294785 6.73474e-4 -5.01807e-4 0.01296305 6.47245e-4 5.07011e-4 0.01293236 7e-4 -5e-4 0.01293236 7e-4 5e-4 0.01258188 0.001242518 -5e-4 0.01258188 0.001242518 5e-4 0.012389 0.001505315 5e-4 0.01276296 9.74095e-4 5e-4 0.01276296 9.74095e-4 -5e-4 0.01196795 0.002013921 5e-4 0.01173985 0.00225979 5e-4 0.01196795 0.002013921 -5e-4 0.01218438 0.001762449 5e-4 0.01218438 0.001762449 -5e-4 0.012389 0.001505315 -5e-4 0.01173985 0.00225979 -5e-4 0.0115 0.002499997 5e-4 0.0115 0.002499997 -5e-4 -0.004992663 0.01312065 5e-4 -0.004999995 0.01299995 -5e-4 -0.004999995 0.01299995 5e-4 -0.004885435 0.01346457 5e-4 -0.004935026 0.01335448 -5e-4 -0.004935026 0.01335448 5e-4 -0.004970967 0.01323896 5e-4 -0.004970967 0.01323896 -5e-4 -0.004992663 0.01312065 -5e-4 -0.004748642 0.01366287 -5e-4 -0.004748642 0.01366287 5e-4 -0.004663169 0.01374846 5e-4 -0.004885435 0.01346457 -5e-4 -0.004823088 0.01356774 5e-4 -0.004823088 0.01356774 -5e-4 -0.004464924 0.01388525 5e-4 -0.004354774 0.01393485 5e-4 -0.004464924 0.01388525 -5e-4 -0.004568159 0.01382285 5e-4 -0.004568159 0.01382285 -5e-4 -0.004663169 0.01374846 -5e-4 -0.004000246 0.01399999 5e-4 -0.004120767 0.01399266 -5e-4 -0.004120767 0.01399266 5e-4 -0.00423932 0.01397085 -5e-4 -0.004354774 0.01393485 -5e-4 -0.00423932 0.01397085 5e-4 -0.003760695 0.01397085 -5e-4 -0.003760695 0.01397085 5e-4 -0.003645658 0.01393508 5e-4 -0.004000246 0.01399999 -5e-4 -0.003879606 0.01399266 5e-4 -0.003879606 0.01399266 -5e-4 -0.003431975 0.01382297 5e-4 -0.003336966 0.01374858 5e-4 -0.003431975 0.01382297 -5e-4 -0.003535509 0.01388555 5e-4 -0.003535509 0.01388555 -5e-4 -0.003645658 0.01393508 -5e-4 -0.003114521 0.01346474 5e-4 -0.003177106 0.01356816 -5e-4 -0.003177106 0.01356816 5e-4 -0.003251671 0.01366329 -5e-4 -0.003336966 0.01374858 -5e-4 -0.003251671 0.01366329 5e-4 -0.003029108 0.01323956 -5e-4 -0.003029108 0.01323956 5e-4 -0.003007292 0.01312065 5e-4 -0.003114521 0.01346474 -5e-4 -0.003065049 0.01335477 5e-4 -0.003065049 0.01335477 -5e-4 -0.003007292 0.01287925 5e-4 -0.003028988 0.01276099 5e-4 -0.003007292 0.01287925 -5e-4 -0.002999961 0.01299995 5e-4 -0.002999961 0.01299995 -5e-4 -0.003007292 0.01312065 -5e-4 -0.003176867 0.01243215 5e-4 -0.003114461 0.01253539 -5e-4 -0.003114461 0.01253539 5e-4 -0.00306493 0.01264548 -5e-4 -0.003028988 0.01276099 -5e-4 -0.00306493 0.01264548 5e-4 -0.003336787 0.01225149 -5e-4 -0.003336787 0.01225149 5e-4 -0.003431797 0.01217705 5e-4 -0.003176867 0.01243215 -5e-4 -0.003251314 0.01233708 5e-4 -0.003251314 0.01233708 -5e-4 -0.003645181 0.01206505 5e-4 -0.003760635 0.01202905 5e-4 -0.003645181 0.01206505 -5e-4 -0.003534972 0.0121147 5e-4 -0.003534972 0.0121147 -5e-4 -0.003431797 0.01217705 -5e-4 -0.003879189 0.01200729 -5e-4 -0.003760635 0.01202905 -5e-4 -0.003879189 0.01200729 5e-4 -0.004120349 0.01200729 5e-4 -0.004120349 0.01200729 -5e-4 -0.00399971 0.01199996 -5e-4 -0.00399971 0.01199996 5e-4 -0.004239201 0.01202905 5e-4 -0.004239201 0.01202905 -5e-4 -0.004354298 0.01206487 -5e-4 -0.004354298 0.01206487 5e-4 -0.004464447 0.01211434 5e-4 -0.004464447 0.01211434 -5e-4 -0.004567921 0.01217699 5e-4 -0.004567921 0.01217699 -5e-4 -0.00466299 0.01225137 -5e-4 -0.00466299 0.01225137 5e-4 -0.004748284 0.01233667 5e-4 -0.004748284 0.01233667 -5e-4 -0.00482285 0.0124318 5e-4 -0.00482285 0.0124318 -5e-4 -0.004885375 0.01253515 -5e-4 -0.004885375 0.01253515 5e-4 -0.004934906 0.01264518 5e-4 -0.004934906 0.01264518 -5e-4 -0.004970848 0.0127604 5e-4 -0.004970848 0.0127604 -5e-4 -0.004992663 0.01287925 -5e-4 -0.004992663 0.01287925 5e-4 -0.004992663 0.01662069 5e-4 -0.004999995 0.01649999 -5e-4 -0.004999995 0.01649999 5e-4 -0.004885435 0.01696455 5e-4 -0.004935026 0.01685446 -5e-4 -0.004935026 0.01685446 5e-4 -0.004970967 0.01673895 5e-4 -0.004970967 0.01673895 -5e-4 -0.004992663 0.01662069 -5e-4 -0.004748642 0.01716285 -5e-4 -0.004748642 0.01716285 5e-4 -0.004663169 0.01724845 5e-4 -0.004885435 0.01696455 -5e-4 -0.004823088 0.01706779 5e-4 -0.004823088 0.01706779 -5e-4 -0.004464924 0.0173853 5e-4 -0.004354774 0.01743489 5e-4 -0.004464924 0.0173853 -5e-4 -0.004568159 0.01732289 5e-4 -0.004568159 0.01732289 -5e-4 -0.004663169 0.01724845 -5e-4 -0.004000246 0.01749998 5e-4 -0.004120767 0.01749265 -5e-4 -0.004120767 0.01749265 5e-4 -0.00423932 0.01747089 -5e-4 -0.004354774 0.01743489 -5e-4 -0.00423932 0.01747089 5e-4 -0.003760695 0.01747089 -5e-4 -0.003760695 0.01747089 5e-4 -0.003645658 0.01743507 5e-4 -0.004000246 0.01749998 -5e-4 -0.003879606 0.01749265 5e-4 -0.003879606 0.01749265 -5e-4 -0.003431975 0.01732295 5e-4 -0.003336966 0.01724857 5e-4 -0.003431975 0.01732295 -5e-4 -0.003535509 0.0173856 5e-4 -0.003535509 0.0173856 -5e-4 -0.003645658 0.01743507 -5e-4 -0.003114521 0.01696479 5e-4 -0.003177106 0.01706814 -5e-4 -0.003177106 0.01706814 5e-4 -0.003251671 0.01716327 -5e-4 -0.003336966 0.01724857 -5e-4 -0.003251671 0.01716327 5e-4 -0.003029108 0.01673954 -5e-4 -0.003029108 0.01673954 5e-4 -0.003007292 0.01662069 5e-4 -0.003114521 0.01696479 -5e-4 -0.003065049 0.01685476 5e-4 -0.003065049 0.01685476 -5e-4 -0.003007292 0.01637929 5e-4 -0.003028988 0.01626098 5e-4 -0.003007292 0.01637929 -5e-4 -0.002999961 0.01649999 5e-4 -0.002999961 0.01649999 -5e-4 -0.003007292 0.01662069 -5e-4 -0.003176867 0.0159322 5e-4 -0.003114461 0.01603537 -5e-4 -0.003114461 0.01603537 5e-4 -0.00306493 0.01614546 -5e-4 -0.003028988 0.01626098 -5e-4 -0.00306493 0.01614546 5e-4 -0.003336787 0.01575148 -5e-4 -0.003336787 0.01575148 5e-4 -0.003431797 0.01567709 5e-4 -0.003176867 0.0159322 -5e-4 -0.003251314 0.01583707 5e-4 -0.003251314 0.01583707 -5e-4 -0.003645181 0.01556509 5e-4 -0.003760635 0.01552909 5e-4 -0.003645181 0.01556509 -5e-4 -0.003534972 0.01561468 5e-4 -0.003534972 0.01561468 -5e-4 -0.003431797 0.01567709 -5e-4 -0.003879189 0.01550728 -5e-4 -0.003760635 0.01552909 -5e-4 -0.003879189 0.01550728 5e-4 -0.004120349 0.01550728 5e-4 -0.004120349 0.01550728 -5e-4 -0.00399971 0.01549994 -5e-4 -0.00399971 0.01549994 5e-4 -0.004239201 0.01552909 5e-4 -0.004239201 0.01552909 -5e-4 -0.004354298 0.01556485 -5e-4 -0.004354298 0.01556485 5e-4 -0.004464447 0.01561439 5e-4 -0.004464447 0.01561439 -5e-4 -0.004567921 0.01567697 5e-4 -0.004567921 0.01567697 -5e-4 -0.00466299 0.01575136 -5e-4 -0.00466299 0.01575136 5e-4 -0.004748284 0.01583665 5e-4 -0.004748284 0.01583665 -5e-4 -0.00482285 0.01593178 5e-4 -0.00482285 0.01593178 -5e-4 -0.004885375 0.01603519 -5e-4 -0.004885375 0.01603519 5e-4 -0.004934906 0.01614516 5e-4 -0.004934906 0.01614516 -5e-4 -0.004970848 0.01626038 5e-4 -0.004970848 0.01626038 -5e-4 -0.004992663 0.01637929 -5e-4 -0.004992663 0.01637929 5e-4 -0.003999948 0.008499979 5e-4 -0.005707085 0.008207082 5e-4 -0.004120171 0.008507251 5e-4 0 0.002085745 5e-4 -6.31239e-6 0.002197861 5e-4 0.0115 0.002499997 5e-4 -0.005030035 0.01821428 5e-4 -0.004464924 0.0173853 5e-4 -0.005172669 0.01812005 5e-4 0 7e-4 5e-4 0.01173985 0.00225979 5e-4 0.01218438 0.001762449 5e-4 0.01196795 0.002013921 5e-4 0.012389 0.001505315 5e-4 0.01258188 0.001242518 5e-4 0.01276296 9.74095e-4 5e-4 0.01293236 7e-4 5e-4 -2.51435e-5 0.002308547 5e-4 -5.61788e-5 0.002416193 5e-4 -9.90717e-5 0.002519726 5e-4 -1.53405e-4 0.002617955 5e-4 -2.18067e-4 0.00270909 5e-4 2.21952e-4 0.01132625 5e-4 -2.92893e-4 0.002792835 5e-4 6.52065e-5 0.01147949 5e-4 -0.003114521 0.009964764 5e-4 2.90924e-7 0.01156806 5e-4 -0.003065049 0.009854733 5e-4 1.39249e-4 0.01139867 5e-4 -0.003029108 0.009739577 5e-4 -0.003114461 0.01253539 5e-4 -0.00306493 0.01264548 5e-4 -9.8578e-5 0.01176398 5e-4 -0.003431797 0.01217705 5e-4 -0.003336787 0.01225149 5e-4 -0.003336966 0.0102486 5e-4 -0.003028988 0.01276099 5e-4 -0.003007292 0.01287925 5e-4 -0.002999961 0.01299995 5e-4 -0.004354774 0.01743489 5e-4 -0.004722118 0.01836508 5e-4 -0.00423932 0.01747089 5e-4 -0.004970967 0.01673895 5e-4 -0.00593388 0.01700979 5e-4 -0.004935026 0.01685446 5e-4 -0.00455904 0.01842015 5e-4 -0.004392981 0.01846098 5e-4 -0.004878759 0.01829659 5e-4 -0.004568159 0.01732289 5e-4 -0.004120767 0.01749265 5e-4 -0.004000246 0.01749998 5e-4 -0.004222869 0.01848745 5e-4 -0.004663169 0.01724845 5e-4 -0.005307674 0.01801317 5e-4 -0.003880143 0.01849639 5e-4 -0.00405234 0.01849925 5e-4 -0.004748642 0.01716285 5e-4 -0.005432128 0.01789599 5e-4 -0.003879606 0.01749265 5e-4 -0.005546927 0.01776766 5e-4 -0.003710091 0.01847887 5e-4 -0.003540933 0.01844656 5e-4 -0.005649507 0.01763087 5e-4 -0.004823088 0.01706779 5e-4 -0.003760695 0.01747089 5e-4 -0.003376424 0.01840025 5e-4 -0.003645658 0.01743507 5e-4 -0.004885435 0.01696455 5e-4 -0.005740702 0.01748478 5e-4 -0.003061056 0.0182659 5e-4 -0.003215253 0.01833957 5e-4 -0.005818367 0.01733255 5e-4 -0.003535509 0.0173856 5e-4 -0.00291264 0.01817846 5e-4 -0.003431975 0.01732295 5e-4 -0.005883276 0.01717305 5e-4 -0.002641916 0.01796817 5e-4 -0.002773225 0.01807957 5e-4 -0.003336966 0.01724857 5e-4 -0.002521514 0.01784688 5e-4 -0.003251671 0.01716327 5e-4 -0.004992663 0.01662069 5e-4 -0.005970597 0.01684159 5e-4 -0.004999995 0.01649999 5e-4 -0.005999982 0.01649999 5e-4 -0.005992531 0.01667195 5e-4 -0.004934906 0.01614516 5e-4 -0.004885375 0.01603519 5e-4 -0.004992663 0.01637929 5e-4 -0.004970848 0.01626038 5e-4 -0.004748284 0.01583665 5e-4 -0.004748642 0.01366287 5e-4 -0.00482285 0.01593178 5e-4 -0.00466299 0.01575136 5e-4 -0.004663169 0.01374846 5e-4 -5.45318e-5 0.01166325 5e-4 -0.003177106 0.01006817 5e-4 -0.004464447 0.00861442 5e-4 -0.004354536 0.008564949 5e-4 -0.004567742 0.008676826 5e-4 -0.004239022 0.008528947 5e-4 -0.005999982 0.008914172 5e-4 -0.004999995 0.01299995 5e-4 -0.004992663 0.01287925 5e-4 -0.003114521 0.01346474 5e-4 -0.003114461 0.01603537 5e-4 -0.003176867 0.01243215 5e-4 -0.003645181 0.01206505 5e-4 -0.003535509 0.01038557 5e-4 -0.003645658 0.0104351 5e-4 -0.003534972 0.0121147 5e-4 -0.003431975 0.01032298 5e-4 -0.003251314 0.01233708 5e-4 -0.003760695 0.01047086 5e-4 -0.003760635 0.01202905 5e-4 -0.003251671 0.01016324 5e-4 -0.004000246 0.01049995 5e-4 -0.004120767 0.01049268 5e-4 -0.004120349 0.01200729 5e-4 -0.003879189 0.01200729 5e-4 -0.003879606 0.01049268 5e-4 -0.00399971 0.01199996 5e-4 -0.004567921 0.01217699 5e-4 -0.004464924 0.01038527 5e-4 -0.004568159 0.01032286 5e-4 -0.004354298 0.01206487 5e-4 -0.00423932 0.01047086 5e-4 -0.004354774 0.01043486 5e-4 -0.00466299 0.01225137 5e-4 -0.004748344 0.008836686 5e-4 -0.004822731 0.008931636 5e-4 -0.004663169 0.01024848 5e-4 -0.004885315 0.00903511 5e-4 -0.005900979 0.008480429 5e-4 -0.004970788 0.009260356 5e-4 -0.004934906 0.009145259 5e-4 -0.004999995 0.009499967 5e-4 -0.004992663 0.009620666 5e-4 -0.004934906 0.01264518 5e-4 -0.004885375 0.01253515 5e-4 -0.004885435 0.009964585 5e-4 -0.004935026 0.009854435 5e-4 -0.004970848 0.0127604 5e-4 -0.004970967 0.01323896 5e-4 -0.004992663 0.01312065 5e-4 -0.004567921 0.01567697 5e-4 -0.004568159 0.01382285 5e-4 -0.004885435 0.01346457 5e-4 -0.004935026 0.01335448 5e-4 -0.004823088 0.01356774 5e-4 -0.00423932 0.01397085 5e-4 -0.004239201 0.01552909 5e-4 -0.004120767 0.01399266 5e-4 -0.004464924 0.01388525 5e-4 -0.004464447 0.01561439 5e-4 -0.004354774 0.01393485 5e-4 -0.003760635 0.01552909 5e-4 -0.003760695 0.01397085 5e-4 -0.003879189 0.01550728 5e-4 -0.00399971 0.01549994 5e-4 -0.004000246 0.01399999 5e-4 -0.004120349 0.01550728 5e-4 -0.003431797 0.01567709 5e-4 -0.003431975 0.01382297 5e-4 -0.003534972 0.01561468 5e-4 -0.003535509 0.01388555 5e-4 -0.003645181 0.01556509 5e-4 -0.003336966 0.01374858 5e-4 -0.003336787 0.01575148 5e-4 -0.002313196 0.01757454 5e-4 -0.003177106 0.01706814 5e-4 -0.002411127 0.01771467 5e-4 -0.003251314 0.01583707 5e-4 -0.003177106 0.01356816 5e-4 -0.003251671 0.01366329 5e-4 -0.003176867 0.0159322 5e-4 -0.00306493 0.01614546 5e-4 -0.002154469 0.01727068 5e-4 -0.003007292 0.01637929 5e-4 -0.002999961 0.01649999 5e-4 -0.003028988 0.01626098 5e-4 -0.003065049 0.01335477 5e-4 -0.003007292 0.01312065 5e-4 -0.003029108 0.01323956 5e-4 -0.003645658 0.01393508 5e-4 -0.003879606 0.01399266 5e-4 -0.004354298 0.01556485 5e-4 -0.002227604 0.01742655 5e-4 -0.003114521 0.01696479 5e-4 -0.003029108 0.01673954 5e-4 -0.003065049 0.01685476 5e-4 -0.003007292 0.01662069 5e-4 -0.003028988 0.009260952 5e-4 -0.003007292 0.009379208 5e-4 -0.002999961 0.009499967 5e-4 -0.005781888 0.008290827 5e-4 -0.005846798 0.00838238 5e-4 -0.003114402 0.009035527 5e-4 -0.00306493 0.009145438 5e-4 -0.003176808 0.008932173 5e-4 -0.003336727 0.00875163 5e-4 -0.003251373 0.008836925 5e-4 -0.003535091 0.008614599 5e-4 -0.003431618 0.008677184 5e-4 -0.003760337 0.008529126 5e-4 -0.003645241 0.008565008 5e-4 -0.003879189 0.008507311 5e-4 -0.00466299 0.008751392 5e-4 -0.004464447 0.01211434 5e-4 -0.004748284 0.01233667 5e-4 -0.004748642 0.01016288 5e-4 -0.005943894 0.008583962 5e-4 -0.005974948 0.008691906 5e-4 -0.00482285 0.0124318 5e-4 -0.005993664 0.008802056 5e-4 -0.004823088 0.01006776 5e-4 -0.004992663 0.009379208 5e-4 -0.004970967 0.009739041 5e-4 -0.004239201 0.01202905 5e-4 -0.003007292 0.009620666 5e-4 -0.005707085 0.008207082 -5e-4 -0.004464864 0.008614599 -5e-4 -0.004568278 0.008677184 -5e-4 -5.61788e-5 0.002416193 -5e-4 -2.51435e-5 0.002308547 -5e-4 0.0115 0.002499997 -5e-4 -6.31239e-6 0.002197861 -5e-4 -9.90717e-5 0.002519726 -5e-4 -1.53405e-4 0.002617955 -5e-4 2.21952e-4 0.01132625 -5e-4 -2.18067e-4 0.00270909 -5e-4 -0.004120767 0.008507311 -5e-4 -0.004239618 0.008529126 -5e-4 -0.003999948 0.008499979 -5e-4 -0.00482285 0.01593178 -5e-4 -0.004885375 0.01603519 -5e-4 -0.005999982 0.01649999 -5e-4 -0.004992663 0.01287925 -5e-4 -0.004999995 0.01299995 -5e-4 -0.005999982 0.008914172 -5e-4 -0.003760695 0.01747089 -5e-4 -0.003645658 0.01743507 -5e-4 -0.003376424 0.01840025 -5e-4 -0.005970597 0.01684159 -5e-4 -0.004992663 0.01662069 -5e-4 -0.004970967 0.01673895 -5e-4 -0.004000246 0.01749998 -5e-4 -0.004222869 0.01848745 -5e-4 -0.004120767 0.01749265 -5e-4 -0.004722118 0.01836508 -5e-4 -0.004354774 0.01743489 -5e-4 -0.00423932 0.01747089 -5e-4 -0.005030035 0.01821428 -5e-4 -0.005172669 0.01812005 -5e-4 -0.004464924 0.0173853 -5e-4 -0.004392981 0.01846098 -5e-4 -0.00455904 0.01842015 -5e-4 -0.004878759 0.01829659 -5e-4 -0.004568159 0.01732289 -5e-4 -0.004663169 0.01724845 -5e-4 -0.005432128 0.01789599 -5e-4 -0.004748642 0.01716285 -5e-4 -0.005307674 0.01801317 -5e-4 -0.005546927 0.01776766 -5e-4 -0.003880143 0.01849639 -5e-4 -0.00405234 0.01849925 -5e-4 -0.005649507 0.01763087 -5e-4 -0.004823088 0.01706779 -5e-4 -0.003879606 0.01749265 -5e-4 -0.005740702 0.01748478 -5e-4 -0.004885435 0.01696455 -5e-4 -0.003710091 0.01847887 -5e-4 -0.003540933 0.01844656 -5e-4 -0.003061056 0.0182659 -5e-4 -0.003215253 0.01833957 -5e-4 -0.004935026 0.01685446 -5e-4 -0.005818367 0.01733255 -5e-4 -0.00291264 0.01817846 -5e-4 -0.003535509 0.0173856 -5e-4 -0.003431975 0.01732295 -5e-4 -0.005883276 0.01717305 -5e-4 -0.002641916 0.01796817 -5e-4 -0.002773225 0.01807957 -5e-4 -0.00593388 0.01700979 -5e-4 -0.002521514 0.01784688 -5e-4 -0.003336966 0.01724857 -5e-4 -0.003251671 0.01716327 -5e-4 -0.004999995 0.01649999 -5e-4 -0.005992531 0.01667195 -5e-4 -0.004934906 0.01614516 -5e-4 -0.004992663 0.01637929 -5e-4 -0.004970848 0.01626038 -5e-4 -0.004748642 0.01366287 -5e-4 -0.004748284 0.01583665 -5e-4 -0.003645181 0.01206505 -5e-4 -0.003760635 0.01202905 -5e-4 -0.003645181 0.01043486 -5e-4 -0.004663169 0.01374846 -5e-4 -0.00466299 0.01575136 -5e-4 -0.004934906 0.009854733 -5e-4 -0.004970848 0.009739577 -5e-4 -0.004885554 0.009035527 -5e-4 -0.005993664 0.008802056 -5e-4 -0.003251314 0.01233708 -5e-4 -0.003251314 0.01016288 -5e-4 -9.8578e-5 0.01176398 -5e-4 -0.004354655 0.008565008 -5e-4 -2.92893e-4 0.002792835 -5e-4 -5.45318e-5 0.01166325 -5e-4 -0.003176867 0.01006776 -5e-4 -0.004823148 0.008932173 -5e-4 -0.004748582 0.008836925 -5e-4 -0.005781888 0.008290827 -5e-4 -0.005846798 0.00838238 -5e-4 2.90924e-7 0.01156806 -5e-4 -0.003114461 0.009964585 -5e-4 6.52065e-5 0.01147949 -5e-4 0 0.002085745 -5e-4 0 7e-4 -5e-4 0.01196795 0.002013921 -5e-4 0.01173985 0.00225979 -5e-4 0.01218438 0.001762449 -5e-4 0.012389 0.001505315 -5e-4 0.01276296 9.74095e-4 -5e-4 0.01258188 0.001242518 -5e-4 0.01293236 7e-4 -5e-4 -0.002999961 0.009499967 -5e-4 -0.003007292 0.009379208 -5e-4 -0.003028988 0.009739041 -5e-4 1.39249e-4 0.01139867 -5e-4 -0.00306493 0.009854435 -5e-4 -0.003029167 0.009260356 -5e-4 -0.00306499 0.009145259 -5e-4 -0.003114581 0.00903511 -5e-4 -0.003251612 0.008836686 -5e-4 -0.003177225 0.008931636 -5e-4 -0.003432154 0.008676826 -5e-4 -0.003336966 0.008751392 -5e-4 -0.00364542 0.008564949 -5e-4 -0.003535509 0.00861442 -5e-4 -0.003879725 0.008507251 -5e-4 -0.003760933 0.008528947 -5e-4 -0.004663228 0.00875163 -5e-4 -0.005900979 0.008480429 -5e-4 -0.005974948 0.008691906 -5e-4 -0.005943894 0.008583962 -5e-4 -0.004992663 0.009620666 -5e-4 -0.004999995 0.009499967 -5e-4 -0.004970967 0.009260952 -5e-4 -0.004935026 0.009145438 -5e-4 -0.004992663 0.009379208 -5e-4 -0.003431797 0.01032286 -5e-4 -0.003431797 0.01217705 -5e-4 -0.003534972 0.0121147 -5e-4 -0.004748284 0.01233667 -5e-4 -0.004748284 0.01016324 -5e-4 -0.00466299 0.0102486 -5e-4 -0.004885375 0.009964764 -5e-4 -0.004464447 0.01038557 -5e-4 -0.004354298 0.0104351 -5e-4 -0.004464447 0.01211434 -5e-4 -0.004567921 0.01217699 -5e-4 -0.004567921 0.01032298 -5e-4 -0.00399971 0.01199996 -5e-4 -0.004120349 0.01200729 -5e-4 -0.00399971 0.01049995 -5e-4 -0.004239201 0.01202905 -5e-4 -0.004354298 0.01206487 -5e-4 -0.004239201 0.01047086 -5e-4 -0.003534972 0.01038527 -5e-4 -0.003879189 0.01200729 -5e-4 -0.003760635 0.01047086 -5e-4 -0.003879189 0.01049268 -5e-4 -0.003336787 0.01024848 -5e-4 -0.003336787 0.01225149 -5e-4 -0.003114461 0.01253539 -5e-4 -0.003176867 0.01243215 -5e-4 -0.003028988 0.01276099 -5e-4 -0.00306493 0.01264548 -5e-4 -0.003007292 0.009620666 -5e-4 -0.003114461 0.01603537 -5e-4 -0.003114521 0.01346474 -5e-4 -0.003007292 0.01287925 -5e-4 -0.002999961 0.01299995 -5e-4 -0.004120349 0.01049268 -5e-4 -0.00466299 0.01225137 -5e-4 -0.00482285 0.0124318 -5e-4 -0.00482285 0.01006817 -5e-4 -0.004885375 0.01253515 -5e-4 -0.004934906 0.01264518 -5e-4 -0.004970848 0.0127604 -5e-4 -0.004970967 0.01323896 -5e-4 -0.004992663 0.01312065 -5e-4 -0.004568159 0.01382285 -5e-4 -0.004567921 0.01567697 -5e-4 -0.004885435 0.01346457 -5e-4 -0.004935026 0.01335448 -5e-4 -0.004823088 0.01356774 -5e-4 -0.00423932 0.01397085 -5e-4 -0.004120767 0.01399266 -5e-4 -0.004239201 0.01552909 -5e-4 -0.004464924 0.01388525 -5e-4 -0.004354774 0.01393485 -5e-4 -0.004464447 0.01561439 -5e-4 -0.003760635 0.01552909 -5e-4 -0.003879189 0.01550728 -5e-4 -0.003760695 0.01397085 -5e-4 -0.00399971 0.01549994 -5e-4 -0.004120349 0.01550728 -5e-4 -0.004000246 0.01399999 -5e-4 -0.003431797 0.01567709 -5e-4 -0.003534972 0.01561468 -5e-4 -0.003431975 0.01382297 -5e-4 -0.003535509 0.01388555 -5e-4 -0.003645181 0.01556509 -5e-4 -0.003336966 0.01374858 -5e-4 -0.003336787 0.01575148 -5e-4 -0.003251314 0.01583707 -5e-4 -0.003251671 0.01366329 -5e-4 -0.003177106 0.01356816 -5e-4 -0.003176867 0.0159322 -5e-4 -0.003007292 0.01637929 -5e-4 -0.002154469 0.01727068 -5e-4 -0.002999961 0.01649999 -5e-4 -0.003028988 0.01626098 -5e-4 -0.00306493 0.01614546 -5e-4 -0.003065049 0.01335477 -5e-4 -0.003007292 0.01312065 -5e-4 -0.003029108 0.01323956 -5e-4 -0.003177106 0.01706814 -5e-4 -0.002313196 0.01757454 -5e-4 -0.002411127 0.01771467 -5e-4 -0.003645658 0.01393508 -5e-4 -0.003879606 0.01399266 -5e-4 -0.004354298 0.01556485 -5e-4 -0.002227604 0.01742655 -5e-4 -0.003114521 0.01696479 -5e-4 -0.003029108 0.01673954 -5e-4 -0.003065049 0.01685476 -5e-4 -0.003007292 0.01662069 -5e-4 -0.004992663 0.009620666 5e-4 -0.004999995 0.009499967 -5e-4 -0.004999995 0.009499967 5e-4 -0.004885435 0.009964585 5e-4 -0.004934906 0.009854733 -5e-4 -0.004935026 0.009854435 5e-4 -0.004970967 0.009739041 5e-4 -0.004970848 0.009739577 -5e-4 -0.004992663 0.009620666 -5e-4 -0.004748284 0.01016324 -5e-4 -0.004748642 0.01016288 5e-4 -0.004663169 0.01024848 5e-4 -0.004885375 0.009964764 -5e-4 -0.004823088 0.01006776 5e-4 -0.00482285 0.01006817 -5e-4 -0.004464924 0.01038527 5e-4 -0.004354774 0.01043486 5e-4 -0.004464447 0.01038557 -5e-4 -0.004568159 0.01032286 5e-4 -0.004567921 0.01032298 -5e-4 -0.00466299 0.0102486 -5e-4 -0.004000246 0.01049995 5e-4 -0.004120349 0.01049268 -5e-4 -0.004120767 0.01049268 5e-4 -0.004239201 0.01047086 -5e-4 -0.004354298 0.0104351 -5e-4 -0.00423932 0.01047086 5e-4 -0.003760635 0.01047086 -5e-4 -0.003760695 0.01047086 5e-4 -0.003645658 0.0104351 5e-4 -0.00399971 0.01049995 -5e-4 -0.003879606 0.01049268 5e-4 -0.003879189 0.01049268 -5e-4 -0.003431975 0.01032298 5e-4 -0.003336966 0.0102486 5e-4 -0.003431797 0.01032286 -5e-4 -0.003535509 0.01038557 5e-4 -0.003534972 0.01038527 -5e-4 -0.003645181 0.01043486 -5e-4 -0.003114521 0.009964764 5e-4 -0.003176867 0.01006776 -5e-4 -0.003177106 0.01006817 5e-4 -0.003251314 0.01016288 -5e-4 -0.003336787 0.01024848 -5e-4 -0.003251671 0.01016324 5e-4 -0.003028988 0.009739041 -5e-4 -0.003029108 0.009739577 5e-4 -0.003007292 0.009620666 5e-4 -0.003114461 0.009964585 -5e-4 -0.003065049 0.009854733 5e-4 -0.00306493 0.009854435 -5e-4 -0.003007292 0.009379208 5e-4 -0.003028988 0.009260952 5e-4 -0.003007292 0.009379208 -5e-4 -0.002999961 0.009499967 5e-4 -0.002999961 0.009499967 -5e-4 -0.003007292 0.009620666 -5e-4 -0.003176808 0.008932173 5e-4 -0.003114581 0.00903511 -5e-4 -0.003114402 0.009035527 5e-4 -0.00306499 0.009145259 -5e-4 -0.003029167 0.009260356 -5e-4 -0.00306493 0.009145438 5e-4 -0.003336966 0.008751392 -5e-4 -0.003336727 0.00875163 5e-4 -0.003431618 0.008677184 5e-4 -0.003177225 0.008931636 -5e-4 -0.003251373 0.008836925 5e-4 -0.003251612 0.008836686 -5e-4 -0.003645241 0.008565008 5e-4 -0.003760337 0.008529126 5e-4 -0.00364542 0.008564949 -5e-4 -0.003535091 0.008614599 5e-4 -0.003535509 0.00861442 -5e-4 -0.003432154 0.008676826 -5e-4 -0.003879725 0.008507251 -5e-4 -0.003760933 0.008528947 -5e-4 -0.003879189 0.008507311 5e-4 -0.004120171 0.008507251 5e-4 -0.004120767 0.008507311 -5e-4 -0.003999948 0.008499979 -5e-4 -0.003999948 0.008499979 5e-4 -0.004239022 0.008528947 5e-4 -0.004239618 0.008529126 -5e-4 -0.004354655 0.008565008 -5e-4 -0.004354536 0.008564949 5e-4 -0.004464447 0.00861442 5e-4 -0.004464864 0.008614599 -5e-4 -0.004567742 0.008676826 5e-4 -0.004568278 0.008677184 -5e-4 -0.004663228 0.00875163 -5e-4 -0.00466299 0.008751392 5e-4 -0.004748344 0.008836686 5e-4 -0.004748582 0.008836925 -5e-4 -0.004822731 0.008931636 5e-4 -0.004823148 0.008932173 -5e-4 -0.004885554 0.009035527 -5e-4 -0.004885315 0.00903511 5e-4 -0.004934906 0.009145259 5e-4 -0.004935026 0.009145438 -5e-4 -0.004970788 0.009260356 5e-4 -0.004970967 0.009260952 -5e-4 -0.004992663 0.009379208 -5e-4 -0.004992663 0.009379208 5e-4 + + + + + + + + + + -0.9761871 -0.2169305 0 0.1520573 -0.9883717 0 0.1520573 -0.9883717 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 1.16884e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.84901 -0.5283767 0 -0.9257904 -0.3780374 0 -0.9543975 -0.2985392 0 -0.6257329 -0.7800375 0 -0.4855885 -0.8741875 0 -0.7480252 -0.6636703 0 -0.3316226 -0.9434123 0 -0.1681886 -0.9857548 0 -0.08438402 -0.9964334 0 0.9751317 0.2216264 0 0.9666868 0.2559622 0 0.9823791 0.1868989 0 0.9883732 0.152048 0 0.9909014 0.1345902 0 0.9570001 0.2900879 0 0.9461448 0.3237438 0 0.9403447 0.3402234 0 0 -1 0 0 -1 0 1 5.1521e-4 0 1 0 1.11345e-4 0.9998442 -0.01765561 0 1 0 -1.11345e-4 0.9999999 5.09219e-4 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 0.9889115 0.1485061 0 0.9876874 0.1564405 0 0.9969195 0.07843267 0 0.8090303 0.587767 0 0.8910139 0.4539761 0 0.8306108 0.5568535 0 0.9510608 0.309004 0 0.9560143 0.2933201 0 0.9023097 0.4310883 -3.05192e-5 0.5316439 0.846968 3.05194e-5 0.4539761 0.8910139 3.05193e-5 0.5878015 0.8090053 0 0.7443419 0.6677988 0 0.6437109 0.7652688 3.05195e-5 0.7071068 0.7071068 0 0.2837984 0.958884 3.05192e-5 0.1564108 0.9876922 3.05189e-5 0.309004 0.9510608 0 0.4113112 0.911495 0 0.07843267 0.9969195 0 0.152658 0.9882791 0 0.06790441 0.9976919 0 0.997057 0.07666379 0.6163083 0.787505 0 0.8378868 0.5458441 0 0.8927485 0.4505554 0 0.9161881 0.4007484 0 0.6990348 0.7150877 0 0.6586904 0.7524141 0 0.7731217 0.6342577 0 0.9368384 0.3497627 0 0.9368384 0.3497627 0 -0.9963108 0.08581835 0 -0.9990646 0.04324513 0 -0.9990633 0.04327559 0 -0.9416155 0.3366902 0 -0.9670007 0.2547742 0 -0.9852818 0.170938 0 -0.8702849 0.492549 0 -0.8249403 0.5652199 0 -0.9092627 0.4162228 0 -0.7160978 0.698 0 -0.6537923 0.7566741 0 -0.7733696 0.6339555 0 -0.4396655 0.8981617 0 -0.514949 0.8572209 0 -0.5864574 0.8099802 0 -0.2795827 0.9601216 0 -0.1964507 0.9805138 0 -0.3607107 0.9326778 0 -0.02609395 0.9996595 0 0.05963438 0.9982203 0 -0.1115469 0.9937592 0 0.3119671 0.9500929 0 0.2294085 0.9733303 0 0.1450863 0.9894191 0 0.4697279 0.8828114 0 0.5435512 0.8393761 0 0.3921763 0.9198901 0 0.6133827 0.7897859 0 0.6788997 0.734231 0 0.7393571 0.6733136 0 0.7943544 0.6074547 0 0.8434202 0.5372546 0 0.8862756 0.4631583 0 0.9052313 0.4249194 0 -0.7819901 -0.623291 0 -0.7457401 -0.6662372 0 -0.9439169 -0.3301832 0 -0.9010111 -0.4337964 0 -0.8468511 -0.5318303 0 -0.7819633 -0.6233245 0 -0.9937043 -0.1120359 0 -0.9749509 -0.2224204 0 -0.9937075 -0.1120057 0 -0.9984222 -0.05615454 0 -0.9984204 -0.05618494 0 -0.707107 -0.7071066 0 -0.707107 -0.7071066 0 -0.9748736 -0.2227593 0 -0.9936906 -0.1121564 0 -0.9009222 -0.4339808 0 -0.8466618 -0.5321316 0 -0.9438531 -0.3303654 0 -0.7818831 -0.6234251 0 -0.7457113 -0.6662693 0 -1 0 0 -1 -5.41561e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -5.41562e-7 0 3.05189e-5 0.309004 -0.9510608 -3.05189e-5 0.2853817 -0.958414 -3.05192e-5 0.4110625 -0.9116073 0 0.07843267 -0.9969195 0 0.1558607 -0.987779 0 0.1564108 -0.9876922 0 0.6420677 -0.7666479 0 0.7437205 -0.6684908 3.05195e-5 0.7071068 -0.7071068 3.05193e-5 0.5878015 -0.8090053 3.05194e-5 0.4539761 -0.8910139 -3.05191e-5 0.5295984 -0.8482486 0 0.9510608 -0.309004 0 0.9026917 -0.4302877 0 0.9560058 -0.293348 0 0.8910139 -0.4539761 0 0.8090303 -0.587767 0 0.8311618 -0.5560306 0 0.9888936 -0.1486254 0 0.9876874 -0.1564405 0 0.997043 -0.07684582 0 0.9969195 -0.07843267 0 0.06793481 -0.9976898 0.8655719 0.5007848 -7.4213e-5 0.8723533 0.4888761 2.26396e-6 0.8594916 0.5111501 0 0.8748543 0.4843864 -1.44521e-5 0.8752146 0.4837348 1.61431e-6 0.8654432 0.5010073 4.33636e-7 0.8712601 0.4908216 -1.04787e-5 0.8652339 0.5013685 -4.96214e-6 0.8653305 0.5012019 -2.02175e-6 0.8634088 0.5045052 0 0.8633202 0.5046567 -5.01358e-6 0.8177208 0.5756151 0 0.7944731 0.6072995 0 0.8572209 0.514949 0 0.8399876 0.5426058 0 0.7456675 0.6663184 0 0.7204078 0.6935508 0 0.7704181 0.637539 0 0.7204225 0.6935355 0 0.707534 0.7066794 0 0.8571642 0.5150432 0 0.8679411 0.4966673 -1.96608e-6 0.8672958 0.4977932 1.70372e-5 0.8667323 0.4987738 -7.43036e-5 0.8715066 0.4903839 4.78822e-7 0.8657456 0.5004844 1.708e-5 0.8722475 0.4890647 -1.04648e-5 0.8754811 0.4832525 1.56407e-6 0.8721632 0.4892151 -1.46072e-5 0.8752697 0.4836352 2.24776e-6 0.8720739 0.4893745 1.87202e-6 0.8602439 0.5098827 1.9035e-6 0.9926961 -0.1206421 0 1 0 0 0.8854585 -0.4647185 0 0.9350855 -0.3544224 0 0.9350754 -0.354449 0 0.970991 -0.239116 0 0.7488707 -0.6627162 0 0.6633309 -0.7483264 0 0.8231229 -0.5678635 0 0.4647424 -0.885446 0 0.3547297 -0.9349689 0 0.567989 -0.8230362 0 3.05194e-5 -1 0 0.1208563 -0.99267 0 0.2396693 -0.9708546 0 0.3547195 -0.9349728 0 -0.239116 -0.970991 0 -0.3541151 -0.9352019 0 3.05185e-5 -1 0 -0.120582 -0.9927035 0 -0.5680589 -0.822988 0 -0.6629913 -0.7486271 0 -0.4645976 -0.8855219 0 -0.4646216 -0.8855094 0 -0.8853633 -0.4648997 0 -0.822762 -0.5683861 0 -0.748412 -0.6632341 0 -0.9708777 -0.2395759 0 -0.9926815 -0.1207624 0 -0.9708706 -0.2396047 0 -0.934993 -0.3546662 0 -0.9926961 0.1206421 0 -0.970991 0.239116 0 -0.8231229 0.5678635 0 -0.8854585 0.4647185 0 -0.9350754 0.354449 0 -0.9350855 0.3544224 0 -0.6633309 0.7483264 0 -0.567989 0.8230362 0 -0.7488574 0.6627313 0 -0.7488707 0.6627162 0 -0.3547297 0.9349689 0 -0.2396693 0.9708546 0 -0.4647424 0.885446 0 -0.1208563 0.99267 0 0.120582 0.9927035 0 -3.05185e-5 1 0 0.239116 0.970991 0 0.3541151 0.9352019 0 0.4645976 0.8855219 0 0.5680589 0.822988 0 0.6629913 0.7486271 0 0.748412 0.6632341 0 0.822762 0.5683861 0 0.8853633 0.4648997 0 0.934993 0.3546662 0 0.9708706 0.2396047 0 0.9926815 0.1207624 0 0.4647789 -0.8854268 0 -0.7484272 -0.6632171 0 -3.05194e-5 1 0 0.6630064 0.7486138 0 0.9708777 0.2395759 0 5.96579e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.67744e-7 0 1 0 0 1 0 0 1 -4.73643e-7 0 1 4.71371e-7 0 1 -6.61359e-7 0 1 4.69121e-7 0 1 8.36161e-7 0 1 -1.65382e-7 0 1 0 0 1 0 0 1 -9.41783e-7 0 1 3.31977e-7 0 1 4.71364e-7 0 1 2.85367e-7 0 1 0 0 1 0 0 1 -1.33073e-6 0 1 0 0 1 0 0 1 0 0 1 -2.54763e-6 0 1 0 0 1 -1.38494e-7 0 1 0 0 1 -6.04846e-7 0 1 -6.33985e-7 0 1 0 0 1 -3.20942e-7 0 1 4.12294e-7 0 1 -1.49398e-7 0 1 2.03342e-7 0 1 0 0 1 -7.5338e-7 0 1 0 0 1 1.16232e-6 0 1 4.85611e-7 0 1 6.45171e-7 0 1 -5.72002e-7 0 1 1.29102e-7 0 1 2.10126e-7 0 1 2.98435e-7 0 1 0 0 1 -2.63015e-7 0 1 -3.98877e-7 0 1 0 0 1 -6.96969e-7 0 1 -2.49682e-7 0 1 -1.38494e-7 0 1 0 0 1 -1.21133e-7 0 1 1.33073e-6 0 1 -2.38227e-7 0 1 0 0 1 -2.97181e-7 0 1 0 0 1 6.35273e-7 0 1 -2.22759e-7 0 1 4.58945e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.91421e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 4.20656e-7 0 1 -4.4755e-7 0 1 1.65372e-7 0 1 0 0 1 0 0 1 1.65176e-7 0 1 -2.37152e-7 0 1 0 0 1 1.84414e-7 0 1 0 0 1 0 0 1 2.74561e-7 0 1 4.20636e-7 0 1 0 0 1 0 0 1 3.31841e-7 0 1 -3.80845e-7 0 1 -1.22725e-7 0 1 0 0 1 -4.38375e-7 0 1 5.73681e-7 0 1 -2.18309e-7 0 1 0 0 1 -2.20393e-7 0 1 0 0 1 0 0 1 0 0 1 2.42266e-7 0 1 -1.33073e-6 0 1 3.57341e-7 0 1 3.36805e-7 0 1 1.38494e-7 0 1 2.0715e-7 0 1 0 0 1 6.04128e-7 0 1 9.56463e-7 0 1 -6.35274e-7 0 1 -2.67707e-7 0 1 0 0 1 3.04599e-7 0 1 0 0 1 0 0 -1 0 0 -1 -3.0194e-6 0 -1 -9.41783e-7 0 -1 0 0 -1 0 0 -1 -4.73643e-7 0 -1 4.69121e-7 0 -1 4.71371e-7 0 -1 -1.65382e-7 0 -1 -5.86439e-7 0 -1 0 0 -1 9.38847e-7 0 -1 2.07485e-7 0 -1 0 0 -1 1.23405e-7 0 -1 2.34991e-7 0 -1 2.35681e-7 0 -1 0 0 -1 2.85367e-7 0 -1 6.04e-7 0 -1 -1.33073e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.60528e-7 0 -1 0 0 -1 6.2238e-7 0 -1 -5.30895e-7 0 -1 -3.69968e-7 0 -1 -2.2098e-7 0 -1 2.12091e-7 0 -1 -5.007e-7 0 -1 -4.19401e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -3.71217e-7 0 -1 3.44939e-7 0 -1 3.33323e-7 0 -1 6.33996e-7 0 -1 -3.16501e-7 0 -1 1.22342e-6 0 -1 -2.67268e-7 0 -1 0 0 -1 3.04593e-7 0 -1 0 0 -1 0 0 -1 -1.35049e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.84129e-7 0 -1 -1.29054e-6 0 -1 -9.27468e-7 0 -1 -1.41351e-6 0 -1 1.5372e-6 0 -1 -7.5338e-7 0 -1 0 0 -1 1.16232e-6 0 -1 4.85611e-7 0 -1 6.45171e-7 0 -1 -5.72002e-7 0 -1 1.29102e-7 0 -1 2.10126e-7 0 -1 2.98435e-7 0 -1 0 0 -1 -6.04846e-7 0 -1 -2.63015e-7 0 -1 -3.98877e-7 0 -1 -6.96969e-7 0 -1 -2.49682e-7 0 -1 -1.38494e-7 0 -1 0 0 -1 -1.21133e-7 0 -1 1.33073e-6 0 -1 -2.38227e-7 0 -1 0 0 -1 -2.97181e-7 0 -1 0 0 -1 6.35273e-7 0 -1 -2.22759e-7 0 -1 4.58945e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.91421e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 4.20656e-7 0 -1 -4.4755e-7 0 -1 1.65372e-7 0 -1 0 0 -1 0 0 -1 1.65176e-7 0 -1 -2.37152e-7 0 -1 0 0 -1 1.84414e-7 0 -1 0.9926998 -0.1206121 0 0.8854776 -0.464682 0 0.9349829 -0.3546929 0 0.9709751 -0.2391806 0 0.9926815 -0.1207624 0 0.9708706 -0.2396047 3.0519e-5 0.7484272 -0.6632171 3.05194e-5 0.7488574 -0.6627313 0 0.8853952 -0.4648393 0 0.8228004 -0.5683305 3.05193e-5 0.8230987 -0.5678985 0 0.4646216 -0.8855094 0 0.3547195 -0.9349728 -6.10375e-5 0.567989 -0.8230362 3.0519e-5 0.6629913 -0.7486271 6.10377e-5 0.5680239 -0.8230121 0 0.120582 -0.9927035 3.05194e-5 0.2391448 -0.9709839 3.05187e-5 0.2396335 -0.9708635 0 0.3541151 -0.9352019 0 -0.2396335 -0.9708635 0 -0.2391448 -0.9709839 -3.05187e-5 -3.05185e-5 -1 0 -0.1208563 -0.99267 0 -0.120582 -0.9927035 -3.05194e-5 -0.5680239 -0.8230121 -3.05192e-5 -0.567989 -0.8230362 -3.0519e-5 -0.6629913 -0.7486271 -6.10377e-5 -0.3547195 -0.9349728 6.10375e-5 -0.4647789 -0.8854268 0 -0.8853826 -0.4648633 0 -0.8228004 -0.5683305 -3.05193e-5 -0.8230987 -0.5678985 0 -0.7488574 -0.6627313 0 -0.7484272 -0.6632171 -3.05194e-5 -0.6633309 -0.7483264 0 -0.9709751 -0.2391806 0 -0.9708706 -0.2396047 -3.0519e-5 -0.8854776 -0.464682 0 -0.9350754 -0.354449 0 -0.9349829 -0.3546929 0 -0.9926998 0.1206121 0 -0.9926736 0.1208263 0 -0.9709751 0.2391806 0 -0.9926998 -0.1206121 0 -0.8231995 0.5677523 -3.05194e-5 -0.8855411 0.4645612 0 -0.8853508 0.4649236 0 -0.9349829 0.3546929 0 -0.9350513 0.3545125 0 -0.9708706 0.2396047 3.0519e-5 -0.6630064 0.7486138 0 -0.5683305 0.8228004 -3.05193e-5 -0.6632341 0.748412 0 -0.8227763 0.5683655 3.05195e-5 -0.7484272 0.6632171 0 -0.7486271 0.6629913 0 -0.3547195 0.9349728 0 -0.3545125 0.9350513 0 -0.2396047 0.9708706 -3.0519e-5 -0.4649236 0.8853508 0 -0.5677729 0.8231853 3.05189e-5 -0.4645612 0.8855411 0 -0.1203377 0.9927331 0 -0.1207962 0.9926773 0 -0.238965 0.9710283 3.05192e-5 0.1203377 0.9927331 0 6.10389e-5 1 0 0.1208263 0.9926736 0 -6.1037e-5 1 0 0.2396047 0.9708706 3.0519e-5 0.238965 0.9710283 -3.05192e-5 0.3547195 0.9349728 0 0.3544859 0.9350615 0 0.4645612 0.8855411 0 0.4649236 0.8853508 0 0.5683305 0.8228004 3.05193e-5 0.5677729 0.8231853 -3.05189e-5 0.6632171 0.7484272 0 0.7484272 0.6632171 0 0.7486271 0.6629913 0 0.8231995 0.5677523 3.05194e-5 0.8227763 0.5683655 -3.05195e-5 0.8855411 0.4645612 0 0.8853508 0.4649236 0 0.9349829 0.3546929 0 0.9350513 0.3545125 0 0.9709839 0.2391448 0 0.9708706 0.2396047 -3.0519e-5 0.9926998 0.1206121 0 0.99267 0.1208563 0 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + -0.9847438 0.01528251 0.1733368 7.34404e-4 -0.1732838 0.004741894 -0.9848603 -7.57255e-4 -0.01587308 -0.9998723 -0.002021338 -7.00891e-5 0 0 0 1 + + + + + + + + + + -0.9592486 -0.0545002 0.277258 0.007883787 -0.2778881 0.004191671 -0.9606041 0.007483479 0.05119094 -0.9985053 -0.0191658 -0.001933447 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_tail.dae b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_tail.dae new file mode 100644 index 00000000..1588690c --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_tail.dae @@ -0,0 +1,89 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-04T12:02:35 + 2023-07-04T12:02:35 + + Z_UP + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + + + + + + + 0.05364465 -9.49699e-4 -0.01177817 0.04670375 -0.001456379 -0.01127147 0.08193737 -4.91641e-4 -0.01223629 0.123 -0.00789982 -0.004828035 0.08226495 -4.95118e-4 -0.01223278 0.03978276 -0.002114415 -0.0106135 0.08160555 -4.36537e-4 -0.01229137 0.07458567 -3.3778e-4 -0.01239007 0.06758558 -3.90389e-4 -0.01233744 0.06060516 -5.94362e-4 -0.01213359 0.02599996 -0.009541511 -0.003186345 0.02599996 -0.003884673 -0.008843183 0.03288149 -0.002923846 -0.00980401 0.109531 -0.001092791 -0.01163506 0.123 -0.001535832 -0.01119196 0.09605759 -7.29795e-4 -0.01199805 0.0825802 -4.4681e-4 -0.01228106 0.123 -0.00789982 -0.004828035 0.123 0.004828035 -0.004828035 0.123 -0.001535832 -0.01119196 0.123 -0.001535832 0.001535832 0.02599996 -0.009541511 -0.003186345 0.123 -0.001535832 0.001535832 0.123 -0.00789982 -0.004828035 0.02599996 -0.003177583 0.003177583 0.02599996 -0.003884673 -0.008843183 0.02599996 -0.003177583 0.003177583 0.02599996 -0.009541511 -0.003186345 0.02599996 0.002479255 -0.002479255 0.110471 0.005237162 -0.005237162 0.09789538 0.005588352 -0.005588352 0.109531 -0.001092791 -0.01163506 0.123 -0.001535832 -0.01119196 0.123 0.004828035 -0.004828035 0.09605759 -7.29795e-4 -0.01199805 0.08527415 0.005881667 -0.005881667 0.08326375 -1.8203e-4 -0.0120002 0.0829395 -3.36831e-4 -0.01216268 0.0825802 -4.4681e-4 -0.01228106 0.08379811 2.19771e-4 -0.01158487 0.08354979 6.30442e-6 -0.01180469 0.0841853 6.99516e-4 -0.01109468 0.0840097 4.52341e-4 -0.01134675 0.0844292 0.001226305 -0.01056146 0.08432447 9.58141e-4 -0.01083248 0.08449757 0.00149995 -0.01028585 0.08193737 -4.91641e-4 -0.01223629 0.116994 -4.69493e-4 0.187533 0.08160555 -4.36537e-4 -0.01229137 0.0812987 -3.23894e-4 -0.01218456 0.116663 -3.79193e-4 0.187592 0.116352 -2.31812e-4 0.187646 0.116071 -3.18309e-5 0.187696 0.08102166 -1.5569e-4 -0.01202148 0.115828 2.14674e-4 0.187739 0.08080637 3.99107e-5 -0.01182967 0.08063685 2.64059e-4 -0.01160836 0.115631 5.00214e-4 0.187774 0.0804367 7.4664e-4 -0.01112908 0.08051478 5.02735e-4 -0.01137167 0.115486 8.16116e-4 0.187799 0.08039158 0.001247942 -0.01062846 0.08039617 0.001000344 -0.01087599 0.115397 0.001152753 0.187815 0.115367 0.00149995 0.18782 0.08041995 0.00149995 -0.01037597 0.117336 -4.99965e-4 0.1874729 0.08226495 -4.95118e-4 -0.01223278 0.117678 -4.69676e-4 0.187413 0.0825802 -4.4681e-4 -0.01228106 0.11801 -3.79541e-4 0.187354 0.118321 -2.32289e-4 0.187299 0.0829395 -3.36831e-4 -0.01216268 0.08326375 -1.8203e-4 -0.0120002 0.08354979 6.30442e-6 -0.01180469 0.118603 -3.2386e-5 0.18725 0.118845 2.14101e-4 0.187207 0.08379811 2.19771e-4 -0.01158487 0.0840097 4.52341e-4 -0.01134675 0.0841853 6.99516e-4 -0.01109468 0.119042 4.9969e-4 0.1871719 0.08432447 9.58141e-4 -0.01083248 0.119188 8.15708e-4 0.187146 0.119277 0.001152515 0.187131 0.0844292 0.001226305 -0.01056146 0.119307 0.00149995 0.187125 0.08449757 0.00149995 -0.01028585 0.06940639 0.005919158 -0.005919158 0.07524526 0.01560199 0.00368762 0.06763356 0.0158149 0.004027724 0.08120369 0.005931198 -0.005931198 0.07390189 0.005954384 -0.005954384 0.08285719 0.01527398 0.003445982 0.03978276 -0.002114415 -0.0106135 0.04320675 0.00464189 -0.00464189 0.0403434 0.004354536 -0.004354536 0.04606837 0.004899978 -0.004899978 0.04670375 -0.001456379 -0.01127147 0.0489282 0.00512892 -0.00512892 0.05364465 -9.49699e-4 -0.01177817 0.05178618 0.005328536 -0.005328536 0.05464249 0.005498945 -0.005498945 0.06060516 -5.94362e-4 -0.01213359 0.05749696 0.005640149 -0.005640149 0.06320065 0.005834817 -0.005834817 0.0603497 0.005752086 -0.005752086 0.06604987 0.005888283 -0.005888283 0.06758558 -3.90389e-4 -0.01233744 0.0688973 0.005912542 -0.005912542 0.06995576 0 -0.01185148 0.08102166 -1.5569e-4 -0.01202148 0.07458567 -3.3778e-4 -0.01239007 0.0812987 -3.23894e-4 -0.01218456 0.06940639 0.005919158 -0.005919158 0.07046556 0 -0.01186245 0.07390189 0.005954384 -0.005954384 0.08120369 0.005931198 -0.005931198 0.08041995 0.00149995 -0.01037597 0.08039158 0.001247942 -0.01062846 0.08039617 0.001000344 -0.01087599 0.08080637 3.99107e-5 -0.01182967 0.08063685 2.64059e-4 -0.01160836 0.08051478 5.02735e-4 -0.01137167 0.0804367 7.4664e-4 -0.01112908 0.08160555 -4.36537e-4 -0.01229137 0.03747826 0.004037916 -0.004037916 0.03288149 -0.002923846 -0.00980401 0.0346114 0.00369209 -0.00369209 0.03174269 0.003317058 -0.003317058 0.02887219 0.002912759 -0.002912759 0.02599996 -0.003884673 -0.008843183 0.02599996 0.002479255 -0.002479255 0.004855811 -0.004152476 0.004152476 0.006338596 -0.003193378 0.003193378 0.005363702 0.006727933 0.01432716 0.02599996 0.002479255 -0.002479255 0.02794408 0.01392859 0.008349299 0.02632665 0.01370328 0.008638083 0.004247307 0.005636096 0.01484328 0.003520727 -0.005211293 0.005211293 0.003250777 0.004414498 0.0153234 0.00235188 -0.00637865 0.00637865 0.002392292 0.003068149 0.0157302 0.001680493 0.001610934 0.01602506 0.001114189 5.67419e-5 0.01616406 0.001367807 -0.007663309 0.007663309 6.89221e-4 -0.001543641 0.01610726 5.78153e-4 -0.009069919 0.009069919 3.975e-4 -0.003095984 0.01583784 2.08246e-4 -0.004552423 0.01536685 7.94791e-5 -0.006024479 0.01466035 0 -0.01060658 0.01060658 0 -0.007587611 0.0136255 0.006585597 0.007699131 0.01379847 0.00790137 0.00856167 0.01327204 0.007957279 -0.002328336 0.002328336 0.00929439 0.009324371 0.01275944 0.009696662 -0.001550137 0.001550137 0.01153707 -8.49478e-4 8.49478e-4 0.01072806 0.00998938 0.01227408 0.01346468 -2.19712e-4 2.19712e-4 0.0121932 0.01057046 0.01181739 0.01523208 0.01154375 0.01097506 0.01369649 0.01108574 0.01138454 0.01546728 3.44905e-4 -3.44905e-4 0.01678478 0.01195019 0.01058989 0.01752418 8.54273e-4 -8.54273e-4 0.01833379 0.01230978 0.01023018 0.01989948 0.01263487 0.009888052 0.01961976 0.001315772 -0.001315772 0.02149128 0.01293325 0.009558677 0.02174454 0.001733958 -0.001733958 0.02387189 0.002121508 -0.002121508 0.0230928 0.01320749 0.009242534 0.02470445 0.01346278 0.008936464 0.02956467 0.01414018 0.008068859 0.02887219 0.002912759 -0.002912759 0.0344159 0.01469177 0.007284581 0.03280079 0.01452147 0.007536411 0.0346114 0.00369209 -0.00369209 0.03174269 0.003317058 -0.003317058 0.03118366 0.01433765 0.007797837 0.03747826 0.004037916 -0.004037916 0.03927749 0.01512819 0.006583273 0.0376479 0.01499438 0.006808876 0.03602838 0.01484906 0.007042527 0.0403434 0.004354536 -0.004354536 0.04320675 0.00464189 -0.00464189 0.04254186 0.01535987 0.00616002 0.04090875 0.01524984 0.006367027 0.04581886 0.0155462 0.005772709 0.04606837 0.004899978 -0.004899978 0.04742968 0.0156216 0.005595743 0.04417657 0.01545846 0.005962133 0.0506196 0.01574105 0.005270659 0.0489282 0.00512892 -0.00512892 0.05178618 0.005328536 -0.005328536 0.04902327 0.01568615 0.005429208 0.05749696 0.005640149 -0.005640149 0.05546718 0.01585245 0.004837214 0.05464249 0.005498945 -0.005498945 0.05384147 0.01582407 0.004974782 0.05222558 0.015787 0.005119264 0.05874776 0.0158841 0.004582107 0.05710256 0.01587235 0.004706382 0.0603497 0.005752086 -0.005752086 0.06040287 0.01588767 0.004464328 0.06320065 0.005834817 -0.005834817 0.06206768 0.01588326 0.004352867 0.06604987 0.005888283 -0.005888283 0.06374228 0.01587116 0.004247546 0.0671209 0.01582449 0.004054784 0.0654267 0.01585155 0.004148244 0.0688973 0.005912542 -0.005912542 0 -0.009119987 0.01227635 0 -0.01060658 0.01060658 0 -0.007587611 0.0136255 0.15 -0.005303263 0.005303263 0.15 -0.001060605 0.001060605 0.132 -0.001060605 0.001060605 0.123 0.004828035 -0.004828035 0.123 -0.001535832 0.001535832 0.01346468 -2.19712e-4 2.19712e-4 0.01153707 -8.49478e-4 8.49478e-4 0.02599996 -0.003177583 0.003177583 0.01752418 8.54273e-4 -8.54273e-4 0.01546728 3.44905e-4 -3.44905e-4 0.009696662 -0.001550137 0.001550137 0.006338596 -0.003193378 0.003193378 0.004855811 -0.004152476 0.004152476 0.003520727 -0.005211293 0.005211293 0.00235188 -0.00637865 0.00637865 0.001367807 -0.007663309 0.007663309 5.78153e-4 -0.009069919 0.009069919 0 -0.01060658 0.01060658 0.01961976 0.001315772 -0.001315772 0.02387189 0.002121508 -0.002121508 0.02174454 0.001733958 -0.001733958 0.132 0.004596173 -0.004596173 0.02599996 0.002479255 -0.002479255 0.007957279 -0.002328336 0.002328336 0.15 -0.001060605 0.001060605 0.15 0.002864181 0.006189346 0.15 0.003775954 0.005897283 0.15 0.001031339 0.006596386 0.15 0.001948714 0.00642538 0.15 -8.03212e-4 0.006715893 0.15 1.13457e-4 0.006696164 0.15 -0.002624809 0.006476879 0.15 -0.001716494 0.006645381 0.15 -0.004419744 0.00581336 0.15 -0.003526866 0.006204128 0.15 -0.005303263 0.005303263 0.132 0.004632115 0.006753444 0.132 -0.001060605 0.001060605 0.15 0.003775954 0.005897283 0.15 -0.001060605 0.001060605 0.132 0.004596173 -0.004596173 0.132 0.01000005 0.00401932 0.132 0.01100599 0.003417253 0.132 0.01198929 0.002796888 0.132 0.008971571 0.004602909 0.132 0.007920563 0.005168139 0.132 -0.001060605 0.001060605 0.132 0.006847023 0.005714952 0.132 0.005750834 0.006243407 0.132 0.004632115 0.006753444 0.123 0.004828035 -0.004828035 0.109449 0.01355946 0.003052294 0.110471 0.005237162 -0.005237162 0.132 0.01198929 0.002796888 0.132 0.004596173 -0.004596173 0.09789538 0.005588352 -0.005588352 0.0869019 0.01506096 0.003349661 0.08527415 0.005881667 -0.005881667 0.06075406 0 0.04262727 0.06995576 0 -0.01185148 0.07046556 0 -0.01186245 0.05956 0 0.04647755 0.06616878 0 0.04359239 0.06546688 0 0.04753029 0.06005698 0 0.06078678 0.05953055 0 0.06374019 0.05559265 0 0.0630384 0.05611908 0 0.06008487 0.119307 0.00149995 0.187125 0.1114405 0.003309965 0.1425159 0.1193066 0.002980291 0.187125 0.1156294 0.003135144 0.1662725 0.1077931 0.003460764 0.1218289 0.1052196 0.003566384 0.1072345 0.1021732 0.0036906 0.08995777 0.08449757 0.00149995 -0.01028585 0.09846532 0.003840506 0.06892961 0.09529346 0.003967702 0.05094069 0.09220796 0.004090547 0.03344213 0.08803856 0.004255056 0.009795904 0.08527415 0.005881667 -0.005881667 0.08748179 0.01038706 0.006638526 0.0876125 0.009196758 0.007379829 0.08734536 0.01156866 0.005864799 0.087848 0.006769239 0.008715331 0.0877375 0.007997751 0.008088886 0.08720326 0.01274144 0.005058765 0.08794826 0.005521655 0.009284377 0.08705538 0.01390558 0.004220366 0.0869019 0.01506096 0.003349661 0.116355 0.003041684 0.187646 0.115367 0.003053009 0.18782 0.115367 0.00149995 0.18782 0.117341 0.00302577 0.187472 0.115397 0.001152753 0.187815 0.115486 8.16116e-4 0.187799 0.115631 5.00214e-4 0.187774 0.117678 -4.69676e-4 0.187413 0.11801 -3.79541e-4 0.187354 0.116663 -3.79193e-4 0.187592 0.118321 -2.32289e-4 0.187299 0.116071 -3.18309e-5 0.187696 0.116352 -2.31812e-4 0.187646 0.116994 -4.69493e-4 0.187533 0.117336 -4.99965e-4 0.1874729 0.118603 -3.2386e-5 0.18725 0.115828 2.14674e-4 0.187739 0.118845 2.14101e-4 0.187207 0.119042 4.9969e-4 0.1871719 0.119188 8.15708e-4 0.187146 0.119277 0.001152515 0.187131 0.119307 0.00149995 0.187125 0.118325 0.003005266 0.187299 0.119307 0.002980232 0.187125 0.0840103 0.00446856 0.009985446 0.08378636 0.007312119 0.008716046 0.08120369 0.005931198 -0.005931198 0.08041995 0.00149995 -0.01037597 0.08351349 0.01004129 0.007168531 0.08766794 0.004325747 0.03072935 0.08319729 0.01267427 0.005375146 0.08975249 0.004241645 0.04255145 0.08557856 0.004408061 0.01888012 0.09183406 0.004155814 0.05435627 0.0934174 0.004089176 0.06333619 0.09499293 0.004021883 0.07227152 0.09706866 0.003931522 0.08404326 0.1002016 0.003791511 0.1018109 0.0986436 0.003861606 0.09297537 0.1023163 0.003694593 0.1138048 0.115367 0.00149995 0.18782 0.104407 0.003596842 0.1256601 0.1064793 0.003498017 0.1374167 0.1096413 0.003343701 0.1553462 0.108051 0.003421843 0.146326 0.1117193 0.00323987 0.1671317 0.1137858 0.003134787 0.178851 0.115367 0.003053009 0.18782 0.08285719 0.01527398 0.003445982 0.06694799 0.01071798 0.007874548 0.06727916 0.01329594 0.006015777 0.07521235 0.01238286 0.006124436 0.0666579 0.008030533 0.009501755 0.07521235 0.008626163 0.008588492 0.07037627 0.005079865 0.01065886 0.08351349 0.01004129 0.007168531 0.08319729 0.01267427 0.005375146 0.08378636 0.007312119 0.008716046 0.07686537 0.00481075 0.01033109 0.0791741 0.004704833 0.0102179 0.08155578 0.004590749 0.01010268 0.0840103 0.00446856 0.009985446 0.06763356 0.0158149 0.004027724 0.07524526 0.01560199 0.00368762 0.08285719 0.01527398 0.003445982 0.07246649 0.004998266 0.01055157 0.06641459 0.005218625 0.01086735 0.06835895 0.005153298 0.01076406 0.07462948 0.004908561 0.01044237 0.06075406 0 0.04262727 0.06568127 0.0052284 0.01498144 0.06495535 0.005232214 0.01905447 0.06143587 0.005162715 0.03880149 0.06075406 0.005131065 0.04262727 0.06282168 0.005208253 0.03102618 0.06212508 0.005188405 0.03493446 0.06423676 0.005230128 0.02308619 0.06352555 0.005222141 0.02707678 0.07046556 0 -0.01186245 0.06641459 0.005218625 0.01086735 0.06940639 0.005919158 -0.005919158 0.06694799 0.01071798 0.007874548 0.06727916 0.01329594 0.006015777 0.0666579 0.008030533 0.009501755 0.06763356 0.0158149 0.004027724 0.06616878 0 0.04359239 0.0643692 0.005084693 0.04327166 0.06616878 0.005053162 0.04359239 0.06256425 0.005110621 0.04294997 0.06075406 0 0.04262727 0.06075406 0.005131065 0.04262727 0.06546688 0 0.04753029 0.06616878 0.005053162 0.04359239 0.06546688 0.005031585 0.04753029 0.06616878 0 0.04359239 0.06005698 0 0.06078678 0.05809617 0.004871547 0.06043726 0.06005698 0.004887342 0.06078678 0.05611908 0.00484538 0.06008487 0.05611908 0 0.06008487 0.05956 0 0.04647755 0.06103885 0.005082786 0.04674106 0.05956 0.005091726 0.04647755 0.06251347 0.005069732 0.04700386 0.06251347 0 0.04700386 0.06995576 0 -0.01185148 0.06590175 0.005235254 0.01089489 0.0688973 0.005912542 -0.005912542 0.06614279 0.00802201 0.009542644 0.06628137 0.00937581 0.008764863 0.06601625 0.006641805 0.01025259 0.06643205 0.01070326 0.00791943 0.06659489 0.01200437 0.007006227 0.06676429 0.01329076 0.006055653 0.06032007 0.005137145 0.04221236 0.05956 0 0.04647755 0.05956 0.005091726 0.04647755 0.06693899 0.01456558 0.005075395 0.06108957 0.005174696 0.03789496 0.06186825 0.005204439 0.03352534 0.0626564 0.005226254 0.02910369 0.06345379 0.005240261 0.02462977 0.06507647 0.005244791 0.0155254 0.06426048 0.00524646 0.02010369 0.0671209 0.01582449 0.004054784 0.08592575 -0.004368782 0.009873569 0.1125 -0.004295527 0.008202493 0.132 0.004632115 0.006753444 0.15 0.003775954 0.005897283 0.1125 0.004281222 0.008172452 0.08794826 0.005521655 0.009284377 0.08803856 0.004254937 0.009795963 0.03115618 -0.005204081 0.01304197 0.03160196 -0.005225777 0.01300138 7.94791e-5 -0.006024479 0.01466035 0.100906 0.003484904 0.009223163 0.09876197 0.003620922 0.009320735 0.1125 0.005501031 0.007676541 0.1125 0.003051459 0.008577227 0.105193 0.00320363 0.009025454 0.10305 0.003345787 0.009124696 0.06693899 0.01456558 0.005075395 0.05384147 0.01582407 0.004974782 0.05546718 0.01585245 0.004837214 0.113764 0.002604126 0.008619904 0.111622 0.002758622 0.008722543 0.15 0.002864181 0.006189346 0.15 0.001948714 0.00642538 0.115906 0.002446532 0.008516371 0.120189 0.002122163 0.00830686 0.118048 0.002285897 0.008412063 0.124472 0.001785457 0.008093893 0.122331 0.00195533 0.008200824 0.15 0.001031339 0.006596386 0.128753 0.001436471 0.007877588 0.126612 0.001612544 0.007986187 0.133033 0.001075208 0.007657885 0.130893 0.001257359 0.007768154 0.135173 8.89953e-4 0.007546782 0.1373119 7.01612e-4 0.007434785 0.15 1.13457e-4 0.006696164 0.139452 5.10193e-4 0.007322013 0.143729 1.18126e-4 0.007093846 0.141591 3.15698e-4 0.007208347 0.1437309 -1.18051e-4 0.007105767 0.15 -8.03212e-4 0.006715893 0.1411383 -3.5664e-4 0.007276237 0.1424635 -2.3488e-4 0.007189929 0.1398314 -4.761e-4 0.007359683 0.1384984 -5.97129e-4 0.007443249 0.1370895 -7.23795e-4 0.007529497 0.1360778 -8.13943e-4 0.007590413 0.1347579 -9.30185e-4 0.007668435 0.1332579 -0.001060366 0.007755398 0.1314665 -0.001213312 0.007856726 0.15 -0.001716494 0.006645381 0.1301218 -0.001326262 0.007930934 0.1288264 -0.001433908 0.008001327 0.1270604 -0.001578748 0.008095145 0.1254768 -0.001706838 0.00817734 0.1242119 -0.001808106 0.008241832 0.1230031 -0.001903891 0.00830239 0.1217789 -0.002000093 0.008362889 0.1201832 -0.002123892 0.008440256 0.1188231 -0.002228081 0.008505105 0.15 -0.002624809 0.006476879 0.1175502 -0.002324461 0.008564651 0.116247 -0.002422034 0.008624911 0.1144619 -0.00255382 0.008705973 0.1131295 -0.002650678 0.00876528 0.1125 -0.003096282 0.008677899 0.1117628 -0.002749025 0.008825719 0.1101953 -0.002860188 0.008893907 0.1088704 -0.002952933 0.00895071 0.1075339 -0.00304538 0.009007453 0.1060296 -0.003148078 0.009070515 0.1042343 -0.003268718 0.009144842 0.15 -0.003526866 0.006204128 0.1024435 -0.003386914 0.009218096 0.1011083 -0.00347352 0.009272158 0.09996247 -0.003547012 0.009318292 0.09885752 -0.003616988 0.009362518 0.09753841 -0.003699481 0.00941509 0.09623432 -0.003779709 0.009466886 0.09487271 -0.003862261 0.009520709 0.09330314 -0.003955662 0.0095824 0.09173476 -0.004047155 0.009644031 0.09017026 -0.004136443 0.009705662 0.08883357 -0.004211187 0.009758412 0.08747422 -0.004285693 0.009812176 0.08437001 -0.004450023 0.009935617 0.08324223 -0.004507601 0.009980857 0.15 -0.005303263 0.005303263 0.1125 -0.005474567 0.007524788 0.15 -0.004419744 0.00581336 0.0821523 -0.004562258 0.01002478 0.08123016 -0.004607558 0.01006215 0.07499998 -0.005191922 0.01015657 0.08029627 -0.004652738 0.0101003 0.07912778 -0.004708051 0.01014834 0.07820057 -0.004751026 0.01018679 0.07716351 -0.004798114 0.01023006 0.07604736 -0.004847586 0.01027715 0.07499998 -0.006592154 0.009203672 0.07500654 -0.004892647 0.01032143 0.07380878 -0.004943013 0.01037287 0.07268375 -0.004989087 0.01042187 0.07162708 -0.005031049 0.01046836 0.07073175 -0.005065679 0.01050817 0.06979554 -0.005100846 0.0105502 0.06870466 -0.005140602 0.01059997 0.06739401 -0.005186378 0.0106607 0.06602662 -0.005231857 0.01072525 0.1125 -0.006629109 0.006629109 0.06465005 -0.00527507 0.01079165 0.06354343 -0.005307912 0.01084595 0.06269097 -0.005332112 0.01088839 0.06158024 -0.005362033 0.01094448 0.06065255 -0.005385577 0.01099246 0.05999583 -0.005401551 0.01102674 0.05816555 -0.00544238 0.01112425 0.05906629 -0.005422949 0.01107579 0.03749996 -0.009280741 0.009280741 0 -0.01060658 0.01060658 0 -0.009119987 0.01227635 0.05729293 -0.005459964 0.01117187 0.05639791 -0.005476593 0.01122146 0.05555278 -0.005491077 0.01126909 0.05483675 -0.005502343 0.0113101 0.03749996 -0.007709741 0.01088249 0.03749996 -0.006088376 0.01211076 0.05416101 -0.005512177 0.01134926 0.05324554 -0.005524158 0.01140308 0.05233693 -0.00553441 0.01145744 0.05170559 -0.005540609 0.01149576 0.05099451 -0.005546689 0.01153945 0.05036389 -0.005551218 0.01157879 0.04969698 -0.005555152 0.01162087 0.04881018 -0.005558967 0.01167762 0.04792046 -0.005561113 0.01173555 0.04657655 -0.005561053 0.01182496 0.04723346 -0.00556153 0.01178097 0.04567974 -0.005558788 0.011886 0.04477268 -0.005554556 0.0119487 0.04410398 -0.005550086 0.01199579 0.04344946 -0.005544781 0.0120424 0.04207915 -0.00552994 0.01214206 0.04276305 -0.005537927 0.01209199 0.04142248 -0.005520999 0.01219075 0.04074484 -0.005510568 0.01224178 0.03988742 -0.005495488 0.01230722 0.03807544 -0.005456209 0.0124495 0.03897392 -0.005476951 0.01237827 0.03716534 -0.005432605 0.01252287 0 -0.007587611 0.0136255 0.0362823 -0.005407094 0.01259541 0.03539377 -0.005378842 0.01266968 0.03427785 -0.005339324 0.01276475 0.03472405 -0.005355596 0.01272648 0.03383177 -0.005322277 0.01280337 0.03338569 -0.005304515 0.01284229 0.03293967 -0.005286037 0.01288157 0.03249365 -0.005266726 0.01292115 0.03204774 -0.005246639 0.01296108 0.03026497 -0.005158126 0.01312416 0.03071057 -0.005181491 0.01308286 0.029374 -0.005108594 0.01320785 0.02981936 -0.005133807 0.01316589 0.02848339 -0.005055308 0.01329284 0.02892857 -0.005082428 0.01325017 0.02714818 -0.004967927 0.01342308 0.02759307 -0.004998087 0.01337927 0.0280382 -0.005027174 0.01333588 0.02625846 -0.004904448 0.01351159 0.02670329 -0.004936695 0.01346719 0.0253694 -0.004836499 0.0136016 0.02581387 -0.00487107 0.01355636 0.02448076 -0.004763782 0.01369297 0.02492499 -0.004800736 0.01364707 0.0240367 -0.004725515 0.01373928 2.08246e-4 -0.004552423 0.01536685 0.02314895 -0.00464493 0.01383298 0.02359277 -0.004685878 0.01378595 0.02226197 -0.004558682 0.01392817 0.02270537 -0.004602491 0.01388037 0.02137577 -0.004466414 0.01402467 0.02181875 -0.004513323 0.01397627 0.02049028 -0.004367828 0.01412254 0.02093285 -0.004417955 0.01407349 0.01960575 -0.004262566 0.01422178 0.02004796 -0.004316091 0.01417195 0.01872235 -0.004150211 0.01432228 0.01916396 -0.004207313 0.01427185 0.01739925 -0.003966987 0.01447516 0.01783996 -0.004030108 0.01442396 0.01828098 -0.004091143 0.014373 0.01651895 -0.003834187 0.01457846 0.01695895 -0.00390172 0.01452666 0.01564037 -0.003691315 0.01468294 0.01607948 -0.003764152 0.01463055 3.975e-4 -0.003095984 0.01583784 0.01520198 -0.00361526 0.01473575 0.01432716 -0.003451883 0.01484268 0.01476418 -0.003535568 0.01478898 0.01345604 -0.003271222 0.01495134 0.01389116 -0.003363847 0.01489686 0.01258939 -0.003071546 0.01506137 0.01302218 -0.003173828 0.0150063 0.01172739 -0.00285232 0.01517164 0.01215779 -0.002964377 0.01511645 0.0104441 -0.002486944 0.0153352 0.01087039 -0.002613782 0.01528108 0.01129829 -0.002735435 0.0152266 0.009598076 -0.00221157 0.01544225 0.01001936 -0.002354085 0.01538878 0.009183168 -0.002050995 0.01549637 6.89221e-4 -0.001543641 0.01610726 0.008388161 -0.001653194 0.01560568 0.008779346 -0.00186479 0.01555126 0.007328987 -8.45326e-4 0.01575028 0.007655203 -0.001149177 0.01570695 0.00801146 -0.001416087 0.01565819 0.001114189 5.67419e-5 0.01616406 0.006915926 -6.86681e-5 0.01579999 0.007059991 -4.89649e-4 0.01578408 0.00723505 7.43052e-4 0.0157541 0.001680493 0.001610934 0.01602506 0.007547557 0.001060664 0.01571059 0.006996273 3.67003e-4 0.01578736 0.01031059 0.002446711 0.01534616 0.002392292 0.003068149 0.0157302 0.01073688 0.002575159 0.01529455 0.009054124 0.001997113 0.01550257 0.008653759 0.001803398 0.01555639 0.003250777 0.004414498 0.0153234 0.01375818 0.003334224 0.01493358 0.01245588 0.003038048 0.01508718 0.01202416 0.002929568 0.01513898 0.01726877 0.003944277 0.01454395 0.01770985 0.004007935 0.01449686 0.01594775 0.003739595 0.014687 0.01550847 0.003665983 0.0147354 0.02213585 0.00454092 0.01404345 0.004247307 0.005636096 0.01484328 0.02257966 0.004585146 0.01399987 0.01991987 0.004296243 0.01426625 0.01947724 0.00424236 0.01431179 0.02791655 0.005013823 0.01350116 0.0274713 0.004984438 0.0135411 0.02569067 0.004856169 0.01370358 0.0252459 0.0048213 0.01374495 0.02880769 0.005069673 0.01342219 0.02836209 0.005042254 0.01346147 0.02969896 0.005121648 0.01334428 0.0292533 0.005096137 0.01338309 0.005363702 0.006727933 0.01432716 0.03103655 0.005192697 0.01322954 0.03059065 0.005169868 0.01326745 0.03014475 0.005146205 0.01330578 0.03192865 0.005235791 0.01315426 0.03148257 0.005214691 0.01319175 0.03282088 0.005275726 0.01308017 0.03326719 0.005294501 0.01304346 0.03237479 0.005256175 0.01311707 0.03482335 0.005354166 0.01291733 0.03415977 0.005329787 0.0129708 0.0337134 0.005312502 0.01300698 0.03749996 0.005949974 0.01250088 0.03570628 0.005384147 0.01284718 0.0671209 0.01582449 0.004054784 0.0654267 0.01585155 0.004148244 0.03707915 0.005425512 0.01273989 0.03639209 0.005405485 0.0127933 0.06374228 0.01587116 0.004247546 0.06206768 0.01588326 0.004352867 0.06040287 0.01588767 0.004464328 0.03795468 0.005448639 0.0126726 0.03862535 0.005464613 0.0126217 0.05710256 0.01587235 0.004706382 0.05874776 0.0158841 0.004582107 0.03928691 0.005479156 0.01257199 0.05222558 0.015787 0.005119264 0.0506196 0.01574105 0.005270659 0.04902327 0.01568615 0.005429208 0.04742968 0.0156216 0.005595743 0.04581886 0.0155462 0.005772709 0.06676429 0.01329076 0.006055653 0.04018145 0.005496621 0.01250547 0.04417657 0.01545846 0.005962133 0.04254186 0.01535987 0.00616002 0.04090875 0.01524984 0.006367027 0.03927749 0.01512819 0.006583273 0.0376479 0.01499438 0.006808876 0.03602838 0.01484906 0.007042527 0.0408594 0.005508244 0.0124557 0.03749996 0.01416695 0.007470309 0.06659489 0.01200437 0.007006227 0.0344159 0.01469177 0.007284581 0.02956467 0.01414018 0.008068859 0.03118366 0.01433765 0.007797837 0.04155451 0.005518913 0.01240515 0.04240858 0.005530118 0.01234376 0.02794408 0.01392859 0.008349299 0.03749996 0.01261216 0.008633792 0.02632665 0.01370328 0.008638083 0.04309409 0.005537629 0.01229494 0.06643205 0.01070326 0.00791943 0.04375547 0.005543828 0.01224839 0.02149128 0.01293325 0.009558677 0.0230928 0.01320749 0.009242534 0.03749996 0.01100444 0.009745359 0.01989948 0.01263487 0.009888052 0.04443508 0.005548894 0.01220095 0.04511791 0.005553007 0.0121538 0.04643774 0.005557656 0.01206386 0.04577624 0.005555808 0.01210868 0.01833379 0.01230978 0.01023018 0.01523208 0.01154375 0.01097506 0.03749996 0.009352505 0.01077824 0.01369649 0.01108574 0.01138454 0.06628137 0.00937581 0.008764863 0.04711765 0.005558431 0.01201808 0.04779624 0.005558311 0.0119729 0.06614279 0.00802201 0.009542644 0.04914206 0.005555033 0.01188433 0.04845905 0.005557119 0.01192909 0.006585597 0.007699131 0.01379847 0.03749996 0.007664799 0.01170569 0.01072806 0.00998938 0.01227408 0.00929439 0.009324371 0.01275944 0.05001699 0.005550861 0.01182758 0.05091077 0.00554496 0.01177036 0.05176323 0.005537807 0.01171624 0.06601625 0.006641805 0.01025259 0.05248385 0.005530655 0.01167106 0.05316102 0.005523085 0.01162898 0.05403381 0.005511999 0.01157516 0.05493575 0.005499124 0.01152014 0.05582946 0.005484819 0.01146638 0.05650919 0.005473017 0.01142579 0.0571748 0.005460739 0.01138633 0.05785095 0.005447447 0.01134657 0.05852127 0.005433559 0.01130747 0.05919277 0.005418896 0.01126855 0.05986374 0.005403578 0.01123005 0.06075292 0.00538212 0.01117932 0.06184828 0.005354106 0.01111751 0.06299382 0.005322873 0.01105368 0.06385254 0.005298197 0.01100629 0.06473648 0.005271792 0.01095795 0.06590181 0.005235314 0.01089483 0.107336 0.003058373 0.008925318 0.09447336 0.003883779 0.009513378 0.09232866 0.004010558 0.009608387 0.09661775 0.0037539 0.009417474 0.09018379 0.004134297 0.009702622 0.087848 0.006769239 0.008715331 0.132 0.005750834 0.006243407 0.1125 0.006706595 0.00710529 0.0869019 0.01506096 0.003349661 0.109449 0.01355946 0.003052294 0.1125 0.01236915 0.003674089 0.02702599 0.00495398 0.01358127 0.02658075 0.004922449 0.01362174 0.02613568 0.004889845 0.01366257 0.02480119 0.00478518 0.01378667 0.02391207 0.004709243 0.01387095 0.0243566 0.004747867 0.01382869 0.02346777 0.004669249 0.01391369 0.02302366 0.004627883 0.01395654 0.02169227 0.004495143 0.01408737 0.02080565 0.004398941 0.01417618 0.02124887 0.004447817 0.01413166 0.02036255 0.004348456 0.01422107 0.01903498 0.00418663 0.01435768 0.01859295 0.004128992 0.01440376 0.01815128 0.004069447 0.01445019 0.01682806 0.003878474 0.01459127 0.0163877 0.003810346 0.01463896 0.01506966 0.003588974 0.01478415 0.01419448 0.003423511 0.01488327 0.01463168 0.003508269 0.01483345 0.01332294 0.003240287 0.01498436 0.01288884 0.003141582 0.01503568 0.01159375 0.002816259 0.01519078 0.01116454 0.002698063 0.01524275 0.009886384 0.002311766 0.01539766 0.00946635 0.002164661 0.01544946 0.008266806 0.001583874 0.01560997 0.007895648 0.001338362 0.01566189 0.0877375 0.007997751 0.008088886 0.1125 0.007893502 0.006474614 0.132 0.006847023 0.005714952 0.0876125 0.009196758 0.007379829 0.1125 0.009057521 0.005800247 0.132 0.007920563 0.005168139 0.1125 0.01129966 0.00438416 0.1125 0.01019436 0.005098164 0.08720326 0.01274144 0.005058765 0.08734536 0.01156866 0.005864799 0.132 0.008971571 0.004602909 0.08705538 0.01390558 0.004220366 0.132 0.01000005 0.00401932 0.132 0.01198929 0.002796888 0.132 0.01100599 0.003417253 0.03280079 0.01452147 0.007536411 0.08748179 0.01038706 0.006638526 0.02470445 0.01346278 0.008936464 0.01678478 0.01195019 0.01058989 0.0121932 0.01057046 0.01181739 0.00790137 0.00856167 0.01327204 0.109479 0.002910017 0.008824348 0.07499998 -0.007954895 0.007954895 0.1437309 -1.18072e-4 0.007105708 0.1445469 1.15888e-4 0.0150519 0.143729 1.18126e-4 0.007093846 0.144547 -1.15784e-4 0.0150519 0.1443499 0.001376092 0.163223 0.142936 0.001482248 0.163128 0.1443499 -0.001376569 0.163223 0.138695 -0.001788914 0.162843 0.138695 0.001788437 0.162843 0.137281 0.001886427 0.162748 0.145763 0.00126791 0.163317 0.145763 -0.001268386 0.163317 0.147176 -0.001158177 0.163412 0.147176 0.001157701 0.163412 0.148589 -0.001045882 0.163507 0.148589 0.001045465 0.163507 0.150002 9.31158e-4 0.1636019 0.150002 -9.31629e-4 0.1636019 0.151414 -8.15285e-4 0.163697 0.151414 8.14812e-4 0.163697 0.152827 -6.96901e-4 0.163792 0.152827 6.96426e-4 0.163792 0.1542389 5.75999e-4 0.163886 0.1542389 -5.76477e-4 0.163886 0.155651 -4.54012e-4 0.163981 0.155651 4.53533e-4 0.163981 0.157063 -3.29507e-4 0.164076 0.157063 3.29026e-4 0.164076 0.158475 2.0248e-4 0.164171 0.158475 -2.02961e-4 0.164171 0.159887 -7.43762e-5 0.164265 0.159887 7.38935e-5 0.164265 0.142936 -0.001482725 0.163128 0.141523 0.001586377 0.163033 0.140109 0.00168842 0.1629379 0.141523 -0.001586794 0.163033 0.140109 -0.001688897 0.1629379 0.137281 -0.001886844 0.162748 0.1358669 0.00198239 0.162653 0.1358669 -0.001982808 0.162653 0.134452 0.002076327 0.162558 0.1344529 -0.002076685 0.162558 0.133038 -0.002168595 0.162463 0.133038 0.002168178 0.162463 0.131623 0.002258002 0.1623679 0.131623 -0.00225836 0.1623679 0.130209 0.0023458 0.162274 0.130209 -0.002346158 0.162274 0.128794 -0.002431929 0.1621789 0.128794 0.002431511 0.1621789 0.127379 0.002515256 0.162084 0.127379 -0.002515614 0.162084 0.125963 0.002596914 0.161989 0.125963 -0.002597272 0.161989 0.152137 1.47785e-4 0.21 0.152136 -1.47485e-4 0.21 0.1520259 -6.21574e-5 0.21 0.154053 -4.5909e-4 0.21 0.154053 4.5911e-4 0.21 0.154193 4.66857e-4 0.21 0.152027 6.25472e-5 0.21 0.1522639 -2.03533e-4 0.21 0.152397 -2.42911e-4 0.21 0.152398 2.4308e-4 0.21 0.1522639 2.03673e-4 0.21 0.1525329 2.7706e-4 0.21 0.152669 3.06199e-4 0.21 0.1525329 -2.76911e-4 0.21 0.152806 3.3111e-4 0.21 0.152669 -3.06185e-4 0.21 0.152806 -3.31012e-4 0.21 0.152944 3.52574e-4 0.21 0.153082 3.7143e-4 0.21 0.152944 -3.52414e-4 0.21 0.1532199 3.88411e-4 0.21 0.153082 -3.71401e-4 0.21 0.1532199 -3.88431e-4 0.21 0.1533589 4.03737e-4 0.21 0.1534979 4.17479e-4 0.21 0.153358 -4.03716e-4 0.21 0.153636 4.29731e-4 0.21 0.153497 -4.1741e-4 0.21 0.153636 -4.29662e-4 0.21 0.153775 4.40647e-4 0.21 0.153914 4.50395e-4 0.21 0.153775 -4.40606e-4 0.21 0.153914 -4.50377e-4 0.21 0.154192 -4.66826e-4 0.21 0.154332 4.73697e-4 0.21 0.154331 -4.73661e-4 0.21 0.154471 4.79692e-4 0.21 0.15447 -4.79664e-4 0.21 0.1546791 -4.87303e-4 0.21 0.1546783 4.87296e-4 0.21 0.1549589 4.94998e-4 0.21 0.1549519 -4.94842e-4 0.21 0.155231 5.00023e-4 0.21 0.1552342 -5.00065e-4 0.21 0.1555135 -5.02912e-4 0.21 0.1555128 5.0291e-4 0.21 0.155724 5.0365e-4 0.21 0.155724 -5.03651e-4 0.21 0.1617258 2.40584e-4 0.2072946 0.1618072 -2.35608e-4 0.2072131 0.1615999 -2.51977e-4 0.20744 0.161568 2.53097e-4 0.207467 0.1613758 2.68044e-4 0.2076617 0.1613997 -2.67271e-4 0.2076408 0.1610007 -2.97096e-4 0.2080042 0.1610877 2.89423e-4 0.2079241 0.1607224 3.15746e-4 0.2082311 0.1606371 -3.23154e-4 0.2083075 0.160376 -3.41085e-4 0.208506 0.160398 3.38696e-4 0.208485 0.1601949 3.52669e-4 0.208635 0.160197 -3.53172e-4 0.2086319 0.160022 -3.64896e-4 0.208746 0.160015 3.64429e-4 0.208756 0.1597926 -3.79557e-4 0.2088868 0.1594048 -4.02712e-4 0.2091026 0.1595583 3.92894e-4 0.2090296 0.159837 3.75798e-4 0.208869 0.159134 -4.17732e-4 0.209237 0.159309 4.07558e-4 0.209156 0.158956 -4.27481e-4 0.209318 0.1587769 -4.36663e-4 0.209394 0.158954 4.26746e-4 0.20932 0.159134 4.17356e-4 0.209237 0.1581489 -4.64119e-4 0.2096243 0.1583164 4.56788e-4 0.2095701 0.158529 -4.48431e-4 0.2094921 0.1586639 4.41096e-4 0.2094422 0.157867 -4.74261e-4 0.209709 0.158049 4.67639e-4 0.209655 0.157864 4.73998e-4 0.209709 0.157683 -4.80134e-4 0.209758 0.157678 4.79786e-4 0.209758 0.157303 4.89649e-4 0.209843 0.157117 -4.9391e-4 0.209878 0.157114 4.93725e-4 0.209878 0.157491 4.85003e-4 0.209803 0.157307 -4.89958e-4 0.209843 0.155724 5.0365e-4 0.21 0.15593 5.04181e-4 0.209996 0.155929 -5.04174e-4 0.209996 0.156532 5.01922e-4 0.209958 0.156532 -5.01923e-4 0.209958 0.156333 5.03316e-4 0.209975 0.156729 4.99886e-4 0.209936 0.156729 -4.99892e-4 0.209936 0.156333 -5.03313e-4 0.209975 0.156924 -4.97221e-4 0.209909 0.156924 4.97209e-4 0.209909 0.156132 -5.04064e-4 0.2099879 0.1561329 5.04069e-4 0.2099879 0.157496 -4.85366e-4 0.209803 0.155724 -5.03651e-4 0.21 0.1619684 2.20705e-4 0.2070037 0.1619713 -2.22002e-4 0.2070099 0.1622424 -1.9862e-4 0.2066349 0.162138 2.06309e-4 0.206782 0.1623138 1.90961e-4 0.2065393 0.1623922 -1.8555e-4 0.2064151 0.1625169 1.72729e-4 0.2062281 0.1634653 -7.97906e-5 0.2040222 0.163551 6.80043e-5 0.2036612 0.1635564 -6.90624e-5 0.2036311 0.163716 4.5026e-5 0.202368 0.163723 4.31306e-5 0.20217 0.163716 -4.65815e-5 0.2023569 0.1636238 5.898e-5 0.2032637 0.163609 -6.26591e-5 0.203355 0.1626116 -1.65733e-4 0.2060673 0.1634574 7.87436e-5 0.2040527 0.1633502 -9.24736e-5 0.2044203 0.163697 -5.02894e-5 0.2026618 0.1636962 4.87216e-5 0.2026706 0.1633491 9.06683e-5 0.2044237 0.1632519 -1.02768e-4 0.204707 0.163108 1.15838e-4 0.205079 0.1631303 -1.15552e-4 0.2050237 0.1636557 -5.64712e-5 0.2030463 0.163666 5.33374e-5 0.2029629 0.1627246 1.53626e-4 0.205874 0.1627965 -1.48402e-4 0.2057398 0.162855 1.40904e-4 0.2056249 0.1629878 1.27823e-4 0.2053515 0.1629692 -1.31741e-4 0.2053905 0.1632193 1.04391e-4 0.2047973 0.1637238 4.10956e-5 0.2018797 0.163723 -4.47269e-5 0.20216 0.163725 -4.33201e-5 0.201964 0.1637173 -4.1943e-5 0.2016507 0.1637083 3.98959e-5 0.2014881 0.163682 4.02175e-5 0.201182 0.1637 -4.17867e-5 0.201377 0.163682 -4.21712e-5 0.201182 0.1624169 -6.55696e-5 0.188877 0.1630499 -5.54534e-5 0.195029 0.1630499 4.95857e-5 0.195029 0.159887 -7.43762e-5 0.164265 0.161152 6.86771e-5 0.176571 0.16052 7.20366e-5 0.170418 0.159887 7.38935e-5 0.164265 0.16052 -7.69226e-5 0.170418 0.161785 6.38155e-5 0.1827239 0.161152 -7.63042e-5 0.176571 0.1624169 5.74517e-5 0.188877 0.161785 -7.25199e-5 0.1827239 0.163682 4.02175e-5 0.201182 0.163682 -4.21712e-5 0.201182 0.08124488 -0.004532098 0.07298749 0.08124488 0.004532217 0.07298749 0.08067208 0.004532217 0.07620149 0.08010441 0.004528224 0.07938671 0.08067208 -0.004532098 0.07620149 0.08182287 -0.004528105 0.06974476 0.08182287 0.004528164 0.06974476 0.08010441 -0.004528164 0.07938671 0.07954186 0.004520297 0.08254307 0.07954186 -0.004520237 0.08254307 0.08379387 0.004464268 0.07009607 0.08576077 -0.004395246 0.07044661 0.08576077 0.004395365 0.07044661 0.08182287 0.004528164 0.06974476 0.08379387 -0.004464149 0.07009607 0.08182287 -0.004528105 0.06974476 0.08576077 0.004395365 0.07044661 0.08611166 -0.004386186 0.06847769 0.08611166 0.004386305 0.06847769 0.08576077 -0.004395246 0.07044661 0.08414471 0.004457592 0.06812709 0.08217376 -0.004523932 0.06777578 0.08217376 0.004524052 0.06777578 0.08611166 0.004386305 0.06847769 0.08414471 -0.004457473 0.06812709 0.08611166 -0.004386186 0.06847769 0.08439755 -0.004471004 0.05529844 0.08439755 0.004471123 0.05529844 0.08364737 0.004493713 0.05950748 0.08290618 0.004511356 0.06366658 0.08364737 -0.004493594 0.05950748 0.08515655 -0.004443466 0.05103957 0.08515655 0.004443585 0.05103957 0.08290618 -0.004511237 0.06366658 0.08217376 0.004524052 0.06777578 0.08217376 -0.004523932 0.06777578 0.08312189 -0.004529178 0.05067688 0.08108246 -0.004609107 0.05031335 0.08320587 0.004525125 0.0506919 0.06546688 0 0.04753029 0.06546688 0.005031585 0.04753029 0.06745409 0.004995524 0.04788446 0.06251347 0 0.04700386 0.06459569 -0.00504148 0.04737496 0.06251347 -0.005069673 0.04700386 0.06943726 0.004954397 0.04823786 0.07141637 0.004908263 0.04859066 0.07339137 0.004857003 0.04894268 0.07536238 0.004800736 0.04929399 0.08125108 0.004601657 0.05034345 0.07929229 0.004673063 0.04999434 0.07732939 0.004739403 0.04964447 0.08515655 -0.004443466 0.05103957 0.08515655 0.004443585 0.05103957 0.07903826 -0.004683315 0.04994904 0.07698929 -0.004751741 0.04958385 0.07493555 -0.004814386 0.04921787 0.07081389 -0.004922509 0.04848325 0.0728771 -0.004871368 0.04885095 0.06667315 -0.005007565 0.04774528 0.06874591 -0.004967927 0.04811465 0.06251347 0 0.04700386 0.06005698 0 0.06078678 0.06127297 0.004992306 0.05396407 0.06005698 0.004887342 0.06078678 0.06066185 0.004943251 0.05739259 0.05953055 0 0.06374019 0.05953055 -0.004831314 0.06374019 0.06189018 0.005034446 0.05050116 0.06251347 0.005069732 0.04700386 0.06251347 -0.005069673 0.04700386 0.0619052 -0.005035579 0.05041646 0.0613029 -0.00499469 0.05379635 0.06070625 -0.004947006 0.05714356 0.06011545 -0.004892587 0.06045818 0.05757105 -0.004806935 0.06339097 0.05559265 -0.004771292 0.0630384 0.05559265 0 0.0630384 0.05953055 0 0.06374019 0.05953055 -0.004831314 0.06374019 0.05567866 0.004784047 0.06255549 0.05611908 0.00484538 0.06008487 0.05611908 0 0.06008487 0.05559265 0 0.0630384 0.0552417 0.00471723 0.06500726 0.05559265 -0.004771292 0.0630384 0.0552417 -0.004717171 0.06500726 0.05722147 0.004759609 0.06536018 0.05917966 -0.004790067 0.06570917 0.05917966 0.004790127 0.06570917 0.0552417 0.00471723 0.06500726 0.05722135 -0.00475955 0.06536018 0.0552417 -0.004717171 0.06500726 0.05746018 0.004534006 0.07535678 0.05689865 -0.004428625 0.07850748 0.05689865 0.004428625 0.07850748 0.05860066 0.004714727 0.06895756 0.05802756 -0.004629373 0.07217347 0.05802756 0.004629373 0.07217347 0.05746018 -0.004534006 0.07535678 0.05860066 -0.004714727 0.06895756 0.05917966 0.004790127 0.06570917 0.05917966 -0.004790067 0.06570917 0.07033926 0.004637837 0.08090287 0.06845897 0.004634678 0.08056765 0.07033908 -0.004637837 0.08090275 0.06845879 -0.004634618 0.08056765 0.06656545 0.004622578 0.08023029 0.07220637 0.004632174 0.08123558 0.07220619 -0.004632115 0.08123558 0.07405996 -0.004617512 0.08156597 0.07406008 0.004617512 0.08156597 0.07590049 -0.004593968 0.08189409 0.07590055 0.004594027 0.08189409 0.07772785 0.004561603 0.08221977 0.07772779 -0.004561543 0.08221977 0.07954186 -0.004520237 0.08254307 0.07954186 0.004520297 0.08254307 0.06656515 -0.004622519 0.08023017 0.06465858 0.004601597 0.07989037 0.0646584 -0.004601538 0.07989037 0.06273847 0.004571676 0.07954818 0.06273835 -0.004571676 0.07954818 0.06080508 -0.004532873 0.07920366 0.0608052 0.004532933 0.07920366 0.05885857 0.004485249 0.07885676 0.05885845 -0.004485189 0.07885676 0.05689865 0.004428625 0.07850748 0.05689865 -0.004428625 0.07850748 0.1123616 0.003103494 0.08307027 0.1148831 -0.003010392 0.09770059 0.1168358 0.002938151 0.1090303 0.1194915 -0.002839386 0.1244398 0.1224139 0.00273025 0.1413971 0.1234468 -0.002691745 0.1473899 0.125963 -0.002597272 0.161989 0.125963 0.002596914 0.161989 0.1093384 -0.003214478 0.06552928 0.1073379 0.003287851 0.05392217 0.1043187 -0.003397643 0.03640413 0.102311 0.003470599 0.0247547 0.0998069 -0.003561079 0.01022607 0.0998069 0.003561079 0.01022607 0.163028 1.23816e-4 0.205262 0.162944 1.32172e-4 0.205444 0.16276 1.4126e-4 0.204029 0.1624138 5.73457e-5 0.1888469 0.1630539 4.92927e-5 0.1950674 0.1595805 2.43898e-4 0.1801609 0.1590614 3.40703e-4 0.1861275 0.162443 1.29779e-4 0.198064 0.163666 5.33374e-5 0.2029629 0.163639 5.69831e-5 0.203162 0.163571 6.5587e-5 0.2035599 0.1635299 7.04707e-5 0.203755 0.161785 6.38155e-5 0.1827239 0.163682 4.02175e-5 0.201182 0.163723 4.31306e-5 0.20217 0.163716 4.5026e-5 0.202368 0.163687 5.01294e-5 0.202764 0.163704 4.73589e-5 0.202566 0.161072 2.54752e-4 0.198064 0.1632519 1.00985e-4 0.204707 0.163721 4.06527e-5 0.201774 0.163713 4.007e-5 0.201577 0.1637 3.9925e-5 0.201379 0.163724 4.16729e-5 0.201972 0.163607 6.10662e-5 0.20336 0.163433 8.14431e-5 0.20414 0.163378 8.75461e-5 0.20433 0.161152 6.86771e-5 0.176571 0.163317 9.40602e-5 0.204519 0.15891 2.53342e-4 0.1741924 0.16052 7.20366e-5 0.170418 0.158304 2.18001e-4 0.1641595 0.1618379 2.2193e-4 0.2040235 0.1588635 4.06921e-4 0.1920945 0.157278 4.26089e-4 0.1771755 0.159887 7.38935e-5 0.164265 0.1559685 5.41857e-4 0.177175 0.162666 1.59092e-4 0.205977 0.1622511 1.96337e-4 0.2066277 0.1592569 4.16992e-4 0.1980634 0.156679 6.00638e-4 0.1920925 0.154659 6.5512e-4 0.1771734 0.1573446 5.82407e-4 0.1980735 0.159967 3.76368e-4 0.2040035 0.1482565 0.001257777 0.1861104 0.14612 0.001370489 0.18015 0.1533505 7.65975e-4 0.177172 0.1520425 8.7466e-4 0.1771705 0.154519 7.86626e-4 0.192089 0.1556034 7.28095e-4 0.1980808 0.1505849 0.001018524 0.180155 0.14958 0.00104922 0.1741794 0.1586949 4.75322e-4 0.2039217 0.146912 0.001258492 0.1741735 0.1480315 0.001222193 0.1801519 0.1515495 0.001035511 0.192099 0.1442425 0.001460254 0.174166 0.1574295 5.69125e-4 0.2039293 0.15345 9.0289e-4 0.198058 0.154335 8.31727e-4 0.198059 0.144848 0.00146681 0.180148 0.152568 9.72739e-4 0.1980569 0.156457 6.38234e-4 0.20394 0.151688 0.001041233 0.198056 0.150811 0.001108407 0.198055 0.155809 6.83062e-4 0.203926 0.143577 0.001561224 0.180146 0.142241 0.001606762 0.17416 0.155158 7.2702e-4 0.2039099 0.149936 0.001174271 0.198054 0.142307 0.00165385 0.180144 0.1402375 0.001748561 0.1741524 0.154505 7.70123e-4 0.203894 0.149063 0.001238882 0.198052 0.141039 0.001744687 0.180142 0.153849 8.1239e-4 0.203877 0.148192 0.001302182 0.198051 0.139771 0.001833736 0.180139 0.137567 0.001931428 0.174143 0.1448951 0.00155723 0.1920697 0.1428449 0.001707494 0.1920613 0.138505 0.001920998 0.180137 0.1372399 0.002006411 0.180135 0.135563 0.002063989 0.174135 0.1388858 0.001954197 0.1860806 0.135975 0.002089917 0.180132 0.1407929 0.001852333 0.1920544 0.134712 0.002171516 0.18013 0.139411 0.00194633 0.192045 0.136025 0.002146005 0.186071 0.137178 0.00206989 0.186075 0.133724 0.002292215 0.186061 0.1309249 0.002404212 0.180122 0.134873 0.002220094 0.186066 0.132187 0.002328753 0.1801249 0.1210474 0.002826869 0.1468189 0.124099 0.002667129 0.1511737 0.125963 0.002596735 0.161989 0.1249495 0.002658307 0.1633392 0.1185197 0.002916038 0.1291372 0.116846 0.002962172 0.114423 0.1164748 0.002951502 0.1069355 0.1191079 0.002853751 0.1222144 0.1135502 0.003099501 0.0995869 0.115195 0.003058016 0.114416 0.08125692 0.00460565 0.01011705 0.07893341 0.004716694 0.01022958 0.08714598 0.00434643 0.02776908 0.08819121 0.004304766 0.03369688 0.0877425 0.004314363 0.03096479 0.1114943 0.003135323 0.07803875 0.06822288 0.005158007 0.01077121 0.06582415 0.005226194 0.0141797 0.06641459 0.005218625 0.01086735 0.1024884 0.003528237 0.04103565 0.1045623 0.003388524 0.03781759 0.1025513 0.003461778 0.02614915 0.0880385 0.004255235 0.009795963 0.09052121 0.00411576 0.00968784 0.09232866 0.004010558 0.009608387 0.09418207 0.003916501 0.01306158 0.09631723 0.003773152 0.009430944 0.09853804 0.003635585 0.009330868 0.09980696 0.003561437 0.01022613 0.09447336 0.003883779 0.009513378 0.143729 1.1811e-4 0.007093846 0.141591 3.15698e-4 0.007208347 0.100906 0.003484904 0.009223163 0.1445471 1.17239e-4 0.01505184 0.1388601 6.26819e-4 0.0144385 0.139452 5.10193e-4 0.007322013 0.1299925 0.001379787 0.01348203 0.128753 0.001436471 0.007877588 0.126612 0.001612544 0.007986187 0.1256226 0.001731872 0.01301056 0.124472 0.001785457 0.008093893 0.122331 0.00195533 0.008200824 0.1212658 0.002070426 0.01254069 0.120189 0.002122163 0.00830686 0.118048 0.002285897 0.008412063 0.1166647 0.002414762 0.01204442 0.115906 0.002446532 0.008516371 0.113764 0.002604126 0.008619904 0.111622 0.002758622 0.008722543 0.1121855 0.002736926 0.01156127 0.109479 0.002910017 0.008824348 0.1088629 0.002967238 0.01120299 0.107336 0.003058373 0.008925318 0.105193 0.00320363 0.009025454 0.1054174 0.003199636 0.01083129 0.10305 0.003345787 0.009124696 0.09969937 0.00368154 0.03767877 0.1292819 0.002286374 0.198014 0.1388443 0.001491844 0.2033614 0.06143587 0.005162715 0.03880149 0.06212508 0.005188405 0.03493446 0.06346452 0.005098879 0.04311043 0.128422 0.00230515 0.1980119 0.119194 0.002841293 0.191958 0.120756 0.002817809 0.1919642 0.1270217 0.002328932 0.1980066 0.130142 0.002264499 0.198016 0.08624815 0.004380047 0.02499699 0.08585411 0.004397094 0.02044296 0.0840103 0.00446856 0.009985446 0.139773 0.00146687 0.203418 0.140447 0.00144875 0.203441 0.157114 4.93725e-4 0.209878 0.07809293 0.004757106 0.01828324 0.08570045 0.004420399 0.03917062 0.1268489 0.002677857 0.1860319 0.1317014 0.002409994 0.1920158 0.11114 0.003228425 0.09660202 0.08515655 0.004443168 0.05103957 0.07645869 0.004817843 0.0279808 0.132576 0.002362191 0.186057 0.131429 0.002430021 0.186052 0.128403 0.002548396 0.1801159 0.08322829 0.004523575 0.05069589 0.07498162 0.004870116 0.03021866 0.07855665 0.004713177 0.04290026 0.08475387 0.004445731 0.01902925 0.08716243 0.004349946 0.03693032 0.08543878 0.004433214 0.04588443 0.07020509 0.005086183 0.01066774 0.128881 0.002472519 0.174107 0.0767576 0.004757285 0.04954254 0.07652705 0.004785001 0.04290026 0.129664 0.002477467 0.180119 0.1269809 0.002578377 0.1739723 0.1347206 0.002242207 0.1920288 0.133338 0.002321302 0.192019 0.1291379 0.002558767 0.186042 0.1302829 0.002495586 0.186047 0.127143 0.002617001 0.180114 0.125705 0.002733588 0.186027 0.122104 0.002866029 0.180102 0.125883 0.002683162 0.180111 0.1297146 0.002509415 0.1920057 0.136141 0.00203669 0.198028 0.143822 0.00133419 0.203557 0.135285 0.002076148 0.198026 0.142472 0.001384437 0.2035109 0.133572 0.002148807 0.198023 0.134429 0.00211358 0.198024 0.127708 0.002599954 0.1919964 0.1415343 0.001418232 0.2034535 0.132716 0.002181649 0.1980209 0.137755 0.001509606 0.203351 0.131 0.002239644 0.198017 0.131858 0.002211987 0.198019 0.156333 5.03316e-4 0.209975 0.1368853 0.001520872 0.2033339 0.1354842 0.001535177 0.2032732 0.1252959 0.002343952 0.1980049 0.07458704 0.004823863 0.04915577 0.07237219 0.004884958 0.04876101 0.06840687 0.005013823 0.0429002 0.06279426 0.005207836 0.0311799 0.06353574 0.005222141 0.02701979 0.06616878 0.005053222 0.04359239 0.09367924 0.004071056 0.06975758 0.09446269 0.004044592 0.06926405 0.100302 0.003773272 0.12018 0.100328 0.00375837 0.125984 0.09785139 0.003866851 0.117252 0.09516835 0.004008293 0.08915579 0.09986758 0.003806769 0.09991651 0.06848865 0.00497502 0.04806882 0.06546688 0.005031585 0.04753029 0.08576077 0.004395544 0.07044661 0.09297078 0.004098117 0.08766376 0.09880578 0.003852367 0.102573 0.100329 0.003781616 0.114352 0.09867656 0.00384438 0.114344 0.09390401 0.004049539 0.09734189 0.09451103 0.004011273 0.1055255 0.10387 0.003622055 0.122614 0.05860066 0.004714727 0.06895756 0.05802756 0.004629373 0.07217347 0.0552417 0.00471723 0.06500726 0.06507647 0.005244791 0.0155254 0.06426048 0.00524646 0.02010369 0.06265443 0.005332171 0.01107251 0.06590181 0.005235493 0.01089477 0.06128346 0.005369007 0.01114922 0.09620851 0.003920376 0.1172315 0.0638743 0.00529772 0.01100504 0.102099 0.003662586 0.137609 0.1004577 0.003712534 0.1373904 0.09285438 0.0040434 0.1113985 0.1025587 0.003595888 0.1492853 0.104046 0.003556072 0.149348 0.06075406 0.005131065 0.04262727 0.09134405 0.004172742 0.06080478 0.09139496 0.004172742 0.06826549 0.09175306 0.004148781 0.05483645 0.09237343 0.004133343 0.0574156 0.0932784 0.004082262 0.06080478 0.0833736 0.004501342 0.06104391 0.08611166 0.004386305 0.06847769 0.08414471 0.004457592 0.06812709 0.08990466 0.004235804 0.06975787 0.09022766 0.004215538 0.04886835 0.08998125 0.004232048 0.04384881 0.09132695 0.004176855 0.05148047 0.09417456 0.004052042 0.07871097 0.09765267 0.003905773 0.08735549 0.08217376 0.004524052 0.06777578 0.09550648 0.003999769 0.07518386 0.09790718 0.00388658 0.105529 0.05625778 0.005220472 0.03693217 0.05956 0.005091726 0.04647755 0.100413 0.003736793 0.131779 0.09467685 0.003938138 0.1230285 0.111186 0.003266632 0.164109 0.104833 0.003470838 0.161354 0.1029505 0.003550529 0.1552801 0.06005698 0.004887163 0.06078678 0.06082439 0.00495702 0.05648076 0.04963368 0.005401492 0.02350479 0.05176627 0.005401909 0.02350479 0.1034688 0.003496944 0.1614054 0.09260231 0.003918528 0.1316957 0.02302366 0.004627883 0.01395654 0.0237649 0.004696369 0.01388502 0.1041048 0.003437459 0.1676079 0.05722147 0.004759609 0.06536018 0.04804986 0.005558192 0.01195603 0.04404735 0.004898011 0.04290032 0.05154162 0.004777669 0.05782109 0.06009614 0.005398154 0.01121675 0.06251347 0.005071103 0.04700386 0.06189018 0.005034446 0.05050116 0.04192787 0.005524277 0.01237809 0.05921095 0.005407094 0.01306146 0.05906927 0.005421698 0.0112757 0.05648738 0.005473673 0.01142704 0.05785858 0.005447387 0.0113461 0.05494552 0.005499124 0.01151949 0.0625298 0.005223333 0.02981376 0.06339734 0.005239307 0.02494639 0.05483615 0.005487322 0.01306146 0.05371117 0.00551629 0.01159501 0.05251497 0.005530536 0.01166909 0.05768877 0.005367338 0.02201294 0.05013912 0.005550265 0.01181972 0.05149716 0.005540251 0.01173311 0.05699825 0.005334258 0.02648872 0.05340778 0.005412876 0.02201288 0.04921543 0.005554735 0.01187956 0.06186825 0.005204439 0.03352534 0.04552191 0.005555033 0.01212596 0.04686164 0.005558371 0.01203525 0.06108957 0.005174696 0.03789496 0.05733728 0.005251824 0.0339483 0.04333269 0.005540311 0.01227807 0.04435133 0.005548417 0.01220679 0.04380089 0.005428731 0.01902908 0.04048317 0.005502223 0.01248317 0.03919184 0.005477488 0.01257908 0.038253 0.00545603 0.01264983 0.03948968 0.005345702 0.01902896 0.0371958 0.005428731 0.01273089 0.0511046 0.005249857 0.0339483 0.03639209 0.005405485 0.0127933 0.03558897 0.005380272 0.01285642 0.0347715 0.005352318 0.01292151 0.0376687 0.005270659 0.01994836 0.06032007 0.005137145 0.04221236 0.04695016 0.005194842 0.0339483 0.05828028 0.004873335 0.0604701 0.04902726 0.00522834 0.0339483 0.03215074 0.005246162 0.01313567 0.03518015 0.005204975 0.01902896 0.04487341 0.00514841 0.0339483 0.03137779 0.005209743 0.01320064 0.03333669 0.005098998 0.01985794 0.02986764 0.005131125 0.01332962 0.02836209 0.005042254 0.01346147 0.0309121 0.004994511 0.01913088 0.02909684 0.005087137 0.01339673 0.05554401 0.00476402 0.06331092 0.05611908 0.004845261 0.06008487 0.02742087 0.004981219 0.01354551 0.0264036 0.004909753 0.01363795 0.02897858 0.004852175 0.0196945 0.02550566 0.004841864 0.01372069 0.02457731 0.004766702 0.01380777 0.0223546 0.004563093 0.01402193 0.02080565 0.004398941 0.01417618 0.02153891 0.004479169 0.01410263 0.0201503 0.00432384 0.01424264 0.02228647 0.004294931 0.01904243 0.01878947 0.004155218 0.01438319 0.02014559 0.004039108 0.01903998 0.01815128 0.004069447 0.01445019 0.0468353 0.0044806 0.06081211 0.01754039 0.003984034 0.01451486 0.01663273 0.003849029 0.01461231 0.04764294 0.004621028 0.05782109 0.01506966 0.003588974 0.01478415 0.01571977 0.003702223 0.01471197 0.01800853 0.003739893 0.01903319 0.02686423 0.004692077 0.01977723 0.02461433 0.004508376 0.01950871 0.01332294 0.003240287 0.01498436 0.01588338 0.003379523 0.01903218 0.01288884 0.003141582 0.01503568 0.05347532 0.00457406 0.0682668 0.04977589 0.004210114 0.07337772 0.009886384 0.002311766 0.01539766 0.00946635 0.002164661 0.01544946 0.03431034 0.003978729 0.04886853 0.03639853 0.003641963 0.05884033 0.04502785 0.004157364 0.06602883 0.05439609 0.00439769 0.07572889 0.03034961 0.0034644 0.04886847 0.06069242 0.004329204 0.087668 0.06114989 0.004176855 0.09363043 0.05939048 0.004083693 0.09363049 0.01169675 0.002366602 0.01903456 0.01345604 -0.003271222 0.01495134 0.01377689 -0.00292617 0.01903128 0.01588392 -0.003379583 0.01903229 0.0692014 0.004042923 0.110538 0.05587518 0.003842949 0.09363061 0.04740929 0.00387299 0.07678413 0.01801979 -0.003739833 0.01905763 0.01717734 -0.003934502 0.01450103 0.02871274 -0.00267142 0.05425399 0.04725247 0.003642261 0.08095276 0.03978765 0.001986384 0.08447897 0.03852641 0.001293659 0.08541464 0.03082877 -0.00308156 0.0547133 0.02876937 -0.004859268 0.01914364 0.02562868 -0.004856884 0.01357513 0.02662038 -0.004700183 0.01914483 0.03281933 -0.003409624 0.05483704 0.02463328 -0.004508554 0.01954275 0.02246218 -0.004290401 0.01947069 0.02028673 -0.004035711 0.01937907 0.07681685 0.002171099 0.1644907 0.06688272 0.0026564 0.1371715 0.03333181 -0.005099654 0.01982879 0.03115618 -0.004986822 0.01975733 0.04072159 -0.005012869 0.03394824 0.03948986 -0.005345702 0.01902896 0.03767043 -0.005271136 0.01993131 0.03930914 -0.005484104 0.01235204 0.03851753 -0.005466759 0.01241427 0.07388144 9.83895e-4 0.1668597 0.048105 -0.005030393 0.04290032 0.04164534 -0.005393922 0.01902896 0.07326811 -1.30506e-7 0.1674692 0.05742657 -0.004804551 0.06336522 0.05953055 -0.004831135 0.06374019 0.04350852 -0.005545437 0.01203817 0.04695034 -0.005194842 0.0339483 0.07588207 -0.001872539 0.1654756 0.07517701 -0.001506984 0.1669293 0.04574745 -0.005558788 0.01188135 0.07408654 -9.8255e-4 0.1673307 0.04662877 -0.005561113 0.01182144 0.0518772 -0.005219757 0.03618633 0.04902744 -0.005228281 0.0339483 0.04827356 -0.005543291 0.0130614 0.04828965 -0.005560398 0.01171135 0.04739731 -0.00556153 0.01177006 0.04595708 -0.005451023 0.01902908 0.07695758 -0.002168238 0.1648283 0.05059432 -0.005549669 0.01156431 0.05046129 -0.005533814 0.01306146 0.07398158 -0.002496361 0.1543422 0.05218839 -0.005535781 0.01146638 0.05483639 -0.005487322 0.01306146 0.05320709 -0.005524575 0.01140534 0.05702376 -0.005451142 0.01306146 0.0549215 -0.005501151 0.01130521 0.1284959 -0.002601146 0.1860445 0.126516 -0.00265336 0.180112 0.05751752 -0.005455613 0.01115947 0.05610215 -0.005481898 0.01123797 0.08002299 -0.002584218 0.1656482 0.05537265 -0.005332291 0.02798056 0.06056314 -0.005387902 0.01099705 0.06139826 -0.005355536 0.01306146 0.05868065 -0.005431234 0.01109647 0.05943387 -0.005414664 0.0110563 0.1313289 -0.002438187 0.19201 0.1267152 -0.002691566 0.1860612 0.1297128 -0.002517938 0.192 0.05959081 -0.005287468 0.02798062 0.1239321 -0.002821385 0.1860237 0.121476 -0.002896547 0.1801005 0.077165 -0.002858579 0.1551703 0.0796656 -0.002974689 0.1578764 0.06310772 -0.005320608 0.01086747 0.115399 -0.003112018 0.1739495 0.117066 -0.003072023 0.18009 0.118956 -0.003001391 0.1800945 0.06169974 -0.005252599 0.02798062 0.06840687 -0.005013704 0.0429002 0.06637656 -0.005054593 0.0429002 0.1067415 -0.003439605 0.1583725 0.1053145 -0.003477632 0.1583395 0.06435245 -0.00528407 0.01080614 0.06577205 -0.005231738 0.01306146 0.06557363 -0.005246341 0.01074695 0.1053365 -0.003450274 0.1629469 0.1039347 -0.003478407 0.1629195 0.1025332 -0.003501474 0.1628935 0.07229936 -0.004886865 0.04874801 0.06770819 -0.005175828 0.01064598 0.06678205 -0.005207061 0.01068943 0.06465643 -0.00339955 0.1200985 0.0661146 -0.003545165 0.1196996 0.068026 -0.005104064 0.02798074 0.09973013 -0.003531157 0.1628425 0.1011317 -0.003519177 0.1628677 0.0701344 -0.005041241 0.02798074 0.08108377 -0.003097951 0.1578919 0.08250385 -0.003202855 0.1579095 0.09832888 -0.003537178 0.1628177 0.06959134 -0.005108654 0.01055938 0.08634275 -0.003958284 0.1316103 0.08477801 -0.003950357 0.1315907 0.09104615 -0.003554344 0.158041 0.09247201 -0.003577232 0.158067 0.08534801 -0.003367125 0.157948 0.08677148 -0.00342983 0.1579695 0.0839253 -0.003291964 0.1579279 0.09006363 -0.00309807 0.1739684 0.06771582 -0.003665864 0.1196547 0.06921672 -0.003771781 0.1193454 0.07181835 -0.005023777 0.01045978 0.07435077 -0.004897713 0.02798074 0.07375532 -0.004945039 0.0103752 0.07532936 -0.004878818 0.01030761 0.07666337 -0.004761278 0.04952579 0.07288533 -0.004944205 0.03021866 0.07692241 -0.004808902 0.01024019 0.07809299 -0.004756987 0.01828324 0.07652705 -0.004784882 0.04290026 0.07645869 -0.004817724 0.0279808 0.09416729 -0.003892838 0.1317171 0.07813858 -0.004753649 0.01018935 0.07900398 -0.004713833 0.01015347 0.07855665 -0.004713058 0.04290026 0.09573221 -0.003861367 0.1317397 0.08298128 -0.004534125 0.02052116 0.08071178 -0.00463289 0.01008325 0.08940362 -0.004163205 0.1054931 0.08951807 -0.004127502 0.111388 0.08335381 -0.00450164 0.06115472 0.08611166 -0.004386186 0.06847769 0.08240854 -0.004549264 0.01001441 0.08404964 -0.004466712 0.009948372 0.09285455 -0.004043459 0.1113975 0.08781254 -0.004310548 0.07572686 0.09285932 -0.004094183 0.09362906 0.09400105 -0.00405395 0.0913909 0.0842877 -0.004474163 0.05591505 0.08666419 -0.004329383 0.009844183 0.08355313 -0.004511177 0.05075377 0.0850417 -0.0044505 0.0443924 0.0899046 -0.004235684 0.06975787 0.08925706 -0.004187762 0.009741723 0.09020364 -0.004224538 0.06378912 0.08515655 -0.004443526 0.05103957 0.09134399 -0.004172861 0.06080502 0.08965051 -0.004216194 0.03021883 0.09327822 -0.004082322 0.06080496 0.09521228 -0.003987967 0.06080496 0.09358394 -0.003938972 0.009571373 0.09550255 -0.003942549 0.04588449 0.09134668 -0.004069387 0.009659349 0.09471476 -0.003953814 0.03394871 0.09561532 -0.003817379 0.009491384 0.09803217 -0.003668844 0.00939548 0.0998069 -0.003561139 0.01022607 0.09997737 -0.003546059 0.009317696 0.102076 -0.003417015 0.01047086 0.1020754 -0.003411054 0.009233117 0.1042182 -0.003269791 0.009145498 0.1055918 -0.003188014 0.01085007 0.1060397 -0.003147423 0.009070098 0.1075489 -0.003044366 0.009006798 0.1101046 -0.002882182 0.0113368 0.1088601 -0.002953648 0.008951187 0.1102221 -0.00285834 0.008892714 0.111837 -0.002743721 0.0088225 0.113371 -0.002652406 0.01168918 0.1135885 -0.002617478 0.008745074 0.1153637 -0.00248748 0.008665204 0.1168193 -0.002403318 0.01206105 0.1172233 -0.002349138 0.008579909 0.118843 -0.002226531 0.008504092 0.1213119 -0.00206685 0.0125457 0.1201727 -0.002124667 0.008440792 0.1217569 -0.002001821 0.008363962 0.1231521 -0.001892149 0.008294999 0.1257488 -0.001721739 0.01302427 0.1242803 -0.001802682 0.008238375 0.1254564 -0.001708507 0.008178412 0.1265698 -0.001618504 0.008120715 0.1279038 -0.001509845 0.00805062 0.130271 -0.001356899 0.01351207 0.1294724 -0.001380383 0.007966399 0.1305989 -0.001286327 0.007904708 0.1316628 -0.001196503 0.00784564 0.1334519 -0.001088142 0.0130617 0.1350641 -9.557e-4 0.01402896 0.1332529 -0.001060843 0.007755637 0.1347814 -9.28099e-4 0.007667064 0.136122 -8.09939e-4 0.00758779 0.137922 -7.08453e-4 0.0143373 0.1380642 -6.36264e-4 0.007469952 0.137174 -7.16232e-4 0.007524371 0.1389451 -5.56665e-4 0.007415354 0.1414874 -3.93236e-4 0.01472187 0.1400652 -4.54773e-4 0.007344901 0.1413977 -3.32862e-4 0.007259488 0.1427184 -2.11402e-4 0.00717312 0.144547 -1.15784e-4 0.0150519 0.1437309 -1.18011e-4 0.007105708 0.09103739 -0.003938436 0.1316731 0.08947247 -0.003951847 0.1316518 0.109596 -0.003350853 0.1584395 0.1081685 -0.003397226 0.1584055 0.06434607 -0.00508815 0.0429002 0.0623157 -0.00511384 0.0429002 0.06605058 -0.002927184 0.131419 0.06147754 -0.00500667 0.05281645 0.05126744 -0.005422055 0.02201288 0.05415743 -0.005512237 0.01134943 0.162452 -1.70133e-4 0.2040269 0.16294 -1.34635e-4 0.205452 0.1632519 -1.02768e-4 0.204707 0.162443 -1.3725e-4 0.198064 0.163531 -7.2132e-5 0.203747 0.163572 -6.71297e-5 0.2035509 0.163485 -7.75293e-5 0.203943 0.16364 -5.86064e-5 0.203157 0.163666 -5.49714e-5 0.202959 0.163682 -4.21712e-5 0.201182 0.163609 -6.26591e-5 0.203355 0.163688 -5.17542e-5 0.202759 0.163704 -4.89548e-5 0.2025589 0.163723 -4.47269e-5 0.20216 0.163725 -4.33201e-5 0.201964 0.163716 -4.65815e-5 0.2023569 0.163721 -4.23612e-5 0.201768 0.163713 -4.185e-5 0.201572 0.1637 -4.17867e-5 0.201377 0.1631799 -1.10339e-4 0.204897 0.163318 -9.59109e-5 0.204518 0.156358 -5.38559e-4 0.180159 0.15443 -7.0491e-4 0.1801584 0.155421 -6.76464e-4 0.186124 0.15829 -3.66287e-4 0.1801605 0.1575779 -3.73716e-4 0.1741915 0.1549135 -6.08164e-4 0.174189 0.16052 -7.69226e-5 0.170418 0.159887 -7.43762e-5 0.164265 0.1586139 -1.89928e-4 0.1641803 0.163434 -8.32916e-5 0.204136 0.1631039 -1.18252e-4 0.2050859 0.161073 -2.62193e-4 0.198064 0.159967 -3.22881e-4 0.1920955 0.162761 -1.5176e-4 0.205805 0.162852 -1.43104e-4 0.205631 0.159063 -3.53317e-4 0.1861275 0.1625609 -1.70371e-4 0.2061499 0.161216 -2.76318e-4 0.204017 0.1571465 -5.76315e-4 0.1920954 0.158807 -4.64061e-4 0.198063 0.162457 -1.79769e-4 0.206315 0.160279 -3.53204e-4 0.204007 0.157907 -5.41772e-4 0.198062 0.15701 -6.17956e-4 0.198062 0.1537602 -8.66864e-4 0.1920757 0.152247 -8.32989e-4 0.174185 0.151866 -9.19366e-4 0.1801559 0.159305 -4.30157e-4 0.2038331 0.161842 -2.32796e-4 0.207172 0.156116 -6.92776e-4 0.198061 0.1552259 -7.66362e-4 0.19806 0.14958 -0.001049458 0.1741794 0.1493095 -0.001126408 0.1801534 0.1580556 -5.24921e-4 0.2038817 0.154338 -8.38708e-4 0.198059 0.1511245 -0.001085102 0.1920709 0.153454 -9.09775e-4 0.198058 0.157099 -5.94215e-4 0.203953 0.146759 -0.001326382 0.18015 0.146912 -0.001258671 0.1741729 0.151692 -0.001047909 0.198056 0.1490795 -0.00124973 0.1920708 0.152571 -9.7952e-4 0.1980569 0.1442425 -0.001460433 0.174166 0.1442145 -0.001518845 0.1801469 0.155805 -6.84698e-4 0.203924 0.155154 -7.28627e-4 0.203909 0.150815 -0.001114964 0.198055 0.1415725 -0.001654505 0.174157 0.1416749 -0.001703917 0.1801425 0.14994 -0.001180708 0.198054 0.154501 -7.71701e-4 0.2038919 0.149067 -0.001245141 0.198052 0.153845 -8.13935e-4 0.203875 0.153187 -8.55342e-4 0.203857 0.148196 -0.001308381 0.198051 0.138902 -0.001841068 0.1741474 0.139141 -0.001881837 0.1801379 0.152527 -8.9591e-4 0.203839 0.147328 -0.00137031 0.19805 0.1428691 -0.001718938 0.1920537 0.1400039 -0.001886904 0.1860929 0.1408063 -0.001863956 0.1920443 0.146461 -0.001430928 0.1980479 0.151865 -9.35622e-4 0.203819 0.138339 -0.002001643 0.186079 0.13661 -0.002052426 0.1801335 0.134083 -0.002215385 0.1801285 0.1365603 -0.002120852 0.1860787 0.1387864 -0.001999855 0.1920372 0.13488 -0.002229034 0.186066 0.1367549 -0.002129912 0.19203 0.148531 -0.001120507 0.203716 0.143007 -0.001659631 0.198042 0.142147 -0.001713156 0.19804 0.143869 -0.001604616 0.198043 0.1492 -0.00108546 0.203737 0.1347337 -0.002251863 0.1920216 0.1330927 -0.002340078 0.1860647 0.1308058 -0.002474546 0.1860551 0.1290365 -0.002516508 0.1801174 0.1315585 -0.002370297 0.180123 0.146515 -0.001219451 0.203648 0.140429 -0.001815438 0.198037 0.139572 -0.001864075 0.198035 0.1327395 -0.002364158 0.1920136 0.05162727 -0.005541443 0.01150053 0.04380106 -0.005428671 0.01902908 0.04141581 -0.005521059 0.01219129 0.05746018 -0.004534006 0.07535678 0.05689865 -0.004428744 0.07850748 0.03311294 -0.005293905 0.01286619 0.03405785 -0.005331039 0.01278376 0.03472405 -0.005355596 0.01272648 0.03204774 -0.005246639 0.01296108 0.03269869 -0.005275905 0.01290291 0.06840002 0.00286895 0.1371802 0.07710301 0.002859473 0.1550288 0.02781289 -0.005012631 0.01335775 0.03379535 -0.002066433 0.07052105 0.03886336 -0.001290857 0.08619028 0.03825449 -1.53278e-7 0.08743923 0.0240367 -0.004725515 0.01373928 0.02201974 -0.004534423 0.0139544 0.07084941 0.003856182 0.1194192 0.08015805 0.003659784 0.1401522 0.04461002 0.003149509 0.08332735 0.01983159 -0.004290521 0.01419627 0.05431628 0.003214657 0.1026629 0.00832498 -1.73602e-7 0.01902872 0.07561188 0.004038393 0.119145 0.08634269 0.003958165 0.1316111 0.08477795 0.003950238 0.1315914 0.09103733 0.003938317 0.1316738 0.08947241 0.003951728 0.1316524 0.09973019 0.003531098 0.1628429 0.1011318 0.003519058 0.1628684 0.08790749 0.003958523 0.1316316 0.106135 0.003355681 0.174001 0.108227 0.003281235 0.1800709 0.104797 0.003372669 0.173995 0.103458 0.003384113 0.1739889 0.05994379 0.003903388 0.09959262 0.01564037 -0.003691315 0.01468294 0.08790755 -0.003958582 0.1316306 0.08451223 -0.004336178 0.09512162 0.0861811 -0.004188716 0.111379 0.08451241 -0.004209876 0.111374 0.08063781 -0.004531741 0.07639378 0.08127474 -0.00453186 0.07281976 0.08182287 -0.004528224 0.06974476 0.09045511 -0.004184007 0.0913909 0.08868187 -0.004242002 0.09139102 0.07468366 -0.004821419 0.04917299 0.04939365 -0.005556762 0.01164013 0.0515418 -0.00477761 0.05782109 0.0552417 -0.004717171 0.06500726 0.05802756 -0.004629373 0.07217347 0.05722135 -0.00475955 0.06536018 0.03701061 -0.005428314 0.01253551 0.03628087 -0.005407094 0.01259553 0.163484 7.57513e-5 0.203948 0.1373119 7.01612e-4 0.007434785 0.1560366 4.20039e-4 0.1640069 0.163182 1.08237e-4 0.204894 0.163108 1.15838e-4 0.205079 0.135173 8.89953e-4 0.007546782 0.1542389 5.75999e-4 0.163886 0.1548309 5.64397e-4 0.168214 0.1572329 5.05192e-4 0.1861259 0.162855 1.40904e-4 0.2056249 0.162762 1.50013e-4 0.205804 0.1344358 0.001009047 0.01396125 0.133033 0.001075208 0.007657885 0.152827 6.96426e-4 0.163792 0.1527799 7.39651e-4 0.168205 0.1554175 6.64061e-4 0.186124 0.16236 1.86861e-4 0.206471 0.162567 1.68162e-4 0.206145 0.162465 1.77418e-4 0.20631 0.130893 0.001257359 0.007768154 0.1508108 8.65027e-4 0.1636564 0.162138 2.06309e-4 0.206782 0.1500435 9.65598e-4 0.1681885 0.1530129 8.68913e-4 0.1861209 0.1618 2.34562e-4 0.207208 0.161913 2.25259e-4 0.207072 0.162025 2.15932e-4 0.20693 0.1476474 0.001120924 0.1634437 0.161568 2.53097e-4 0.207467 0.161685 2.43842e-4 0.20734 0.1506265 0.001066684 0.186116 0.16145 2.62327e-4 0.207588 0.145775 0.001267194 0.1633177 0.161155 2.84462e-4 0.207864 0.161316 2.72549e-4 0.207718 0.1443711 0.001374602 0.1632243 0.160983 2.97033e-4 0.208014 0.1423057 0.001529216 0.1630856 0.160799 3.10262e-4 0.208168 0.1490583 0.001236617 0.1920875 0.1458666 0.001444756 0.1860987 0.160604 3.2415e-4 0.208325 0.1394627 0.001734435 0.1628946 0.1469878 0.001398563 0.1920784 0.160398 3.38696e-4 0.208485 0.1435164 0.001622319 0.1860975 0.1601949 3.52669e-4 0.208635 0.1366262 0.001931071 0.162704 0.160015 3.64429e-4 0.208756 0.1412022 0.001791179 0.1860883 0.159837 3.75798e-4 0.208869 0.153192 8.5383e-4 0.203859 0.1338267 0.002117156 0.1625159 0.159659 3.86776e-4 0.208973 0.152532 8.94432e-4 0.20384 0.147323 0.00136429 0.19805 0.15187 9.34179e-4 0.203821 0.159483 3.97362e-4 0.209069 0.146456 0.001425027 0.1980479 0.131622 0.002257943 0.1623679 0.1336229 0.002188384 0.174162 0.145591 0.001484453 0.198047 0.151206 9.73054e-4 0.203801 0.159309 4.07558e-4 0.209156 0.130217 0.002345204 0.1622745 0.1505399 0.001011013 0.203781 0.143864 0.001599192 0.198043 0.144727 0.001542508 0.198045 0.1589574 4.26357e-4 0.2093185 0.1281412 0.002470612 0.1621351 0.130951 0.002351999 0.1741445 0.133449 0.002251207 0.180127 0.149873 0.001048088 0.20376 0.09627604 0.003859281 0.03171086 0.1077182 0.003342747 0.0734874 0.149205 0.001084148 0.203739 0.1377645 0.002054691 0.1920407 0.143003 0.001654386 0.198042 0.1034597 0.003552258 0.06304281 0.142143 0.00170803 0.19804 0.148535 0.001119256 0.2037169 0.158774 4.35739e-4 0.209397 0.09655207 0.003874719 0.04178166 0.1031122 0.003592967 0.06975728 0.1087025 0.003355801 0.09362846 0.1128605 0.003180146 0.111458 0.1169415 0.003004789 0.1291162 0.136368 0.002142727 0.192032 0.141284 0.001760184 0.1980389 0.158594 4.44335e-4 0.209469 0.09214466 0.00409305 0.03308296 0.09618431 0.003932178 0.05599284 0.1028348 0.003626823 0.07647192 0.1097818 0.003331184 0.1055236 0.1160656 0.003060042 0.1320483 0.1224344 0.002782404 0.1587465 0.1255019 0.002658009 0.1740476 0.140425 0.001810669 0.198037 0.147864 0.001153349 0.2036949 0.147192 0.00118637 0.203673 0.09901499 0.003818571 0.07204651 0.1005776 0.003755092 0.08090716 0.105183 0.003544509 0.09362852 0.1095275 0.003359019 0.111448 0.1145021 0.003142297 0.1320251 0.121009 0.002857208 0.1587135 0.1584129 4.52533e-4 0.209536 0.146519 0.001218318 0.2036499 0.139567 0.001859486 0.198035 0.10263 0.003671944 0.09254986 0.1067595 0.003491163 0.1070085 0.112939 0.003221631 0.1320016 0.1195825 0.00292927 0.15868 0.1235409 0.002758085 0.1740307 0.127993 0.002619564 0.186037 0.13871 0.001906514 0.198033 0.145846 0.001249074 0.203627 0.158231 4.60334e-4 0.209598 0.08870226 0.004282414 0.04290038 0.103673 0.003629505 0.09846085 0.1067571 0.00350362 0.1159561 0.1078287 0.003459095 0.1220298 0.1135982 0.003199756 0.140784 0.1181565 0.00299865 0.158646 0.1221999 0.002823591 0.1740155 0.124623 0.00274676 0.180108 0.137854 0.001951813 0.198032 0.158049 4.67639e-4 0.209655 0.07686537 0.00481075 0.01033109 0.108297 0.003438174 0.12608 0.1113484 0.003302931 0.1379125 0.109801 0.003371655 0.1319299 0.1167305 0.003065109 0.158612 0.1208631 0.002886176 0.1740077 0.123364 0.002807736 0.180105 0.1451719 0.001278698 0.203604 0.136997 0.001995205 0.1980299 0.144497 0.00130707 0.203581 0.0744338 0.004917085 0.01045221 0.09601438 0.003969788 0.07871079 0.108884 0.003415763 0.1280159 0.109926 0.003372669 0.133927 0.109776 0.003373265 0.137762 0.1113206 0.003304302 0.143687 0.116954 0.003056704 0.164686 0.1188886 0.002974271 0.1740701 0.157864 4.73998e-4 0.209709 0.07231521 0.005004346 0.01055926 0.08433759 0.00447297 0.05563509 0.110968 0.003329515 0.139838 0.112011 0.003286182 0.145749 0.111421 0.003297328 0.149532 0.115561 0.003115773 0.1646585 0.113046 0.003225505 0.155513 0.120844 0.002921521 0.180099 0.124561 0.002786636 0.186022 0.157678 4.79786e-4 0.209758 0.08801704 0.0043118 0.06975775 0.101779 0.003719329 0.110759 0.113053 0.00324285 0.15166 0.111603 0.0032835 0.155477 0.11504 0.003134191 0.167721 0.113297 0.003209352 0.1615419 0.1168439 0.003057599 0.17405 0.119584 0.002974092 0.180096 0.123418 0.002836942 0.186017 0.143147 0.001359999 0.203534 0.07224267 0.004972398 0.02798074 0.08028674 0.004637956 0.05017161 0.08938521 0.004229605 0.08766412 0.102825 0.00367093 0.1166869 0.114095 0.003199338 0.157571 0.115137 0.003155708 0.163482 0.113665 0.003186225 0.167698 0.118324 0.003023564 0.180093 0.115505 0.003108322 0.174044 0.1218318 0.002901732 0.1860272 0.157491 4.85003e-4 0.209803 0.0841571 0.004452049 0.0701608 0.1050125 0.003567874 0.1290955 0.11618 0.003112018 0.169393 0.114167 0.003155708 0.174037 0.1170639 0.003069698 0.180091 0.126285 0.002657115 0.191988 0.157303 4.89649e-4 0.209843 0.08182287 0.004528522 0.06974476 0.08868181 0.004242062 0.09139102 0.08757525 0.004266679 0.09362953 0.101978 0.003685712 0.131804 0.107005 0.003472626 0.140398 0.117222 0.003068208 0.1753039 0.119983 0.002969086 0.186003 0.1248183 0.002710759 0.1919723 0.06501817 0.00523138 0.01870208 0.06427794 0.005229711 0.02285504 0.08126252 0.004532039 0.07288855 0.08061796 0.004531741 0.07650506 0.08965396 0.004084765 0.117191 0.09129279 0.004051744 0.117201 0.108051 0.003421843 0.146326 0.118264 0.00302428 0.181215 0.119307 0.002980232 0.187125 0.07992118 0.004526376 0.08041453 0.08940351 0.004163146 0.1054933 0.1101338 0.003319323 0.1581399 0.118325 0.003005266 0.187299 0.1227723 0.002772092 0.1919719 0.156924 4.97209e-4 0.209909 0.07954186 0.004520297 0.08254307 0.08451211 0.004336178 0.09512162 0.104385 0.003517091 0.155297 0.117341 0.00302577 0.187472 0.156729 4.99886e-4 0.209936 0.07955294 0.004504263 0.08479249 0.07772785 0.004561603 0.08221977 0.07771974 0.004535079 0.08473712 0.0828436 0.004224181 0.11137 0.08117479 0.004231393 0.111365 0.112232 0.003213942 0.170037 0.116355 0.003041684 0.187646 0.07590055 0.004594027 0.08189409 0.07590687 0.004558205 0.08473116 0.08618092 0.004188656 0.111379 0.10541 0.003417074 0.167566 0.113277 0.003160774 0.175965 0.115367 0.003053009 0.18782 0.156532 5.01922e-4 0.209958 0.07406008 0.004617512 0.08156597 0.08451235 0.004209816 0.111374 0.114322 0.00310713 0.181892 0.1130869 0.003130853 0.185974 0.07220637 0.004632174 0.08123558 0.07409769 0.004573762 0.0847395 0.09832894 0.003537118 0.1628187 0.106962 0.0032925 0.180069 0.111931 0.003141641 0.18597 0.118173 0.002851128 0.191954 0.105696 0.003298163 0.180066 0.1561329 5.04069e-4 0.2099879 0.07033926 0.004637837 0.08090287 0.07229781 0.004581272 0.08477443 0.07783716 0.004222571 0.111357 0.07877624 0.004104614 0.1189201 0.09532481 0.003599047 0.1581234 0.102119 0.003389894 0.173983 0.110774 0.003147125 0.185965 0.11715 0.002856194 0.19195 0.104429 0.003297924 0.180064 0.15593 5.04181e-4 0.209996 0.06127297 0.004992306 0.05396407 0.06845897 0.004634678 0.08056765 0.0704354 0.004582226 0.08468288 0.0739873 0.004445016 0.09512221 0.07950598 0.004231095 0.111361 0.103161 0.003291368 0.180061 0.09951192 0.003381252 0.1740784 0.1008675 0.003387451 0.1741191 0.09389829 0.003591835 0.1580955 0.109614 0.003147006 0.185961 0.116123 0.002856075 0.191947 0.1235615 0.002342581 0.1980027 0.1340678 0.001536428 0.2032247 0.155724 5.0365e-4 0.21 0.06656545 0.004622578 0.08023029 0.06862586 0.004573047 0.08468306 0.07223314 0.004436135 0.09512209 0.09247201 0.003577113 0.158068 0.108452 0.003140807 0.185957 0.115094 0.002850532 0.191943 0.101892 0.003277957 0.180059 0.1553453 5.01646e-4 0.2099999 0.03386986 0.005318701 0.01299422 0.06465858 0.004601597 0.07989037 0.06684261 0.004554152 0.08470964 0.09816157 0.003367841 0.1740491 0.09681493 0.003346562 0.1740282 0.09104615 0.003554224 0.158042 0.107288 0.003128051 0.185953 0.114062 0.002838969 0.1919389 0.1006219 0.003256976 0.180057 0.12236 0.002330124 0.198001 0.1328031 0.001523375 0.2031975 0.06273847 0.004571676 0.07954818 0.06503278 0.004525065 0.0847088 0.07719528 0.00407648 0.1190372 0.0896207 0.003522455 0.1580165 0.10612 0.003108143 0.185949 0.113026 0.002820909 0.191936 0.09935015 0.003227889 0.180055 0.121487 0.002315282 0.198 0.03305524 0.005285859 0.01306086 0.05917966 0.004790127 0.06570917 0.0608052 0.004532933 0.07920366 0.06323254 0.004484474 0.08473145 0.09547138 0.003316938 0.1740114 0.0881958 0.003481209 0.157993 0.10495 0.003080427 0.185946 0.111986 0.002795815 0.191933 0.09807777 0.003190159 0.1800529 0.120612 0.002294659 0.197999 0.131775 0.001502513 0.2031739 0.1549452 4.94664e-4 0.21 0.05885857 0.004485249 0.07885676 0.06145018 0.004431247 0.0848003 0.07401961 0.003989756 0.1192289 0.0941289 0.003278255 0.1740001 0.08677148 0.00342977 0.15797 0.103776 0.003044426 0.1859419 0.110943 0.002763211 0.1919299 0.09680426 0.003143012 0.180051 0.119735 0.002267837 0.197997 0.13112 0.00148487 0.203158 0.01947724 0.00424236 0.01431179 0.05746018 0.004534006 0.07535678 0.05689865 0.004428625 0.07850748 0.08534789 0.003367066 0.1579484 0.09278708 0.003230035 0.1739872 0.1026 0.002999544 0.185939 0.109896 0.002722442 0.191927 0.09552967 0.003085613 0.180049 0.118856 0.002234339 0.197996 0.1546704 4.87088e-4 0.21 0.130468 0.001462996 0.203143 0.03059065 0.005169868 0.01326745 0.09425395 0.003016769 0.180047 0.09010732 0.003100514 0.1739714 0.09144604 0.003171145 0.173978 0.08392524 0.003291904 0.1579279 0.10142 0.002944827 0.185936 0.108845 0.002672791 0.191924 0.1179749 0.00219357 0.197995 0.129819 0.001436233 0.203128 0.154396 4.76557e-4 0.2099999 0.01419448 0.003423511 0.01488327 0.01463168 0.003508269 0.01483345 0.01142787 0.002771854 0.01521086 0.01377713 0.002926051 0.01903283 0.06926691 0.00376892 0.1195132 0.08250373 0.003202795 0.1579095 0.100237 0.002879142 0.1859329 0.107789 0.002613246 0.1919209 0.09297746 0.002935111 0.180046 0.117091 0.002144634 0.1979939 0.129173 0.001404225 0.203114 0.1541063 4.62286e-4 0.21 0.01245588 0.003038048 0.01508718 0.01202416 0.002929568 0.01513898 0.009054124 0.001997113 0.01550257 0.007059991 -4.89649e-4 0.01578408 0.006915926 -6.86681e-5 0.01579999 0.03094333 0.003079175 0.05498796 0.06771945 0.003664553 0.1196949 0.08876979 0.00301671 0.1739644 0.08743262 0.002918064 0.1739582 0.08108365 0.003097891 0.1578925 0.09905099 0.002801299 0.18593 0.10673 0.002542614 0.191919 0.09170019 0.002839028 0.1800439 0.116205 0.002086639 0.197993 0.12853 0.001366198 0.203101 0.01031059 0.002446711 0.01534616 0.01073688 0.002575159 0.01529455 0.007895648 0.001338362 0.01566189 0.009708583 0.001546084 0.01902943 0.007547557 0.001060664 0.01571059 0.02906316 0.0026654 0.055081 0.06631612 0.00353825 0.1202358 0.07966548 0.002974629 0.1578764 0.08609765 0.002802073 0.1739532 0.09786158 0.002709567 0.185928 0.105666 0.002459406 0.191916 0.09042251 0.002726078 0.180043 0.115317 0.002018332 0.197992 0.127891 0.001321434 0.2030889 0.1538339 4.45077e-4 0.21 0.007328987 -8.45326e-4 0.01575028 0.05649405 0.003625333 0.09959274 0.06482273 0.003394007 0.120534 0.09666895 0.002601802 0.185925 0.104598 0.002361595 0.191914 0.0891447 0.002593755 0.180042 0.114427 0.001938045 0.197991 0.1535612 4.23462e-4 0.21 0.127255 0.001268863 0.203079 0.01375818 0.003334224 0.01493358 0.006996273 3.67003e-4 0.01578736 0.00723505 7.43052e-4 0.0157541 0.05787432 0.003370285 0.1072702 0.08476489 0.002666234 0.1739477 0.07994341 0.002586781 0.1654424 0.0954737 0.002475559 0.185923 0.1035259 0.002247035 0.191913 0.08786737 0.0024392 0.18004 0.113535 0.001843988 0.19799 0.126624 0.001207292 0.203069 0.07869309 0.002392411 0.1657219 0.08341437 0.002506673 0.173927 0.09427595 0.002328097 0.185921 0.10245 0.002113163 0.191911 0.08659148 0.002258479 0.18004 0.112641 0.001734137 0.19799 0.1532199 3.88411e-4 0.21 0.125997 0.001135349 0.203061 0.1533589 4.03737e-4 0.21 0.008779346 -0.00186479 0.01555126 0.008388161 -0.001653194 0.01560568 0.009709119 -0.001546263 0.01902991 0.0114957 -0.002790689 0.01520138 0.01063966 -0.002546668 0.0153104 0.01169598 -0.00236696 0.0190311 0.05216318 0.002986013 0.1015737 0.08531916 0.002040863 0.180039 0.08077079 0.002097249 0.173923 0.0820896 0.002320945 0.173925 0.09307658 0.002155542 0.18592 0.101371 0.001956582 0.191909 0.111747 0.001605629 0.197989 0.125375 0.001051247 0.2030529 0.153082 3.7143e-4 0.21 0.01302218 -0.003173828 0.0150063 0.04456579 0.002812504 0.08748883 0.05357205 0.002637803 0.1089758 0.07568585 0.001875579 0.1650159 0.0794633 0.001815915 0.173922 0.07517588 0.001506984 0.166927 0.09187757 0.001947939 0.185919 0.100291 0.001768171 0.191908 0.0840556 0.001767039 0.180038 0.110852 0.001451015 0.197989 0.124759 9.49963e-4 0.203047 0.152944 3.52574e-4 0.21 0.152806 3.3111e-4 0.21 0.008653759 0.001803398 0.01555639 0.009183168 -0.002050995 0.01549637 0.04273813 0.002436161 0.08731514 0.04851871 0.002340316 0.1009481 0.09068357 0.001686573 0.185918 0.09921348 0.001530945 0.191907 0.08280515 0.001429378 0.180038 0.109962 0.001256287 0.197988 0.124153 8.2256e-4 0.203042 0.152669 3.06199e-4 0.21 0.008266806 0.001583874 0.01560997 0.04680019 0.001893699 0.1008237 0.05018502 0.001848936 0.108694 0.0781719 0.001468837 0.173921 0.08949899 0.00136429 0.185917 0.0981428 0.001238405 0.191907 0.08160948 9.33714e-4 0.180038 0.109079 0.001016259 0.197988 0.123558 6.65351e-4 0.203039 0.1525329 2.7706e-4 0.21 0.152398 2.4308e-4 0.21 0.007655203 -0.001149177 0.01570695 0.01235759 -0.003015279 0.01509094 0.01629334 -0.003798902 0.0146051 0.04509341 0.001238048 0.1005525 0.04858148 0.001208305 0.1085724 0.07693916 9.59497e-4 0.17392 0.08836311 8.9122e-4 0.185916 0.09711456 8.08981e-4 0.191906 0.08077538 0 0.180037 0.108233 6.63856e-4 0.197988 0.1522639 2.03673e-4 0.21 0.122993 4.34614e-4 0.203037 0.00801146 -0.001416087 0.01565819 0.009598076 -0.00221157 0.01544225 0.01476418 -0.003535568 0.01478898 0.01520198 -0.00361526 0.01473575 0.01894146 -0.004179 0.01429718 0.04402518 -1.63712e-7 0.1006427 0.04760992 0 0.1088222 0.08160966 -9.3382e-4 0.180038 0.0875687 0 0.185916 0.08836328 -8.91335e-4 0.185916 0.09639447 0 0.191906 0.107641 0 0.197988 0.07608067 0 0.17392 0.122602 0 0.203036 0.152137 1.47785e-4 0.21 0.01001936 -0.002354085 0.01538878 0.02137577 -0.004466414 0.01402467 0.02070951 -0.0043931 0.01409816 0.04528468 -0.001236677 0.100992 0.04859083 -0.001208484 0.1085933 0.07693928 -9.59593e-4 0.17392 0.0971148 -8.09093e-4 0.191906 0.08280539 -0.001429438 0.180038 0.108233 -6.63938e-4 0.197988 0.1520259 -6.21574e-5 0.21 0.122993 -4.34646e-4 0.203037 0.152027 6.25472e-5 0.21 0.02333021 -0.004662036 0.01381367 0.04675894 -0.001894056 0.1007286 0.05050182 -0.001844823 0.1094304 0.08405578 -0.001767158 0.180038 0.07946348 -0.001815915 0.173922 0.07817208 -0.001468896 0.173921 0.08949917 -0.001364409 0.185917 0.09814298 -0.001238465 0.191907 0.109079 -0.001016318 0.197988 0.123558 -6.65385e-4 0.203039 0.152136 -1.47485e-4 0.21 0.01432716 -0.003451883 0.01484268 0.01389116 -0.003363847 0.01489686 0.01809525 -0.00406593 0.0143944 0.04284381 -0.002434432 0.08756411 0.04925227 -0.002329349 0.1026667 0.09068387 -0.001686751 0.185918 0.09921365 -0.001531064 0.191907 0.08531945 -0.002040982 0.180039 0.109962 -0.001256406 0.197988 0.124153 -8.22577e-4 0.203042 0.1522639 -2.03533e-4 0.21 0.152397 -2.42911e-4 0.21 0.04472351 -0.002808749 0.08787268 0.05369144 -0.002635538 0.1092598 0.08077096 -0.002097308 0.173923 0.09187787 -0.001948118 0.185919 0.100291 -0.00176835 0.191908 0.08659178 -0.002258598 0.18004 0.110853 -0.001451075 0.197989 0.124759 -9.50025e-4 0.203047 0.1525329 -2.76911e-4 0.21 0.02270537 -0.004602491 0.01388037 0.02625846 -0.004904448 0.01351159 0.03047931 -0.005169689 0.0131042 0.02960449 -0.005121886 0.01318603 0.04549461 -0.003129899 0.08546966 0.05468279 -0.002930879 0.1076565 0.08208668 -0.00231868 0.1739386 0.093077 -0.00215584 0.18592 0.101371 -0.001956939 0.191909 0.08786767 -0.002439379 0.18004 0.111747 -0.001605808 0.197989 0.125375 -0.001051247 0.2030529 0.152669 -3.06185e-4 0.21 0.152806 -3.31012e-4 0.21 0.02470564 -0.004782795 0.01366961 0.02875381 -0.005072057 0.01326686 0.04430401 -0.003451704 0.07818102 0.05416601 -0.003217637 0.1023087 0.08341449 -0.002506673 0.173927 0.09427648 -0.002328395 0.185921 0.10245 -0.00211358 0.191911 0.089145 -0.002593934 0.180042 0.112642 -0.001734316 0.19799 0.152944 -3.52414e-4 0.21 0.125997 -0.001135408 0.20306 0.02692019 -0.004952192 0.01344561 0.04576104 -0.00368005 0.07725805 0.05793219 -0.003368616 0.1074168 0.08473461 -0.002663016 0.1739456 0.09042286 -0.002726316 0.180043 0.0954743 -0.002475976 0.185923 0.09666979 -0.002602398 0.185925 0.1035259 -0.002247512 0.1919119 0.113535 -0.001844227 0.19799 0.126623 -0.001207351 0.203069 0.153082 -3.71401e-4 0.21 0.04734337 -0.003874897 0.07661652 0.05649429 -0.003625392 0.09959274 0.08606523 -0.002799153 0.1739504 0.1045989 -0.00236231 0.191914 0.09170067 -0.002839326 0.1800439 0.114428 -0.001938402 0.197991 0.153358 -4.03716e-4 0.21 0.127255 -0.001268982 0.203079 0.1532199 -3.88431e-4 0.21 0.04283684 -0.004220604 0.06045758 0.05587542 -0.003842949 0.09363061 0.06167107 -0.004012107 0.09959262 0.08739513 -0.002915203 0.1739547 0.09786236 -0.002710282 0.185928 0.105667 -0.002460241 0.191916 0.115318 -0.002018749 0.197992 0.1278899 -0.001321554 0.2030889 0.1535569 -4.22982e-4 0.2099999 0.04480004 -0.004362523 0.06054008 0.05763232 -0.003973066 0.09363055 0.08872866 -0.003014087 0.1739609 0.092978 -0.002935528 0.180046 0.09905195 -0.002802073 0.18593 0.1067309 -0.002543628 0.191919 0.09425455 -0.003017246 0.180047 0.116206 -0.002087116 0.197993 0.12853 -0.001366317 0.203101 0.1538348 -4.45104e-4 0.21 0.03136992 -0.005214691 0.01302242 0.05146783 -0.004332959 0.07292217 0.07950615 -0.004231095 0.111361 0.0778374 -0.004222631 0.111357 0.100238 -0.002880156 0.1859329 0.107791 -0.002614498 0.1919209 0.09553027 -0.003086149 0.180049 0.117092 -0.00214523 0.1979939 0.129172 -0.001404345 0.203114 0.03761845 -0.005444645 0.01248615 0.04764312 -0.004621028 0.05782109 0.05664867 -0.00432384 0.08169853 0.06339913 -0.00410366 0.09959256 0.07073903 -0.003861308 0.119081 0.09139662 -0.00316888 0.1739732 0.101422 -0.002945959 0.185936 0.108846 -0.002674281 0.191924 0.09680497 -0.003143608 0.180051 0.117976 -0.002194285 0.197995 0.129818 -0.001436412 0.203128 0.1541141 -4.6266e-4 0.2099999 0.04042112 -0.005505323 0.01226627 0.04959207 -0.004706978 0.05782109 0.05969178 -0.004361808 0.08502012 0.05885845 -0.004485189 0.07885676 0.07237368 -0.003933012 0.1191079 0.0881958 -0.003481268 0.157992 0.09273391 -0.003228068 0.1739822 0.102601 -0.003000915 0.185939 0.109898 -0.00272417 0.191926 0.0980786 -0.003190815 0.1800529 0.118857 -0.002235174 0.197996 0.1543946 -4.76628e-4 0.21 0.1308724 -0.001477062 0.2031552 0.03539413 -0.005378842 0.01266962 0.04202991 -0.005529284 0.01214569 0.06080508 -0.004532873 0.07920366 0.06139171 -0.004430592 0.08474713 0.07402169 -0.003991305 0.1191713 0.0896207 -0.003522515 0.1580165 0.09407144 -0.003276586 0.1739937 0.0993511 -0.003228664 0.180055 0.103778 -0.003045976 0.1859419 0.104952 -0.003082215 0.185946 0.110945 -0.002765119 0.191929 0.119737 -0.002268731 0.197997 0.04455459 -0.005553364 0.0119639 0.05559265 -0.004771471 0.0630384 0.06273835 -0.004571676 0.07954818 0.06318545 -0.00448358 0.0847156 0.07561606 -0.004039824 0.1190893 0.09540826 -0.003315508 0.1740041 0.111989 -0.00279802 0.191933 0.1006219 -0.00325787 0.180057 0.120614 -0.002295672 0.197999 0.1546754 -4.87139e-4 0.2099999 0.1322036 -0.001511394 0.2031903 0.04276305 -0.005537927 0.01209199 0.05860066 -0.004714727 0.06895756 0.0646584 -0.004601538 0.07989037 0.06499338 -0.004524171 0.08471655 0.07717996 -0.004078686 0.1189174 0.09674888 -0.003345489 0.1740199 0.106122 -0.00311011 0.185949 0.113028 -0.002823412 0.191936 0.121489 -0.002316474 0.198 0.1550098 -4.96207e-4 0.2099999 0.05917966 -0.004790067 0.06570917 0.06656515 -0.004622519 0.08023017 0.06681191 -0.00455302 0.08474659 0.07876425 -0.00410664 0.1188008 0.09389823 -0.003591954 0.1580945 0.101893 -0.003278911 0.180059 0.09808844 -0.003367066 0.1740381 0.10729 -0.003130257 0.185953 0.114064 -0.002841711 0.1919389 0.103162 -0.003292441 0.180061 0.122362 -0.002331435 0.198001 0.1335397 -0.001529395 0.2032305 0.06014943 -0.004896163 0.0602675 0.06845879 -0.004634618 0.08056765 0.0686261 -0.004573047 0.08468306 0.07585525 -0.004558682 0.08473306 0.07223325 -0.004436135 0.09512209 0.09532475 -0.003599166 0.1581225 0.09942913 -0.003380894 0.17406 0.108455 -0.00314325 0.185957 0.115097 -0.002853572 0.191943 0.10443 -0.003299117 0.180064 0.123233 -0.002341091 0.1980029 0.1553634 -5.01679e-4 0.21 0.06081897 -0.004956662 0.0565114 0.07033908 -0.004637837 0.08090275 0.07043546 -0.004582226 0.08468288 0.07398748 -0.004445016 0.09512221 0.1007694 -0.003387689 0.1740843 0.109617 -0.003149688 0.185961 0.116127 -0.002859473 0.191946 0.1241019 -0.00234586 0.198004 0.1349032 -0.001529753 0.2032998 0.1557249 -5.03915e-4 0.21 0.07224869 -0.004581272 0.08477801 0.07220619 -0.004632115 0.08123558 0.08117496 -0.004231452 0.111365 0.102119 -0.003389954 0.173983 0.105697 -0.003299415 0.180066 0.110777 -0.003150045 0.185965 0.106963 -0.003293871 0.180069 0.124969 -0.002346158 0.198006 0.117153 -0.00285983 0.19195 0.06210589 -0.005047738 0.04929047 0.07404798 -0.004574 0.0847426 0.07405996 -0.004617512 0.08156597 0.08284372 -0.00422424 0.11137 0.111935 -0.00314486 0.18597 0.108229 -0.003282725 0.1800709 0.103458 -0.003384172 0.1739889 0.125835 -0.002342224 0.198007 0.135745 -0.001533031 0.203287 0.1181769 -0.002855122 0.191954 0.155929 -5.04174e-4 0.209996 0.06251347 -0.005069673 0.04700386 0.07590049 -0.004593968 0.08189409 0.09260237 -0.003918647 0.1316947 0.11309 -0.00313431 0.185974 0.1101024 -0.003257036 0.1800907 0.104797 -0.003372669 0.173995 0.1267 -0.002334356 0.198009 0.136413 -0.001527845 0.203307 0.119677 -0.002840101 0.1919596 0.156132 -5.04064e-4 0.2099879 0.06561708 -0.005026459 0.04755705 0.07766878 -0.004535734 0.08474016 0.07772779 -0.004561543 0.08221977 0.106136 -0.003355741 0.174 0.114773 -0.003110408 0.1859822 0.1275629 -0.002322673 0.19801 0.156333 -5.03313e-4 0.209975 0.07950127 -0.004505217 0.08478385 0.07954186 -0.004520237 0.08254307 0.07994401 -0.004526615 0.08028656 0.08784967 -0.004161119 0.111383 0.1081338 -0.003321409 0.1740385 0.1216912 -0.002803862 0.1919667 0.128424 -0.002307474 0.1980119 0.137082 -0.001520216 0.203329 0.137753 -0.001510202 0.20335 0.06177288 -0.005356967 0.01093482 0.0699523 -0.004942893 0.04832971 0.1100381 -0.003278315 0.1738655 0.1170744 -0.003060936 0.1859923 0.1126351 -0.003204762 0.1801002 0.156532 -5.01923e-4 0.209958 0.138424 -0.001497983 0.203372 0.129285 -0.002288937 0.198014 0.09452259 -0.00399369 0.111403 0.09729701 -0.003824591 0.1317627 0.1151738 -0.003134846 0.1801142 0.130145 -0.002267181 0.198015 0.139097 -0.001483738 0.203395 0.123705 -0.002751827 0.1919752 0.156729 -4.99892e-4 0.209936 0.08757531 -0.004266619 0.09362953 0.09886181 -0.003782749 0.1317861 0.1004264 -0.003736197 0.1318096 0.1113806 -0.003242492 0.1738985 0.1193667 -0.002995133 0.1860022 0.131003 -0.002242505 0.198017 0.13977 -0.001467525 0.203417 0.156924 -4.97221e-4 0.209909 0.0841788 -0.004451155 0.07016468 0.1019909 -0.003685176 0.1318333 0.1216537 -0.002914667 0.1860126 0.1127232 -0.003202676 0.1739174 0.131862 -0.002215027 0.198019 0.1257166 -0.002685606 0.1919836 0.140444 -0.001449525 0.20344 0.08576077 -0.004395246 0.07044661 0.09619045 -0.003939092 0.1114079 0.1035553 -0.003629863 0.1318571 0.1140621 -0.003159105 0.1739358 0.157117 -4.9391e-4 0.209878 0.141118 -0.001429736 0.203463 0.132719 -0.002184867 0.1980209 0.08012396 -0.004645287 0.05014258 0.08414471 -0.004457473 0.06812709 0.08217376 -0.004523932 0.06777578 0.09785813 -0.003880023 0.111413 0.1051195 -0.003570616 0.1318808 0.1110225 -0.003300547 0.1584734 0.1277214 -0.002607047 0.1919921 0.133576 -0.002152204 0.198022 0.141793 -0.001408338 0.203486 0.157307 -4.89958e-4 0.209843 0.08058619 -0.004636108 0.04290038 0.09638124 -0.003956198 0.093629 0.09952551 -0.003816664 0.1114175 0.106684 -0.003507614 0.1319049 0.11245 -0.003246665 0.158508 0.1167378 -0.003061473 0.1739584 0.134432 -0.002117156 0.198024 0.157496 -4.85366e-4 0.209803 0.101193 -0.00374931 0.111423 0.109812 -0.003371238 0.1319526 0.1082477 -0.003441095 0.1319287 0.1138765 -0.003189384 0.158542 0.1255105 -0.0027498 0.1860129 0.1180764 -0.00300765 0.1739684 0.142468 -0.001385331 0.20351 0.135289 -0.002079904 0.198026 0.1431429 -0.001360893 0.2035329 0.09754639 -0.003906905 0.0913906 0.1028605 -0.003678202 0.111428 0.115303 -0.003128945 0.158576 0.1194117 -0.002951025 0.1739868 0.1361449 -0.002040565 0.198028 0.143818 -0.001335144 0.203556 0.157683 -4.80134e-4 0.209758 0.09931874 -0.003827571 0.09139072 0.1045275 -0.003603518 0.111433 0.1167294 -0.003065407 0.1586099 0.1207557 -0.002891123 0.1739933 0.137001 -0.001999258 0.1980299 0.157867 -4.74261e-4 0.209709 0.1010912 -0.003744542 0.0913906 0.1061944 -0.003525376 0.111438 0.1113753 -0.003298103 0.1319765 0.118156 -0.002998948 0.158644 0.1220912 -0.002828776 0.1739997 0.144493 -0.001308083 0.203579 0.137858 -0.001956045 0.198031 0.145168 -0.001279711 0.203603 0.1028633 -0.003657937 0.09139043 0.107861 -0.003443896 0.111443 0.1129388 -0.003221869 0.1320002 0.1095275 -0.003359138 0.111448 0.1145023 -0.003142595 0.1320238 0.1207487 -0.002878844 0.163255 0.1240478 -0.002732992 0.1740456 0.138714 -0.001910924 0.198033 0.145842 -0.001250147 0.203626 0.15805 -4.67749e-4 0.209655 0.09641516 -0.003921329 0.05782067 0.1029922 -0.003638148 0.08467727 0.1069427 -0.003451704 0.09362864 0.121008 -0.002857506 0.158711 0.1256091 -0.002652764 0.1740877 0.158233 -4.608e-4 0.209596 0.1012257 -0.003695547 0.06975734 0.111194 -0.003271222 0.1114529 0.1160652 -0.00306034 0.1320467 0.1235492 -0.002734541 0.1633102 0.147188 -0.001187562 0.203671 0.1003139 -0.003712534 0.05782067 0.1066067 -0.003444433 0.0846771 0.1128605 -0.003180265 0.1114575 0.1176281 -0.002975285 0.1320704 0.1259629 -0.002596795 0.161989 0.1249495 -0.002658486 0.1633372 0.1283144 -0.002505064 0.174102 0.158415 -4.53322e-4 0.209533 0.1478599 -0.001154601 0.203693 0.141288 -0.001765072 0.198038 0.09952652 -0.003719747 0.04588454 0.1046562 -0.003501176 0.06826502 0.11114 -0.003228425 0.09660202 0.1168572 -0.002987444 0.1217762 0.1171697 -0.002948641 0.115893 0.1281226 -0.002471983 0.1621339 0.1585969 -4.45277e-4 0.209466 0.1037102 -0.003511309 0.05558264 0.1092208 -0.003279507 0.08020198 0.110833 -0.003159463 0.07420146 0.1132205 -0.00311321 0.09810286 0.1196967 -0.002832114 0.1256309 0.153017 -8.81097e-4 0.18612 0.150631 -0.001078605 0.186116 0.1309739 -0.002350628 0.174117 0.1587769 -4.36663e-4 0.209394 0.1033862 -0.003490209 0.04513859 0.1154111 -0.002990782 0.1007643 0.1302306 -0.002344608 0.1622754 0.149869 -0.001049399 0.203758 0.103794 -0.003416419 0.03336024 0.1316416 -0.002256989 0.1623692 0.1336591 -0.002186059 0.1741309 0.158956 -4.27481e-4 0.209318 0.150536 -0.001012384 0.203779 0.144731 -0.001548111 0.198045 0.133691 -0.002126336 0.1625068 0.145595 -0.001490175 0.198047 0.151201 -9.7446e-4 0.2038 0.159134 -4.17732e-4 0.209237 0.1363225 -0.002013802 0.1740399 0.159313 -4.07844e-4 0.209149 0.1366717 -0.001928269 0.162707 0.159491 -3.97699e-4 0.209056 0.142347 -0.001719415 0.1860952 0.1449502 -0.001566886 0.1920597 0.1393033 -0.001745998 0.1628838 0.159668 -3.87159e-4 0.208958 0.144149 -0.001586258 0.1860989 0.1598449 -3.76225e-4 0.208855 0.1469953 -0.001412272 0.1920648 0.1410815 -0.001618802 0.1630033 0.145907 -0.001452982 0.1861039 0.160022 -3.64896e-4 0.208746 0.1440948 -0.001396119 0.1632059 0.160197 -3.53172e-4 0.2086319 0.1482615 -0.0012694 0.1861104 0.160376 -3.41085e-4 0.208506 0.156453 -6.39897e-4 0.203939 0.1457641 -0.001268327 0.163317 0.160558 -3.28634e-4 0.208369 0.1477651 -0.001111984 0.1634516 0.160741 -3.15803e-4 0.208223 0.160925 -3.02593e-4 0.208069 0.16111 -2.89002e-4 0.207907 0.1505513 -8.86822e-4 0.163639 0.161462 -2.6253e-4 0.207579 0.161296 -2.75032e-4 0.207737 0.151412 -8.5382e-4 0.1681964 0.1615999 -2.51977e-4 0.20744 0.152827 -6.96901e-4 0.163792 0.1617259 -2.42066e-4 0.207304 0.154147 -6.23365e-4 0.168211 0.1542389 -5.76477e-4 0.163886 0.157236 -5.1772e-4 0.1861259 0.162039 -2.1618e-4 0.206918 0.1619459 -2.24167e-4 0.2070429 0.1565075 -3.79285e-4 0.1640386 0.159711 -3.84659e-4 0.198063 0.162244 -1.98509e-4 0.206633 0.162135 -2.07852e-4 0.206784 0.1599014 -1.91812e-4 0.177177 0.162351 -1.89148e-4 0.206476 0.16163 -1.70635e-4 0.1920959 0.162663 -1.60955e-4 0.205979 0.160902 -1.8558e-4 0.186129 0.1630229 -1.26351e-4 0.205271 0.161152 -7.63042e-5 0.176571 0.161785 -7.25199e-5 0.1827239 0.1624169 -6.55696e-5 0.188877 0.1630499 -5.54534e-5 0.195029 0.163378 -8.94188e-5 0.204328 0.124581 -0.001813411 0.01289826 0.122346 -0.001987159 0.01265716 0.104977 0 0.01078379 0.126814 0.001636743 0.01313906 0.1268129 -0.001636683 0.01313906 0.124582 0.001813471 0.01289838 0.129042 0.001457035 0.01337945 0.129042 -0.001456975 0.01337945 0.131267 -0.001274287 0.01361948 0.131267 0.001274406 0.01361948 0.133489 0.001088738 0.01385915 0.133489 -0.001088678 0.01385909 0.135708 9.00136e-4 0.01409834 0.135707 -9.00058e-4 0.01409834 0.137922 -7.08453e-4 0.0143373 0.137923 7.08537e-4 0.01433736 0.140134 5.13962e-4 0.01457589 0.140134 -5.13872e-4 0.01457589 0.142343 3.16413e-4 0.01481407 0.142342 -3.16316e-4 0.01481407 0.144547 -1.15784e-4 0.0150519 0.144547 1.15888e-4 0.0150519 0.122346 0.001987218 0.01265728 0.104852 -4.75918e-4 0.01077026 0.120107 -0.002157926 0.01241576 0.104759 -6.14183e-4 0.01076024 0.104963 1.64624e-4 0.01078218 0.104508 -8.37137e-4 0.01073318 0.11562 -0.00249058 0.01193165 0.104358 -9.15744e-4 0.01071697 0.104921 3.24729e-4 0.01077765 0.111119 -0.002811312 0.01144617 0.104197 -9.69371e-4 0.01069957 0.113371 -0.002652406 0.01168918 0.120108 0.002157986 0.01241576 0.104028 -9.96555e-4 0.01068145 0.1088629 -0.002967178 0.01120299 0.104852 4.75977e-4 0.01077026 0.106604 -0.003120124 0.01095926 0.104759 6.14242e-4 0.01076024 0.104342 -0.003270089 0.01071524 0.103857 -9.96555e-4 0.01066297 0.117866 0.002325773 0.01217395 0.102076 -0.003417015 0.01047086 0.0998069 -0.003561019 0.01022607 0.104643 7.35753e-4 0.01074779 0.103377 -8.37137e-4 0.01061129 0.103242 -7.35695e-4 0.01059669 0.104508 8.37196e-4 0.01073318 0.104358 9.15803e-4 0.01071697 0.11562 0.002490639 0.01193177 0.102909 0 0.01056069 0.0998069 0.003561079 0.01022607 0.106604 0.003120183 0.01095926 0.104028 9.96614e-4 0.01068145 0.103857 9.96614e-4 0.01066297 0.111119 0.002811312 0.01144629 0.1088629 0.002967238 0.01120299 0.103033 4.75977e-4 0.01057416 0.1029649 3.24729e-4 0.01056677 0.113371 0.002652466 0.01168918 0.104197 9.6943e-4 0.01069957 0.104342 0.003270089 0.01071524 0.102076 0.003417074 0.01047086 0.103689 9.6943e-4 0.01064485 0.103377 8.37196e-4 0.01061129 0.103527 9.15803e-4 0.01062744 0.103127 6.14242e-4 0.01058417 0.103242 7.35753e-4 0.01059669 0.102923 1.64624e-4 0.0105623 0.102923 -1.64565e-4 0.0105623 0.1029649 -3.2467e-4 0.01056677 0.103033 -4.75918e-4 0.01057416 0.103127 -6.14183e-4 0.01058417 0.103527 -9.15744e-4 0.01062744 0.103689 -9.69371e-4 0.01064485 0.117865 -0.002325773 0.01217389 0.104643 -7.35695e-4 0.01074779 0.104921 -3.2467e-4 0.01077765 0.104963 -1.64565e-4 0.01078218 0.102169 0 0.006267428 0.1033959 9.6943e-4 0.006055891 0.10355 9.15803e-4 0.006029367 0.102758 9.15803e-4 0.006165802 0.1023769 6.14242e-4 0.006231606 0.102487 7.35753e-4 0.006212592 0.1026149 8.37196e-4 0.006190478 0.102912 9.6943e-4 0.006139278 0.102288 4.75977e-4 0.006246984 0.102222 3.24729e-4 0.006258249 0.103073 9.96614e-4 0.006111621 0.103236 9.96614e-4 0.006083548 0.102182 1.64624e-4 0.006265103 0.102288 -4.75717e-4 0.006246984 0.102222 -3.24516e-4 0.006258249 0.103822 7.35753e-4 0.005982577 0.103693 8.37196e-4 0.006004691 0.102182 -1.64611e-4 0.006265103 0.103932 6.14242e-4 0.005963563 0.104021 4.75977e-4 0.005948185 0.102376 -6.1396e-4 0.006231665 0.102758 -9.15584e-4 0.006165862 0.104126 1.64624e-4 0.005930066 0.10414 0 0.005927741 0.102487 -7.35473e-4 0.006212651 0.104086 3.24729e-4 0.00593692 0.1026149 -8.36938e-4 0.006190538 0.104086 -3.24757e-4 0.00593692 0.104021 -4.76037e-4 0.005948245 0.103235 -9.96562e-4 0.006083607 0.104126 -1.64611e-4 0.005930066 0.103073 -9.96504e-4 0.006111681 0.102912 -9.69263e-4 0.006139338 0.103822 -7.35836e-4 0.005982577 0.103693 -8.37266e-4 0.006004691 0.10355 -9.15845e-4 0.006029427 0.1033959 -9.6943e-4 0.006055951 0.103932 -6.14321e-4 0.005963563 0.102923 1.64624e-4 0.0105623 0.102169 0 0.006267428 0.102909 0 0.01056069 0.1023769 6.14242e-4 0.006231606 0.102288 4.75977e-4 0.006246984 0.103127 6.14242e-4 0.01058417 0.103033 4.75977e-4 0.01057416 0.102222 3.24729e-4 0.006258249 0.1029649 3.24729e-4 0.01056677 0.1026149 8.37196e-4 0.006190478 0.103527 9.15803e-4 0.01062744 0.102758 9.15803e-4 0.006165802 0.103242 7.35753e-4 0.01059669 0.103377 8.37196e-4 0.01061129 0.102487 7.35753e-4 0.006212592 0.104028 9.96614e-4 0.01068145 0.103236 9.96614e-4 0.006083548 0.103073 9.96614e-4 0.006111621 0.103857 9.96614e-4 0.01066297 0.102912 9.6943e-4 0.006139278 0.103689 9.6943e-4 0.01064485 0.103693 8.37196e-4 0.006004691 0.10355 9.15803e-4 0.006029367 0.104508 8.37196e-4 0.01073318 0.1033959 9.6943e-4 0.006055891 0.104197 9.6943e-4 0.01069957 0.104358 9.15803e-4 0.01071697 0.104852 4.75977e-4 0.01077026 0.104921 3.24729e-4 0.01077765 0.104021 4.75977e-4 0.005948185 0.104759 6.14242e-4 0.01076024 0.103932 6.14242e-4 0.005963563 0.103822 7.35753e-4 0.005982577 0.104963 -1.64565e-4 0.01078218 0.10414 0 0.005927741 0.104977 0 0.01078379 0.104126 1.64624e-4 0.005930066 0.104086 3.24729e-4 0.00593692 0.104963 1.64624e-4 0.01078218 0.104021 -4.76037e-4 0.005948245 0.104852 -4.75918e-4 0.01077026 0.104759 -6.14183e-4 0.01076024 0.104126 -1.64611e-4 0.005930066 0.104921 -3.2467e-4 0.01077765 0.104086 -3.24757e-4 0.00593692 0.104508 -8.37137e-4 0.01073318 0.104358 -9.15744e-4 0.01071697 0.103693 -8.37266e-4 0.006004691 0.104643 -7.35695e-4 0.01074779 0.103822 -7.35836e-4 0.005982577 0.103932 -6.14321e-4 0.005963563 0.104028 -9.96555e-4 0.01068145 0.103235 -9.96562e-4 0.006083607 0.1033959 -9.6943e-4 0.006055951 0.104197 -9.69371e-4 0.01069957 0.10355 -9.15845e-4 0.006029427 0.103857 -9.96555e-4 0.01066297 0.103689 -9.69371e-4 0.01064485 0.103073 -9.96504e-4 0.006111681 0.102912 -9.69263e-4 0.006139338 0.103527 -9.15744e-4 0.01062744 0.103377 -8.37137e-4 0.01061129 0.102758 -9.15584e-4 0.006165862 0.103242 -7.35695e-4 0.01059669 0.1026149 -8.36938e-4 0.006190538 0.102487 -7.35473e-4 0.006212651 0.103127 -6.14183e-4 0.01058417 0.103033 -4.75918e-4 0.01057416 0.102376 -6.1396e-4 0.006231665 0.1029649 -3.2467e-4 0.01056677 0.102288 -4.75717e-4 0.006246984 0.102222 -3.24516e-4 0.006258249 0.102923 -1.64565e-4 0.0105623 0.102182 -1.64611e-4 0.006265103 0.104643 7.35753e-4 0.01074779 0.102182 1.64624e-4 0.006265103 + + + + + + + + + + -1.26818e-6 -0.7070968 -0.7071169 6.89531e-7 -0.7071048 -0.7071089 -5.44931e-6 -0.7070932 -0.7071204 -6.19489e-7 -0.7069699 -0.7072438 1.45185e-6 -0.7071837 -0.7070298 -7.68973e-7 -0.7069893 -0.7072244 3.71636e-5 -0.7076008 -0.7066124 -4.05165e-6 -0.7070479 -0.7071657 0 -0.7071068 -0.7071068 -1.65442e-6 -0.7071219 -0.7070917 0 -0.7071066 -0.707107 1.80067e-6 -0.7071046 -0.707109 1.40682e-6 -0.7071031 -0.7071106 -1.4814e-6 -0.7071085 -0.7071051 3.47526e-6 -0.7070599 -0.7071537 1 0 0 0.02392834 -0.7069043 0.7069043 0.02392834 -0.7069043 0.7069043 -1 0 0 0.04312396 0.7069524 -0.7059453 0.04242146 0.7068212 -0.7061192 0.03607392 0.7068297 -0.7064635 0.04612922 0.7063523 -0.7063558 0.0464726 0.7066799 -0.7060056 0.03470075 0.7060397 -0.7073216 0.03192365 0.706319 -0.7071735 0.02984762 0.6943701 -0.7189989 0.02966457 0.68726 -0.7258056 0.02966487 0.6858633 -0.7271256 0.03018313 0.7003467 -0.7131645 0.03003102 0.6982217 -0.7152515 0.03058034 0.7031657 -0.7103682 0.03039711 0.7020031 -0.711525 0.03100752 0.7049027 -0.708626 0.03076344 0.7038975 -0.7096351 0.03122168 0.7055861 -0.7079361 0.1023608 0.9945844 -0.0180062 0.2537373 0.9662407 -0.04468023 0.1714264 0.9847326 -0.03024452 0.3926255 0.9170925 -0.06918627 0.3372923 0.9395171 -0.05951136 0.4927322 0.8658292 -0.08691859 0.5317665 0.8416889 -0.09372442 0.6329649 0.766089 -0.1116386 0.6532423 0.7483415 -0.1151506 0.7541505 0.6430925 -0.133001 0.7553148 0.6416926 -0.1331544 0.8529001 0.4999412 -0.1504005 0.8372316 0.5265467 -0.147621 0.9001001 0.4057515 -0.1586993 0.9253912 0.3420853 -0.163184 0.9725787 0.1571422 -0.1714556 0.9697884 0.1739558 -0.171026 0.9449077 0.2817846 -0.1665742 0.981053 0.08719182 -0.1730103 0.9828609 0.06289941 -0.1732863 1.83111e-4 1 -6.1037e-5 -0.06369286 0.997906 0.01126146 -0.1705722 0.9848875 0.03003096 -0.3364701 0.9398273 0.05926752 -0.2140314 0.976097 0.03775227 -0.4919101 0.866321 0.0866748 -0.3599458 0.9308111 0.06348031 -0.5034461 0.8594534 0.08878058 -0.6331177 0.7659671 0.1116082 -0.6285066 0.7698701 0.1108142 -0.7547376 0.6423968 0.1330327 -0.8198032 0.5541042 0.1445383 -0.7336293 0.6671272 0.1293419 -0.888158 0.4320241 0.1566224 -0.8521848 0.5012152 0.150215 -0.925028 0.343124 0.1630625 -0.9386398 0.3025951 0.165504 -0.9698088 0.1738984 0.1709685 -0.9701088 0.1721274 0.1710592 -0.981023 0.08764964 0.1729493 -0.9823213 0.07104867 0.1731964 -0.0112617 0.7076873 -0.706436 -0.01174992 0.7078358 -0.7062793 -0.002044796 0.7075935 -0.7066169 0.005615592 0.7069278 -0.7072635 -0.00375384 0.7071629 -0.7070408 0.008057057 0.7076787 -0.7064885 -0.14884 0.6926845 -0.705716 -0.1471628 0.6943389 -0.7044407 -0.1334614 0.6948661 -0.7066466 -0.1198168 0.6968362 -0.7071515 -0.1176205 0.6955909 -0.7087447 -0.1052904 0.6979383 -0.7083758 -0.08597248 0.6999267 -0.7090215 -0.09210646 0.700107 -0.7080726 -0.07641911 0.701628 -0.7084337 -0.06463885 0.7037333 -0.7075177 -0.05472093 0.705452 -0.7066423 -0.04831218 0.707257 -0.7053038 -0.03592121 0.7096046 -0.7036839 -0.02005106 0.7139644 -0.699895 -0.009094715 0.7188799 -0.6950749 0.02703821 0.7108261 -0.7028479 -0.005798637 0.7144269 -0.6996861 0.02002048 0.712316 -0.7015733 0.01989853 0.7152193 -0.6986169 -0.005005121 0.7183299 -0.6956847 -0.01104784 0.7075213 -0.7066057 -0.004059076 0.7104046 -0.7037818 -0.01638871 0.7702403 -0.6375433 0.002105772 0.7745753 -0.6324783 0.004455745 0.7077708 -0.7064281 0.01434403 0.710368 -0.7036843 0.02160739 0.7066059 -0.7072773 0.02121084 0.7073138 -0.7065814 0.02017331 0.7108283 -0.7030763 0.02035605 0.7097777 -0.7041317 0.02060067 0.7088464 -0.705062 0.02087527 0.7080506 -0.7058532 0.01986825 0.7158982 -0.6979221 -0.1613255 0.6926985 -0.7029531 -0.1798787 0.6909187 -0.7001964 -0.1891259 0.690827 -0.6978463 -0.1741416 0.6923853 -0.7001982 -0.2002983 0.6904386 -0.6951081 -0.1967291 0.6904444 -0.696121 -0.2087495 0.6915286 -0.6915286 -0.7115371 0.4955794 -0.4981126 -0.6809476 0.5182489 -0.517425 -0.6394664 0.542782 -0.5444911 -0.2204381 0.6891784 -0.6902465 -0.2239813 0.6891264 -0.6891569 -0.2142425 0.6900622 -0.6913135 -0.7825989 0.4389854 -0.4413964 -0.7373734 0.4781436 -0.4771365 -0.7908438 0.4329757 -0.4325485 -0.849067 0.3721783 -0.374925 -0.8789891 0.3372393 -0.3371172 -0.8381869 0.3854915 -0.3857967 -0.9059355 0.2975634 -0.3012257 -0.9119763 0.2899024 -0.2902686 -0.9355612 0.248486 -0.2509581 -0.9493969 0.219648 -0.2245005 -0.9542746 0.2110098 -0.2117422 -0.9645916 0.1845194 -0.1884564 -0.9720121 0.1648963 -0.1673378 -0.9670983 0.1769208 -0.1828111 -0.9781035 0.1471626 -0.1471626 -0.623987 0.5526341 -0.5524815 -0.5689781 0.5814607 -0.5815217 -0.5693059 0.5807201 -0.5819409 -0.5173291 0.6053156 -0.6049494 -0.5047362 0.6096938 -0.6111587 -0.4699022 0.6244814 -0.623871 -0.446891 0.6318367 -0.6333016 -0.394892 0.64915 -0.6501267 -0.4270256 0.6396228 -0.639165 -0.355062 0.6608964 -0.661171 -0.3886908 0.6514295 -0.6515821 -0.325577 0.6686415 -0.6685194 -0.3506051 0.66181 -0.662634 -0.3139482 0.6708977 -0.6718133 -0.3002787 0.674597 -0.6743528 -0.2785177 0.6791121 -0.6791426 -0.282667 0.6779797 -0.6785596 -0.2605767 0.6826022 -0.6827548 -0.2588299 0.6828275 -0.6831938 -0.2458633 0.6854934 -0.6853103 -0.2403688 0.6862535 -0.6864976 -0.2338996 0.6876295 -0.6873549 -0.2051828 0.6908097 -0.6933123 -0.202463 0.6909808 -0.6939411 -0.1773793 0.6935859 -0.6981943 -0.1750901 0.6937379 -0.698621 -0.1864114 0.6926034 -0.6968151 -0.1887328 0.6922441 -0.6965474 -0.1957538 0.6917611 -0.6950878 -0.1611401 0.6954355 -0.7002881 -0.1588553 0.6958504 -0.7003979 -0.1499422 0.6970344 -0.701185 -0.1680992 0.6947674 -0.6993147 -0.147133 0.6974552 -0.7013617 -0.1321809 0.6992677 -0.7025333 -0.1333373 0.6993722 -0.7022106 -0.140572 0.6981296 -0.7020361 -0.1144771 0.7020003 -0.7029159 -0.1065744 0.7030797 -0.7030797 -0.1190551 0.7013601 -0.7027945 -0.1232972 0.7008105 -0.7026112 -0.09082496 0.7051144 -0.7032528 -0.09073412 0.7054859 -0.7028918 -0.1049243 0.7034935 -0.7029137 -0.09811896 0.7041677 -0.7032216 -0.06238114 0.708167 -0.7032839 -0.07672643 0.7070186 -0.7030205 -0.06863754 0.7078918 -0.7029782 -0.08282941 0.7060642 -0.703287 -0.07602369 0.7068588 -0.7032575 -0.05499553 0.7088997 -0.7031621 -0.06164872 0.7085032 -0.7030097 -0.04849451 0.7091986 -0.703339 -0.04822057 0.708904 -0.7036547 -0.04214692 0.7092655 -0.7036805 -0.03384625 0.7091542 -0.7042406 -0.01992911 0.7085669 -0.7053623 -0.0358299 0.7088163 -0.7044826 -0.02575814 0.7085031 -0.7052375 -0.0306105 0.7084063 -0.7051408 -0.01202458 0.7079554 -0.7061548 -0.07185381 0.7075529 -0.7029979 -1 0 0 0 -0.7071067 -0.7071068 0 -0.707107 -0.7071067 0 -0.7071064 -0.7071072 0 -0.7071065 -0.7071071 0 -0.7071071 -0.7071065 0 -0.7071066 -0.707107 0 -0.7071068 -0.7071068 0 -0.7071066 -0.707107 0 -0.7071067 -0.7071069 0 -0.7071069 -0.7071067 0 -0.7071066 -0.707107 0 -0.707107 -0.7071066 0 -0.7071072 -0.7071065 0 -0.7071065 -0.7071072 0 -0.7071061 -0.7071076 0 -0.7071074 -0.7071062 0 -0.7071071 -0.7071065 0 -0.7071067 -0.7071068 0 -0.707107 -0.7071067 1 4.99857e-6 0 1 4.68469e-6 0 1 -2.07077e-5 0 1 0 0 1 2.20065e-5 0 1 4.21122e-6 0 1 -2.26191e-5 0 1 -1.30948e-6 0 1 -1.96897e-5 0 0 0.7071073 -0.7071063 0 0.7071065 -0.7071071 1 1.22084e-6 0 1 -9.81884e-6 0 1 1.93789e-5 0 1 1.24896e-5 0 1 -1.25439e-5 0 0.0461291 0.7077959 -0.7049093 0.03897315 0.7049961 -0.7081396 0.03640919 0.706638 -0.706638 0.04086494 0.7054472 -0.7075836 0.03689759 0.7076469 -0.7056021 0.03534162 0.70726 -0.7060697 0.04098773 0.707138 -0.7058867 0.04297065 0.7077038 -0.7052013 0.03283894 0.7058245 -0.7076252 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.9848052 -2.67412e-4 0.1736622 -0.9848089 -5.21096e-4 0.1736416 -0.9848108 -8.36056e-4 0.1736291 -0.9848061 8.44514e-5 0.1736579 -0.9848071 -2.59823e-4 0.1736521 -0.984808 3.00254e-5 0.1736473 -0.9848081 3.51538e-5 0.1736464 -0.9848078 -1.35675e-5 0.1736483 -0.9848079 1.33988e-5 0.1736474 -0.9848082 0 0.1736464 -0.9848073 -1.39399e-4 0.1736507 -0.9848093 2.35668e-5 0.1736396 -0.9848092 1.25436e-5 0.17364 -0.9848082 -2.48039e-5 0.1736457 -0.9848092 -7.85195e-7 0.1736398 -0.9848098 2.49771e-5 0.1736369 -0.9848088 2.45021e-5 0.1736426 -0.9848114 1.84333e-5 0.1736282 -0.9848034 -4.96117e-5 0.1736732 -0.9848091 -3.61563e-5 0.1736408 -0.1734635 0 -0.9848403 -0.1730488 -7.46571e-4 -0.9849129 -0.1737706 2.23942e-4 -0.9847862 -0.1742169 6.7181e-4 -0.9847071 -0.1724895 -0.001128673 -0.9850108 -0.1740168 -0.003655314 -0.984736 -0.173572 0.002334594 -0.9848184 -0.1727135 0.009987831 -0.9849215 -0.1728641 4.31083e-5 -0.9849457 -0.1739985 -0.006319284 -0.9847257 -0.1734684 0.003269195 -0.9848341 -0.1735631 -0.001309156 -0.984822 -0.1736559 -0.001278817 -0.9848057 -0.1734866 7.98075e-4 -0.9848359 -0.1738042 -8.09007e-4 -0.98478 -0.173669 9.15055e-4 -0.9848037 -0.174346 -4.66377e-4 -0.9846844 -0.1737973 -7.98387e-5 -0.9847815 -0.175185 -0.001887083 -0.9845338 -0.1719805 0.001593053 -0.9850991 -0.1732041 8.975e-4 -0.9848856 -0.1744346 0 -0.9846689 0.9848076 2.64142e-5 -0.1736494 0.9848073 8.1857e-6 -0.1736511 0.9848079 5.44491e-6 -0.1736477 0.9848087 -5.47729e-6 -0.1736431 0.9848077 6.22025e-6 -0.1736485 0.9848074 3.10964e-5 -0.1736506 0.9848074 4.34869e-5 -0.1736502 0.9848088 -1.46552e-4 -0.1736425 0.9848073 1.30581e-4 -0.1736512 0.9848074 4.93682e-5 -0.1736506 0.984807 2.2431e-4 -0.1736523 0.9848087 -1.94334e-4 -0.1736429 0.984809 -3.82577e-4 -0.1736413 0.984808 -2.53033e-5 -0.1736467 0.9848014 -0.001196324 -0.1736803 0.9848183 0.001845717 -0.1735786 0.984812 2.60308e-4 -0.1736239 0.9847882 -0.002364873 -0.173743 0.9848086 -7.49407e-5 -0.1736438 0.9848063 -2.01402e-4 -0.1736565 0.9848136 0 -0.1736151 0.9848093 -4.978e-5 -0.1736395 0.9848094 -1.35192e-5 -0.1736392 0.05749875 0.544224 0.8369672 0.0566433 0.5766269 0.8150417 0.05487287 0.5948736 0.8019441 0.0603969 0.4684044 0.8814474 0.06436556 0.4348109 0.8982185 0.05920672 0.4919652 0.8685994 0.05844384 0.5321292 0.8446437 0.05408048 0.5834408 0.8103531 0.06177079 0.4524165 0.889665 0.05847465 0.4321206 0.8999181 0.06347894 0.4113927 0.909245 0.06372302 0.411087 0.9093661 0.06387645 0.4109702 0.9094082 0.0546301 0.6033731 0.7955857 0.05234062 0.6141402 0.7874594 0.05118113 0.5994334 0.7987866 0.06320488 0.4375206 0.8969843 0.06229007 0.4316357 0.8998948 0.06250298 0.431753 0.8998237 0.06357121 0.4373384 0.8970474 -0.9844868 2.67761e-5 -0.1754584 -0.9844891 0 -0.1754463 -0.9844847 -2.56261e-5 -0.1754707 -0.9844864 -1.44229e-5 -0.1754617 -0.9844878 3.04291e-5 -0.1754531 -0.9844858 -1.68475e-5 -0.1754646 -0.9844839 7.01197e-5 -0.1754754 -0.9844844 -5.44562e-5 -0.1754721 -0.9844865 -8.04572e-7 -0.1754611 -0.9844866 6.6423e-6 -0.1754601 -0.9844879 -2.31898e-5 -0.1754525 -0.984485 2.043e-5 -0.1754691 -0.9844833 2.04987e-5 -0.1754788 -0.9844863 -2.97393e-5 -0.1754617 -0.1754444 0 0.9844894 -0.1755018 0 0.9844791 -0.1754721 -1.08165e-5 0.9844845 -0.1754707 -1.0667e-5 0.9844847 -0.9844838 0 -0.1754755 -0.9844837 0 -0.1754759 -0.1754791 0 0.9844832 -0.1754758 0 0.9844838 -0.1754763 7.46784e-7 0.9844837 0.1754102 0 -0.9844955 0.1754516 0 -0.9844881 0.1754317 -6.20305e-6 -0.9844917 0.9844866 8.86748e-6 0.1754597 0.9844868 1.42854e-5 0.1754592 0.9844868 -1.97555e-5 0.1754587 0.9844872 0 0.1754568 0.9844853 -3.07377e-5 0.1754676 0.984486 -1.02275e-5 0.1754632 0.9844874 0 0.1754558 0.984489 0 0.1754462 0.9844877 5.0961e-6 0.1754539 0.9844894 -2.56324e-5 0.1754446 0.9844853 1.82177e-5 0.1754674 0.9844851 3.21956e-5 0.1754685 0.984485 5.04236e-5 0.1754692 0.9844853 3.8101e-5 0.1754673 0.9844853 4.37376e-5 0.1754669 0.9844863 1.49853e-6 0.1754618 0.9844855 -2.86223e-5 0.1754662 0.9844866 0 0.1754599 0.06137478 0.3770383 0.9241619 0.0619536 0.3444684 0.9367515 0.06174015 0.3057099 0.9501209 0.06030642 0.3984925 0.9151868 0.06091618 0.3772165 0.9241195 0.05826091 -0.459953 0.8860298 0.05700999 -0.4973421 0.8656793 0.05826175 -0.4627979 0.8845472 0.06348025 0.3221928 0.9445434 0.06293016 0.3289642 0.9422433 0.0605508 0.4020038 0.9136338 0.0643959 0.2945733 0.9534567 0.06488442 0.33486 0.9400313 0.0646401 0.3123968 0.94775 0.05374491 0.6151829 0.7865504 0.05453747 0.6297909 0.7748479 0.05466079 0.6309955 0.7738584 0.06332719 0.2695754 0.9608948 0.06534177 0.2794345 0.9579389 0.06228852 0.2772617 0.9587733 0.0628997 0.2148234 0.9746254 0.06283897 0.2161979 0.9743252 0.06289988 0.1934912 0.9790837 0.06287014 0.2038092 0.97699 0.06305253 0.1766142 0.9822585 0.06296044 0.184975 0.9807245 0.06290018 0.1454853 0.987359 0.0631746 0.1691066 0.9835711 0.06235104 0.1495754 0.9867825 0.06225854 0.1399292 0.9882023 0.06222742 0.1320235 0.9892915 0.062258 0.1251875 0.9901778 0.06238067 0.1191154 0.9909189 0.06253373 0.1145689 0.9914453 0.06369346 0.06515836 0.9958401 0.06308352 0.08780425 0.9941383 0.06314432 0.1149965 0.991357 0.06396722 0.03088492 0.997474 0.06369304 -0.02813845 0.9975728 0.063784 0.0137639 0.9978688 0.06332755 0.00476098 0.9979814 0.0630216 -0.004944026 0.998 0.06277662 -0.01803642 0.9978647 0.0626862 -0.0291152 0.9976086 0.06268835 -0.02944922 0.9975987 0.06265628 -0.041781 0.9971603 0.06274658 -0.05740582 0.9963772 0.06295984 -0.07794451 0.9949678 0.06250286 -0.09039723 0.9939426 0.06228935 -0.1300417 0.9895501 0.06225895 -0.09976696 0.9930612 0.06198436 -0.1130123 0.9916583 0.06176972 -0.1280562 0.9898415 0.06178086 -0.1284971 0.9897837 0.06164842 -0.1408148 0.9881148 0.06158757 -0.1535112 0.9862259 0.06155669 -0.1639783 0.9845414 0.06155717 -0.1794834 0.9818332 0.06158792 -0.1946521 0.978937 0.06103897 -0.201276 0.9776309 0.06067281 -0.2364044 0.9697587 0.06082493 -0.2100643 0.9757937 0.06058049 -0.2219962 0.9731638 0.06059104 -0.2223159 0.9730902 0.06024467 -0.2724441 0.9602838 0.06036669 -0.2356682 0.9699569 0.06027501 -0.3218536 0.9448689 0.06152713 -0.2774519 0.9587674 0.06085562 -0.2817855 0.9575456 0.06045848 -0.2877349 0.9557999 0.0602138 -0.2960947 0.9532588 0.06020796 -0.2963372 0.9531838 0.06009179 -0.3254542 0.9436464 0.06024485 -0.3440123 0.9370306 0.05838245 -0.3460221 0.9364082 0.0604276 -0.3572553 0.9320501 0.06048911 -0.3689472 0.92748 0.05716288 -0.4338641 0.8991632 0.06021475 -0.3724893 0.9260809 0.05987864 -0.3770038 0.9242742 0.05960458 -0.3811885 0.9225739 0.05923736 -0.3880795 0.9197203 0.05899351 -0.3928428 0.9177115 0.05878049 -0.3981572 0.915432 0.05859714 -0.403344 0.9131703 0.05841457 -0.4089024 0.9107066 0.05822986 -0.4144455 0.9082095 0.05807787 -0.4206758 0.9053502 0.0579555 -0.4259836 0.9028728 0.05796587 -0.4260848 0.9028243 0.05340898 -0.5021667 0.86312 0.05526912 -0.4514307 0.8905929 0.05353093 -0.5560933 0.8293942 0.05777245 -0.4343771 0.8988764 0.05786472 -0.429957 0.9009932 0.05716317 -0.4666444 0.8825958 0.05636972 -0.5224652 0.8507953 0.05923712 -0.4912626 0.8689949 0.05887198 -0.487426 0.8711774 0.05865824 -0.4855942 0.8722141 0.0584141 -0.4839765 0.8731293 0.05823099 -0.483061 0.8736482 0.05322444 -0.6196808 0.7830471 0.0579257 -0.4826027 0.8739219 0.05780386 -0.4826657 0.8738951 0.057621 -0.4839496 0.8731968 0.05752772 -0.4846676 0.8728046 0.05743747 -0.4859603 0.8720915 0.05746805 -0.4856253 0.8722761 0.0573765 -0.4878227 0.8710551 0.05734598 -0.4883717 0.8707495 0.05734544 -0.488276 0.8708031 0.05148577 -0.6131602 0.7882791 0.05735766 -0.4882925 0.8707931 0.05722016 -0.4933629 0.8679395 0.05720746 -0.4937818 0.867702 0.05711066 -0.4983854 0.8650726 0.05697953 -0.5535596 0.8308582 0.05676507 -0.555108 0.8298391 0.05655151 -0.5563595 0.8290153 0.05661284 -0.5561185 0.8291726 0.05636858 -0.557735 0.8281029 0.05130261 -0.7136283 0.6986435 0.05139422 -0.7035887 0.7087465 0.04983687 -0.7459668 0.6641159 0.05627804 -0.5583555 0.8276907 0.05618554 -0.5591089 0.8271883 0.05609393 -0.559841 0.8266993 0.05703932 -0.5519294 0.8319379 0.05560624 -0.5572531 0.8284788 0.05328619 -0.659699 0.7496385 0.05694878 -0.5217254 0.8512105 0.05691891 -0.5181607 0.8533872 0.05691832 -0.5181248 0.8534091 0.0569185 -0.5176685 0.853686 0.0569182 -0.5175744 0.853743 0.05688863 -0.5166979 0.8542758 0.0569179 -0.5184872 0.853189 0.0568875 -0.5163215 0.8545033 0.05688846 -0.5159945 0.8547009 0.0568878 -0.5164156 0.8544465 0.05685669 -0.51522 0.85517 0.05685752 -0.51535 0.8550916 0.0567646 -0.5138726 0.8559864 0.05679684 -0.5139794 0.8559203 0.05679649 -0.5141903 0.8557936 0.05670434 -0.5131473 0.8564255 0.05667394 -0.5128428 0.8566098 0.05658197 -0.5120459 0.8570924 0.05661273 -0.5122921 0.8569434 0.05643069 -0.5114166 0.8574781 0.05627763 -0.510985 0.8577455 0.05612516 -0.510742 0.8579002 0.05581909 -0.510643 0.857979 0.05432432 -0.6078528 0.7921894 0.05545353 -0.5110762 0.8577448 0.05496543 -0.5119935 0.8572289 0.05453753 -0.5131779 0.8565478 0.05484318 -0.5122665 0.8570737 0.05771237 -0.5024732 0.8626645 0.05823093 -0.4681367 0.8817353 0.05823075 -0.4682573 0.8816714 0.0582605 -0.4655653 0.8830939 0.05826056 -0.4631242 0.8843765 0.05826061 -0.4566546 0.8877344 0.05826073 -0.4574798 0.8873094 0.05826061 -0.4526568 0.8897795 0.05826139 -0.4555013 0.8883267 0.05822992 -0.4481386 0.8920657 0.05823123 -0.4495528 0.8913537 0.05817043 -0.4434506 0.8944091 0.05813878 -0.4418244 0.8952156 0.05820029 -0.4450022 0.8936363 0.05810928 -0.4385665 0.8968182 0.05804795 -0.4355124 0.8983092 0.05798643 -0.4337692 0.8991562 0.05795556 -0.4316912 0.9001577 0.05786418 -0.4282439 0.9018087 0.0578339 -0.4260483 0.90285 0.05902361 -0.413654 0.9085189 0.05893158 -0.3795001 0.923313 0.0594213 -0.4034972 0.9130495 0.0591762 -0.4096557 0.9103189 0.05966573 -0.3954117 0.9165641 0.0595436 -0.3994399 0.9148237 0.05996972 -0.3841117 0.921337 0.05981725 -0.3895754 0.9190501 0.06015378 -0.3748399 0.925136 0.06006115 -0.3800517 0.9230133 0.06027555 -0.3658958 0.9287019 0.06024491 -0.3698319 0.9271435 0.0603367 -0.3558861 0.9325795 0.06030589 -0.3609809 0.9306213 0.06030529 -0.3459317 0.9363197 0.06024539 -0.3401395 0.9384433 0.06033688 -0.3508817 0.9344739 0.06018465 -0.3354715 0.9401259 0.06006246 -0.3304962 0.9418944 0.05990833 -0.3252387 0.9437324 0.05972617 -0.3195061 0.9457002 0.05978757 -0.2550204 0.9650855 0.05954235 -0.3140091 0.9475511 0.0605809 -0.2950916 0.9535466 0.06009232 -0.3041241 0.9507352 0.06143468 -0.2751896 0.9594252 0.06100702 -0.2859306 0.9563064 0.06192255 -0.2566629 0.9645154 0.06170946 -0.2664616 0.9618681 0.06210637 -0.2378355 0.9693179 0.06207597 -0.2463812 0.9671829 0.06180101 -0.2177532 0.9740453 0.06146603 -0.2082949 0.9761328 0.06201523 -0.2275215 0.9717963 0.06091523 -0.1981576 0.9782755 0.06027555 -0.187724 0.9803707 0.06033682 -0.1734113 0.9829996 0.05963337 -0.1262251 0.9902077 0.06247252 -0.1354131 0.9888178 0.06161868 -0.1546114 0.986052 0.06231981 -0.09250313 0.9937603 0.06073319 -0.06790518 0.9958415 0.06280738 -0.1150858 0.991368 0.05932807 -0.003540098 0.9982323 0.0601536 -0.03885108 0.9974328 0.06259489 -4.27269e-4 0.998039 0.06060999 0.06872797 0.9957926 0.06180089 0.09088546 0.9939419 0.0599386 0.1057165 0.9925882 0.06189239 0.03720253 0.9973892 0.06216651 0.186408 0.9805037 0.0625329 0.1938245 0.9790412 0.06112885 0.1977913 0.9783363 0.06146442 0.159246 0.9853237 0.06241077 0.1431022 0.9877382 0.06128251 0.2456184 0.9674276 0.06189203 0.2732955 0.959937 0.06283819 0.2207425 0.9733058 0.06290072 0.2143385 0.9747321 0.06256365 0.2757989 0.9591772 0.06259465 0.27809 0.9585134 0.06229019 0.2650614 0.9622174 0.0621671 0.261578 0.9631783 0.06161832 0.3149584 0.9471033 0.06171065 0.3170987 0.9463827 0.06213736 0.3352243 0.9400871 0.06259876 0.2915899 0.9544929 0.06210678 0.3377878 0.9391711 0.06210678 0.3348885 0.9402087 0.06201559 0.3277794 0.9427167 0.06201434 0.3278338 0.9426978 0.06103885 0.3526217 0.9337732 0.06210559 0.3369879 0.9394584 0.06106942 0.3541477 0.9331934 0.06201392 0.3839553 0.9212669 0.06100809 0.3534443 0.9334641 0.06109952 0.355122 0.932821 0.0612511 0.3585648 0.9314933 0.06115996 0.3560954 0.9324461 0.06125134 0.3588715 0.9313751 0.06128293 0.359061 0.9313 0.06134438 0.3607723 0.9306344 0.06140404 0.3627783 0.9298502 0.06128269 0.3591509 0.9312654 0.06155616 0.3708022 0.9266697 0.06143468 0.3639389 0.9293946 0.06137335 0.3623197 0.9300311 0.06085556 0.3735263 0.9256213 0.06158798 0.3964766 0.9159767 0.05295103 0.6242429 0.7794338 0.05313366 0.6243894 0.7793041 0.0611608 0.372794 0.9258964 0.05343896 0.624818 0.7789396 0.05371457 0.6255001 0.778373 0.05395787 0.6262532 0.7777503 0.06112998 0.372884 0.9258621 0.06137394 0.3728522 0.9258588 0.0613743 0.3727629 0.9258948 0.05417162 0.6272923 0.7768976 0.05438488 0.6286006 0.7758244 0.06146508 0.3731549 0.9257308 0.05478107 0.632287 0.7727952 0.05484199 0.6334756 0.7718167 0.05487316 0.6340935 0.771307 0.05490374 0.6349794 0.7705756 0.05649083 0.623597 0.7797023 0.0554232 0.5973869 0.8000358 0.06158691 0.3738249 0.9254524 0.05664372 0.6241497 0.7792487 0.05667495 0.6244016 0.7790448 0.05664294 0.6238968 0.7794514 0.05661278 0.6231683 0.7800362 0.05740672 0.6168863 0.784956 0.06152653 0.3734322 0.925615 0.05716317 0.6109106 0.7896332 0.05716204 0.5795861 0.8129037 0.05752819 0.6161472 0.7855274 0.0574482 0.6117198 0.7889858 0.0577417 0.607631 0.7921178 0.06158691 0.3739773 0.9253908 0.06167876 0.3752306 0.9248771 0.05874842 0.6001496 0.7977275 0.05783426 0.5792891 0.8130679 0.05862742 0.5974141 0.7997871 0.06161868 0.3740764 0.9253486 0.05829221 0.5516705 0.8320227 0.06170934 0.375902 0.9246024 0.05993956 0.578185 0.8137011 0.05838257 0.5889834 0.8060335 0.05874949 0.5485831 0.8340294 0.05972605 0.5733641 0.8171209 0.0616483 0.3744067 0.925213 0.06174057 0.3772188 0.924064 0.06161814 0.3731883 0.9257072 0.06173962 0.3783727 0.9235921 0.05939102 0.5671144 0.8214949 0.06070226 0.5450695 0.8361904 0.06036734 0.534456 0.8430377 0.05972546 0.5050877 0.8609991 0.05954247 0.5136951 0.8559042 0.06167858 0.3747107 0.925088 0.0617401 0.3774601 0.9239654 0.06088697 0.4738807 0.8784816 0.06167948 0.3752044 0.9248877 0.0617398 0.3780686 0.9237166 0.06146496 0.4234187 0.9038466 0.06103938 0.4505012 0.8906868 0.06134372 0.5010043 0.8632681 0.06097775 0.4815046 0.8743198 0.0616793 0.37325 0.9256782 0.06174027 0.3819782 0.9221068 0.06168007 0.3745058 0.9251708 0.06173956 0.4325127 0.8995116 0.06106907 0.413872 0.9082844 0.06122124 0.415334 0.9076067 0.06128239 0.4158537 0.9073644 0.06122213 0.4153707 0.9075896 0.06140452 0.4168308 0.9069077 0.06137448 0.4166205 0.9070064 0.06152635 0.4180804 0.906324 0.06116056 0.4139938 0.9082227 0.06152617 0.4119449 0.9091292 0.06167906 0.4113059 0.9094082 0.06161737 0.4116067 0.9092763 0.0617392 0.4110559 0.9095172 0.06186175 0.4107535 0.9096454 0.06189274 0.4106652 0.9096832 0.06198436 0.4105132 0.9097456 0.06204581 0.4104241 0.9097815 0.06213682 0.4103596 0.9098044 0.06460827 0.2964595 0.9528576 0.06152725 0.3571084 0.9320343 0.06198406 0.3464517 0.9360178 0.06244295 0.3370273 0.939422 0.06113046 0.3694381 0.9272425 0.05939084 0.4388393 0.8966008 0.06119048 0.4239082 0.9036357 0.05994027 0.4479348 0.8920547 0.05340838 0.6039426 0.7952364 0.05014312 0.5565494 0.8293001 0.04815924 0.5563645 0.8295416 0.06207662 0.3322964 0.9411301 0.06207525 0.333479 0.9407117 0.06204545 0.3308584 0.9416387 0.06198412 0.3260654 0.943313 0.06189286 0.3221603 0.9446597 0.06192404 0.3240866 0.9439986 0.06186276 0.3214301 0.9449105 0.06174027 0.3181321 0.946034 0.06152683 0.3127614 0.9478369 0.06128209 0.3083637 0.9492926 0.06146574 0.311571 0.9482329 0.06128197 0.3070508 0.9497181 0.06261509 0.2897102 0.9550641 0.06253308 0.294934 0.9534693 0.06262493 0.2847421 0.9565564 0.06262516 0.281325 0.957567 0.0625953 0.2894768 0.9551362 0.06250214 0.2715549 0.9603914 0.06241184 0.2689051 0.9611425 0.06195396 0.257521 0.9642845 0.06146609 0.2498319 0.9663364 0.0617398 0.2539176 0.9652534 0.06247276 0.2347231 0.9700527 0.0626561 0.2286505 0.9714902 0.06286942 0.2067671 0.9763682 0.06277674 0.2011785 0.9775409 0.0616486 0.1792998 0.9818611 0.06100708 0.1708443 0.9834076 0.06289929 0.1276908 0.9898176 0.06277817 0.1103577 0.9919073 0.05856573 0.4865626 0.8716804 0.05795651 0.4847411 0.8727355 0.05993932 0.4438685 0.8940851 0.05832248 0.5232547 0.8501783 0.05545401 0.5123929 0.8569588 0.05749845 0.4638334 0.8840547 0.05148619 0.5471212 0.8354685 0.05548304 0.5794592 0.8131105 0.05353099 0.5331125 0.8443492 0.05655145 0.5611505 0.8257797 0.05450785 0.4837648 0.873499 0.05420136 0.5970701 0.8003559 0.05160838 0.5036625 0.8623577 0.04666441 0.5330243 0.8448122 0.04855626 0.523956 0.8503602 0.0574066 0.6144736 0.7868461 0.05741333 0.6143532 0.7869396 0.05777221 0.5421985 0.8382621 0.05844485 0.5937268 0.8025414 0.05920761 0.5590543 0.8270145 0.06003212 0.5209095 0.8514984 0.06079494 0.4559317 0.887936 0.06482201 0.2855954 0.9561555 0.06006085 -0.3090021 0.9491631 0.05139458 -0.6754547 0.7356083 0.9947555 0.003080427 -0.1022358 0.9947676 3.77444e-4 -0.1021636 0.06702423 0 -0.9977514 0.06702816 0 -0.9977512 0.06636184 0 -0.9977957 0.06638687 0 -0.997794 0.06707626 0 -0.9977479 0.06708979 0 -0.997747 0.06703531 0 -0.9977506 0.06712043 0 -0.997745 0.0670762 0 -0.9977479 0.06709402 0 -0.9977468 0.06714671 0 -0.9977431 0.06712478 0 -0.9977446 0.06706637 0 -0.9977486 0.06709551 0 -0.9977467 0.06641995 0 -0.9977918 0.0664075 0 -0.9977927 0.06712543 0 -0.9977446 0.06715053 0 -0.997743 0.06714266 0 -0.9977434 0.0670979 0 -0.9977464 0.06708151 0 -0.9977476 0.0671575 0 -0.9977425 0.06642377 0 -0.9977915 0.06646287 0 -0.9977889 0.06701844 0 -0.9977518 0.0670821 0 -0.9977476 0.06699538 0 -0.9977533 0.06709408 0 -0.9977467 0.06704723 0 -0.9977498 0.06706088 0 -0.9977489 0.06705051 0 -0.9977496 0.06702673 0 -0.9977512 0.06705427 0 -0.9977494 0.06702476 0 -0.9977514 0.06699192 1.63796e-5 -0.9977536 0.06696981 0 -0.997755 0.06698668 0 -0.9977539 0.0670728 1.57619e-5 -0.9977481 0.06700813 0 -0.9977524 0.06696134 0 -0.9977556 0.06632161 0 -0.9977983 0.0663349 0 -0.9977974 0.06699001 0 -0.9977537 0.06698918 0 -0.9977537 0.06696295 0 -0.9977555 0.06699317 0 -0.9977535 0.06694453 0 -0.9977567 0.06694918 0 -0.9977565 0 0 1 1.57426e-4 0 1 -2.66862e-4 0 1 -7.32122e-4 0 0.9999998 -2.35801e-4 0 1 1.93146e-4 0 1 1.93167e-4 0 1 -8.95832e-5 0 1 -1.40367e-4 0 1 2.99151e-4 0 1 2.83911e-4 0 1 -2.83911e-4 0 1 1.97937e-4 0 1 -4.58124e-4 0 1 2.52633e-4 0 1 -2.50762e-4 0 1 -2.89292e-4 0 1 1.2182e-4 0 1 -2.37597e-4 0 1 2.37572e-4 0 1 3.99521e-5 0 1 -2.28036e-4 0 1 1.27769e-4 0 1 -4.02979e-5 0 1 2.18244e-4 0 1 -2.21028e-4 0 1 1.42812e-4 0 1 -1.46324e-4 0 1 1.07738e-4 0 1 -2.12816e-4 0 1 -3.30215e-5 0 1 -5.1504e-5 0 1 -2.0724e-4 0 1 2.06578e-4 0 1 1.37262e-4 0 1 -1.36998e-4 0 1 0.7232776 0.008911609 0.6904999 0.7506194 0.01532059 0.6605573 0.7233296 0.00766021 0.6904607 0.7580969 0.01446604 0.6519816 0.6915085 0.00262463 0.7223637 0.6915062 0.003692805 0.7223612 0.6600967 0.004760921 0.7511656 0.6551262 0.004822015 0.7555041 0.6305618 0.009705126 0.7760784 0.622288 0.006866812 0.7827584 0.5915223 0.002197325 0.8062856 0.6037943 0.007629811 0.7971037 0.5726549 -7.6297e-4 0.8197962 0.5603558 -0.001922667 0.8282498 0.5354903 -0.00476098 0.844528 0.5447678 -0.008331716 0.8385456 0.5064666 -0.01025444 0.8621987 0.475765 -0.008118093 0.879535 0.4632236 -0.009338915 0.8861923 0.5173653 -0.01022398 0.8557037 0.43694 -0.003082394 0.8994855 0.4273632 -0.00262463 0.9040763 0.4025759 -7.01937e-4 0.9153864 0.4032508 -9.15577e-4 0.9150891 0.3799351 -0.002319455 0.9250103 0.4189033 -4.88303e-4 0.9080308 0.3067168 -0.002014219 0.9517987 0.3480727 -0.003418147 0.9374614 0.3236525 0 0.9461761 0.271745 1.52597e-4 0.9623693 0.2910583 7.9349e-4 0.9567051 0.2674375 0.001068115 0.9635747 0.2442441 0.00125128 0.969713 0.2452203 0.001037597 0.9694669 0.1947131 7.01944e-4 0.98086 0.1712741 5.18828e-4 0.9852233 0.1700234 3.66232e-4 0.98544 0.1941025 8.85059e-4 0.9809809 0.220745 0.001037597 0.9753311 0.01934921 0 0.9998129 0.02945107 0 0.9995663 0.02932906 0 0.9995699 0.09799575 0 0.9951869 0.07507669 0 0.9971778 0.09802603 0 0.995184 0.1239972 0 0.9922826 0.1238469 0 0.9923014 0.07471024 0 0.9972053 0.147742 0 0.989026 0.1488434 1.83117e-4 0.9888609 0.0518828 -3.05193e-5 0.9986532 0.05209589 0 0.9986422 0.2203188 0.001129209 0.9754273 0.01956278 0 0.9998087 0.3666237 -5.18822e-4 0.9303691 0.7907586 0.008636951 0.6120673 0.7828526 0.01663303 0.6219849 0.8166666 -0.007629811 0.5770594 0.8050315 0.001831114 0.5932294 0.8235448 -0.006897449 0.5672094 0.8358515 -0.01214647 0.5488213 0.8486527 -0.007233083 0.5289011 0.967719 -0.001983702 0.2520238 0.9795606 -0.003540158 0.2011186 0.9781956 -0.005188226 0.2076209 0.9987292 -0.005096614 0.05014246 0.9988402 -0.005829155 0.04779344 0.9997892 -0.002410948 0.02038639 0.9841784 0.01297056 0.1767053 0.9873555 0.001342833 0.1585164 0.859386 -0.008606314 0.5112552 0.9659552 -5.49341e-4 0.2587091 0.9532726 -5.79868e-4 0.3021112 0.9964073 -3.05188e-4 0.08468955 0.9962072 -8.24018e-4 0.08701014 0.9527572 0.00137335 0.3037298 0.9408623 -5.79856e-4 0.3387886 0.9914372 0.002563536 0.1305599 0.9934945 -0.006683707 0.1136844 0.8735752 -0.001739561 0.4866861 0.8845027 -0.004455745 0.4665139 0.8933504 1.52595e-4 0.4493609 0.908262 -0.002777278 0.4183926 0.9059269 -0.003326535 0.423421 0.9246399 -0.004303157 0.3808184 0.9212284 -0.004120111 0.3890004 0.9367282 -0.00100708 0.3500561 0.9998244 1.83112e-4 0.0187385 0.9998345 3.66229e-4 -0.01818931 0.9998709 0.01599204 0.001617491 0.9989795 0.01837241 -0.04126173 0.9979364 -0.003418087 -0.06412011 0.9959017 0.003692805 -0.09036725 0.9966105 0.006531119 -0.08200556 0.995769 0 -0.09189224 0.9947482 0 -0.1023533 0.9947447 -0.006534397 -0.1021787 0.9947499 0 -0.1023368 0.9947293 0.006504356 -0.1023297 0.9947285 0.006605982 -0.1023313 0.9947401 -0.007285237 -0.1021731 0.9947435 -0.006681084 -0.1021794 0.9947159 0.008193492 -0.1023393 0.9947195 0.007755517 -0.1023388 0.9947662 0 -0.1021773 0.9947136 -0.01043564 -0.1021574 0.9947662 0 -0.102177 -0.9844872 0 -0.1754567 -0.9844858 0 -0.1754643 -0.9844828 0 -0.1754812 -0.9844873 0 -0.1754559 -0.9844861 0 -0.1754633 -0.984489 0 -0.1754462 -0.9844888 0 -0.1754476 0.1754363 0 -0.9844908 0.1754691 0 -0.984485 0.1754376 0 -0.9844906 0.1754583 0 -0.9844869 -0.9844871 0 -0.1754572 -0.9844872 0 -0.1754566 -0.1754782 0 0.9844834 -0.1754811 0 0.9844828 -0.1754729 0 0.9844843 -0.1754766 0 0.9844836 -0.9844846 0 -0.1754712 -0.9844888 0 -0.1754479 -0.9844881 0 -0.1754516 -0.984488 0 -0.1754522 -0.9844847 0 -0.1754708 -0.984489 0 -0.1754469 -0.9844851 0 -0.1754688 -0.984485 0 -0.1754689 -0.17547 -3.10446e-6 0.9844848 -0.1754745 0 0.9844841 -0.1754629 0 0.9844861 -0.1754701 -3.96889e-6 0.9844848 -0.1754967 3.40631e-5 0.9844801 -0.1754297 -1.72105e-5 0.984492 -0.1754688 5.00455e-6 0.984485 -0.175463 -8.59691e-6 0.9844861 -0.1754608 -5.35619e-6 0.9844864 -0.1754295 -8.26785e-5 0.984492 -0.1754845 0 0.9844822 -0.1754815 -3.04047e-6 0.9844828 -0.1754584 -5.51597e-6 0.9844869 -0.1754429 -3.74883e-6 0.9844896 -0.1754713 1.84385e-6 0.9844846 -0.1754938 -2.14316e-6 0.9844806 -0.1754531 3.00714e-5 0.9844878 -0.1754606 1.54909e-6 0.9844865 -0.1754505 1.37358e-5 0.9844883 -0.175472 -1.71372e-5 0.9844845 -0.1754591 2.74786e-6 0.9844867 -0.1754749 -9.27804e-6 0.9844839 -0.1754761 -2.74335e-6 0.9844837 0.9844861 -8.32808e-7 0.1754631 0.9844881 0 0.1754515 0.9844849 0 0.1754701 0.9844855 -8.14847e-6 0.175466 0.9844837 1.70736e-5 0.1754761 0.9844869 0 0.1754586 0.9844822 0 0.1754847 0.9844906 -3.00563e-5 0.1754374 0.9844844 -1.04921e-5 0.1754726 0.9844861 3.32965e-6 0.175463 0.9844836 -1.415e-5 0.1754767 0.9844884 -1.07196e-5 0.1754502 -0.1754655 0 0.9844856 -0.1754502 0 0.9844884 -0.1754462 3.02728e-6 0.9844891 0.9844813 0 0.1754896 0.9844859 1.41947e-5 0.1754642 0.9844847 1.71463e-5 0.1754701 0.9844785 0 0.1755056 0.9844781 0 0.1755074 0.1754635 0 -0.984486 0.1754872 -1.9004e-6 -0.9844818 0.1754479 -1.92128e-6 -0.9844888 0.1755011 0 -0.9844793 0.9844886 0 0.1754493 0.9844894 0 0.1754447 0.9844836 0 0.1754767 0.9844884 0 0.1754499 0.9844837 0 0.1754767 0.9844892 0 0.1754454 0.9844837 0 0.1754765 0.9844838 0 0.1754753 0.1755147 7.39252e-6 -0.9844768 0.175421 -3.46902e-6 -0.9844936 0.1754325 -3.9341e-6 -0.9844915 0.1754733 7.23804e-6 -0.9844843 0.1754687 -1.67371e-6 -0.9844851 0.1754555 -3.9623e-6 -0.9844875 0.1754916 -1.69433e-6 -0.9844809 0.1755077 -2.10712e-6 -0.9844781 0.1754723 -1.7187e-6 -0.9844844 0.1754767 -1.9199e-6 -0.9844836 0.1754634 0 -0.984486 0.1754513 -1.94762e-6 -0.9844882 0.175441 -3.49337e-6 -0.9844899 0.1754757 5.52368e-6 -0.9844838 0.1754395 -3.67367e-6 -0.9844903 0.1754809 5.282e-6 -0.9844828 0.1754648 -2.04014e-6 -0.9844858 0.1754517 -3.44554e-6 -0.9844881 0.1754291 -2.04345e-6 -0.9844921 0.1754323 -1.8235e-6 -0.9844915 0.1754368 -2.05106e-6 -0.9844907 0.1754459 -2.02948e-6 -0.9844891 0.1754672 0 -0.9844854 0.1754676 -2.24085e-6 -0.9844853 0.9854701 -8.80804e-6 -0.1698491 0.9854711 -2.04443e-5 -0.1698436 0.9854722 -2.49672e-6 -0.1698373 0.9854715 6.40806e-6 -0.1698414 0.9854707 0 -0.1698461 0.9854708 5.75615e-6 -0.1698447 0.9854708 3.44724e-6 -0.1698447 0.985471 0 -0.1698441 0.985471 0 -0.169844 0.985471 0 -0.1698437 0.9854707 -3.78829e-6 -0.1698458 0.9854698 6.65218e-6 -0.1698508 0.08811581 0.9960974 -0.005061924 0.09086596 0.9958289 -0.008252918 0.08769959 0.9961267 -0.006351172 0.08801853 0.9960981 -0.006432831 0.09098786 0.9958176 -0.008293211 0.08581066 0.9962903 -0.006497383 0.08894032 0.9960148 -0.006664216 0.08794128 0.9961051 -0.006392836 0.08855819 0.9960493 -0.00657767 0.09081953 0.9958444 -0.006754696 0.09077644 0.9958373 -0.008240878 0.08784395 0.996113 -0.006520152 0.08795607 0.9961038 -0.00640136 0.08642375 0.9962379 -0.006407201 0.0946604 0.9954859 -0.006872236 0.08646339 0.9962344 -0.006424248 0.08773785 0.9961233 -0.006361246 0.09205031 0.9957225 -0.007977485 0.08821648 0.9960805 -0.006451368 0.08862626 0.9960434 -0.006558001 0.09135657 0.9957811 -0.008611619 0.08867728 0.9960422 -0.006039023 0.09121948 0.9957931 -0.008671879 0.09139949 0.9957751 -0.008844316 0.08838057 0.9960696 -0.005873918 0.09081548 0.9958339 -0.008213818 0.09125733 0.9957859 -0.0090878 0.08316785 0.9965298 -0.003399431 0.08903241 0.9960002 -0.007549703 0.08833646 0.9960625 -0.007503986 0.08459782 0.9964051 -0.004486203 0.07843267 0.9969195 -9.15557e-5 0.08258527 0.9965782 -0.003387629 0.08579623 0.9962914 -0.006512224 0.08227986 0.9966056 -0.002716183 0.08099603 0.9966782 -0.008499443 0.07952314 0.9967939 -0.008841156 0.08350354 0.9964931 -0.005378305 0.07733321 0.9969619 -0.009303212 0.07263624 0.9973449 0.005218803 0.08060032 0.996746 -9.76604e-4 0.07956206 0.99683 -6.10373e-5 0.07552796 0.9971054 -0.008734345 0.07812929 0.9969424 0.001403868 0.07690858 0.9970344 0.002777218 0.0699802 0.9975157 0.008087515 0.07559651 0.9971293 0.004303216 0.06805688 0.9976291 0.01022374 0.07411742 0.9972093 -0.008958935 0.07434481 0.9972158 0.005798637 0.06640869 0.9977174 0.01223796 0.07274693 0.9973065 -0.009369194 0.06479227 0.9977957 0.01434403 0.07303208 0.9973016 0.007477164 0.06958371 0.9975504 -0.007171988 0.07059133 0.9974654 -0.008942127 0.07223957 0.9973457 -0.009125292 0.07177978 0.9973794 0.009064018 0.06326657 0.9978606 0.01648044 0.06723237 0.9977124 -0.007049739 0.06958252 0.9975332 -0.009277641 0.07413113 0.9972458 -0.002349972 0.07153761 0.9974376 -9.15584e-4 0.06793618 0.9976488 -0.009033739 0.06494349 0.997866 -0.006775081 0.06668424 0.9977307 -0.009308278 0.06591665 0.9977802 -0.009485304 0.06888061 0.9976248 5.79855e-4 0.0687592 0.9976034 -0.007721245 0.06366193 0.9979305 -0.009064018 0.06515896 0.9978329 -0.009155809 0.06500613 0.9978602 -0.0070194 0.06665259 0.9977747 0.001831114 0.06164747 0.998079 -0.006164729 0.06338763 0.9979662 -0.006744623 0.05880922 0.9982309 -0.008758783 0.06425917 0.9978749 -0.01080328 0.05702555 0.9983672 -0.003330647 0.05645608 0.9984002 -0.003146171 0.05991554 0.9981959 -0.003893256 0.06360387 0.9979647 -0.004577219 0.06178742 0.9980793 -0.004487216 0.0579515 0.9983151 -0.002931654 -0.2777978 -0.9597107 0.04223567 0.0337007 0.9994251 0.003721117 0.05792766 0.9983132 -0.00390172 0.06318068 0.9979782 -0.006911993 0.09152686 0.9957593 -0.009300351 0.09018743 0.9958859 -0.008820295 0.08113551 0.9966734 -0.007702469 0.07871657 0.9968684 -0.007556378 0.07824707 0.9969078 -0.007233798 0.07727044 0.9969822 -0.007475614 0.07589685 0.9970902 -0.007124722 0.07444798 0.9972001 -0.007027924 0.07533729 0.9971356 -0.006686687 0.07303929 0.9973065 -0.006723821 0.07162564 0.9974098 -0.00659579 0.0723983 0.9973567 -0.006178736 0.07018268 0.9975143 -0.006308436 0.06876331 0.9976139 -0.006190061 0.06979382 0.9975439 -0.005922019 0.06734061 0.997711 -0.006161272 0.06789219 0.9976769 -0.005603611 0.06592845 0.9978065 -0.005985677 0.06449615 0.997903 -0.005464613 0.06483519 0.997886 -0.004462718 0.01257801 0.9998814 0.008894562 0.01886069 0.9959243 0.08819967 0.01754844 0.9937913 0.1098685 0.02322524 0.9964287 0.08118164 0.01165837 0.9984404 0.0545991 0.01229918 0.9950171 0.09894317 0.01855564 0.998711 0.04724371 0.02682662 0.996766 0.07574933 0.03531521 0.9993761 6.82943e-4 0.02203476 0.9948613 0.0988208 0.03247261 0.9974352 0.06378555 0.025209 0.9954525 0.09186351 0.05969876 0.9982083 -0.004037499 0.05987852 0.9981896 -0.005676507 0.05533117 0.9984338 -0.00827068 0.0580163 0.9983024 -0.005157649 0.03787761 0.999281 0.00165683 0.03763312 0.9992902 0.001755535 0.05987083 0.9981986 -0.00389719 0.04877269 0.9988092 -0.001216292 0.03627473 0.9993389 -0.002428174 0.04156452 0.9991357 5.56351e-4 0.04252737 0.9990952 4.04402e-4 0.0604586 0.9981318 -0.008820056 0.05713224 0.99835 -0.00576812 0.05707025 0.9983334 -0.008575797 0.05469006 0.9984908 -0.005035579 0.05844473 0.9982606 0.007751882 0.05401933 0.9985339 -0.003479182 0.05548417 0.99841 0.009949266 0.0560019 0.9984216 -0.00427258 0.05331653 0.9985481 -0.007690727 0.04965442 0.9987654 -0.001464903 0.04513698 0.9989656 -0.00552386 0.04745638 0.9988733 -4.2726e-4 0.0513944 0.9986516 -0.007324576 0.04696917 0.9978898 0.04483282 0.04458886 0.9978322 0.04840373 0.03680551 0.997168 0.06558465 0.03250235 0.9966481 0.07507592 0.04208534 0.9977502 0.05218708 0.0393691 0.9976267 0.05649012 0.04232925 0.9988727 0.02148503 0.04724359 0.9987388 0.01699912 0.02880984 0.9960759 0.08368283 0.03653073 0.9975003 0.0604878 0.01266527 0.9925037 0.1215566 0.0302751 0.9970653 0.07031643 0.03338772 0.9972983 0.0654326 0.007019281 0.9907563 0.1354721 0.003479123 0.9935355 0.1134684 -6.40904e-4 0.9879083 0.1550378 0.03324544 0.9994427 0.003009438 0.02669334 0.9996315 0.004963159 0.02395373 0.9996965 0.005768477 0.03528761 0.9993743 0.002405881 0.01720273 0.9998155 0.008557021 0.03493219 0.9993871 0.002278447 0.04289013 0.9990799 -1.85464e-5 0.03796517 0.9992781 0.001401603 0.03795701 0.9992749 0.003026962 -0.02414071 0.9994744 0.02163809 -0.02896225 0.999305 0.02346885 -0.03006142 0.9992609 0.02395755 0.02766871 0.9996068 0.004564702 0.03252214 0.999466 0.003191232 0.02656352 0.9996342 0.005110919 0.01008009 0.9998986 0.01007103 0.03511375 0.999381 0.002192437 -0.3236759 -0.9434089 0.07220453 0.03537666 0.9993712 0.002392411 0.03580373 0.9993563 0.002276957 0.04872983 0.9988113 -0.001213788 0.03098344 0.9995184 0.001769483 0.03993928 0.9992018 8.3615e-4 0.03325164 0.9994438 0.00255537 0.0346542 0.9993984 0.001459658 0.04029905 0.9991875 6.95562e-4 0.002319395 0.9999156 0.01278734 -0.004608392 0.9998772 0.01498502 0.001678526 0.9999166 0.01281785 0.03252393 0.9994664 0.003044247 0.02953583 0.9995555 0.004078865 0.03053867 0.999527 0.00365132 -0.08972495 0.9948484 0.0471819 -0.08026462 0.9958311 0.0433368 -0.08536076 0.9953064 0.04559493 -0.02328604 0.9995006 0.02136337 0.004962682 0.9999232 0.01135975 0.03086024 0.9995176 0.003500878 0.02490198 0.9996648 0.007089197 0.02327829 0.9997091 0.006310105 0.02160149 0.999746 0.006443738 0.02438479 0.9996872 0.005554437 0.02539211 0.9996621 0.005585014 0.02194303 0.9997377 0.006561517 0.01964151 0.9997752 0.007989645 0.01703429 0.9998157 0.008851945 0.01254063 0.99987 0.01013278 0.01444888 0.999858 0.008669078 0.01308137 0.9998719 0.009231746 0.01014971 0.9998968 0.01017391 0.005565583 0.9999162 0.01169615 0.01391661 0.9998627 0.009003043 0.01477104 0.9998531 0.008697807 0.01080369 0.9998916 0.01001018 0.002044737 0.9999158 0.01281785 0.006836116 0.9999126 0.01132237 0.00640887 0.9999144 0.01141399 -0.02412378 0.9994677 0.02196413 -0.02946966 0.9992723 0.0242204 -0.03218472 0.9991721 0.02488577 -0.002655148 0.9998928 0.01440495 0.006042659 0.9999163 0.0114445 -0.02588015 0.9994086 0.02264511 -0.01922678 0.9996122 0.02014237 -0.01971524 0.9995897 0.02078342 -0.0255745 0.999422 0.02240061 -0.03259402 0.9991546 0.02505588 -0.06149953 0.9974555 0.03605878 -0.05790406 0.9977278 0.03444355 -0.07167774 0.9966276 0.03994816 -0.01968497 0.9996009 0.02026486 -0.07458949 0.9963679 0.0410791 -0.07983875 0.9958786 0.04303234 -0.08208107 0.9956588 0.0438922 -0.09408974 0.994367 0.04879969 -0.1010785 0.993512 0.05212622 -0.1058999 0.9929267 0.05368238 -0.02688753 0.9993861 0.02246218 -0.03250271 0.9991622 0.02487295 -0.1232351 0.9905194 0.06070196 -0.1295832 0.9895755 0.06283837 -0.1285175 0.9897162 0.06280905 -0.1366023 0.9883832 0.06662261 -0.1457272 0.9868555 0.06985747 -0.04013305 0.9988101 0.02771162 -0.04846447 0.9983444 0.03097695 -0.04861688 0.9983409 0.03085476 -0.1684024 0.9823371 0.08157658 -0.1525635 0.9856052 0.07284837 -0.1581505 0.9845497 0.07516878 -0.2059416 0.9737672 0.09677547 -0.2149798 0.9714683 0.1001652 -0.1879672 0.9782291 0.08795607 -0.04031598 0.9988052 0.02761995 -0.06827205 0.9969183 0.03863763 -0.06821036 0.9969402 0.03817951 -0.0576803 0.9977477 0.03424197 -0.3016778 0.9436703 0.1359305 -0.3377284 0.9279139 0.1578466 -0.3163595 0.9375119 0.1448734 -0.04840272 0.9983607 0.03054928 -0.04004073 0.9988222 0.02740591 -0.04843312 0.9983582 0.03057968 -0.0577414 0.9977484 0.0341199 -0.2030143 -0.9744811 0.09576952 -0.1879677 -0.9782317 0.08792579 -0.2336269 -0.96637 0.1074592 -0.1525969 -0.9855931 0.0729413 -0.1394433 -0.987945 0.06723433 -0.1284241 -0.9897324 0.06274712 -0.06820911 -0.9969215 0.03866708 -0.08029484 -0.9958274 0.04336714 -0.07382476 -0.9964362 0.04080349 -0.07990002 -0.9958816 0.04284936 -0.09412014 -0.9943657 0.04876911 -0.06842464 -0.9969184 0.03836292 -0.557229 0.7933601 0.2451038 -0.5574995 0.7932931 0.2447052 -0.3180437 0.9373759 0.1420377 -0.9164017 -1.83116e-4 0.40026 -0.9160291 -3.0519e-5 0.4011118 -0.02572774 -0.9994146 0.02255374 -0.01922678 -0.999611 0.02020341 -0.02563631 -0.9994204 0.02240127 -0.01324534 -0.9997497 0.01803684 -0.01406913 -0.9997339 0.01828074 -0.01794511 -0.9996464 0.01962363 0.00211519 -0.9999169 0.01272386 -0.007690787 -0.9998401 0.01614463 -0.002471983 -0.9998852 0.01495414 -0.007812917 -0.9998397 0.01611411 0.006601393 -0.9999158 0.01117855 0.01163691 -0.9998711 0.01106387 -0.1881837 -0.9782746 0.08698076 -0.1526263 -0.9856471 0.0721473 -0.1530544 -0.9855605 0.07242232 0.01652342 -0.9998258 0.008679807 0.01899158 -0.9997933 0.007265269 0.05063104 -0.9986132 0.01443547 0.04672527 -0.9987488 0.01782333 0.04938042 -0.9987788 -0.001586973 0.03646981 -0.9993345 -7.62967e-4 0.03933882 -0.999219 -0.003753781 0.03515803 -0.9993801 -0.001861631 0.02013039 -0.9997731 0.00696808 0.02651619 -0.9996358 0.005044043 0.0310443 -0.9995115 0.003632724 -0.05807715 -0.9977195 0.03439462 -0.04876911 -0.9983326 0.03088504 -0.05847477 -0.9973062 0.04428333 0.03276234 -0.9994585 0.003056764 0.04386043 -0.9990377 6.32901e-5 0.03535741 -0.9993718 0.002402305 0.03792273 -0.9992793 0.001677632 0.02455538 -0.999683 0.005574166 0.0379244 -0.9992797 0.001387953 0.0425235 -0.9990954 4.16098e-4 0.04468393 -0.9990013 -1.64155e-4 0.04416847 -0.9990242 -6.02426e-5 0.04874646 -0.9988104 -0.001249969 0.04673856 -0.9989069 -7.44006e-4 0.05240613 -0.9986237 -0.002131879 0.05645328 -0.9984006 -0.00307703 0.06278228 -0.9980161 -0.004734873 0.06389045 -0.9979452 -0.004850804 0.06558805 -0.9978344 -0.004978001 0.06676667 -0.997751 -0.005931437 0.06790924 -0.9976755 -0.005641996 0.06818556 -0.9976583 -0.00534743 0.06873697 -0.9976171 -0.005955457 0.06955164 -0.9975579 -0.006382107 0.0705198 -0.9974904 -0.006334662 0.07081878 -0.9974704 -0.006128489 0.07159137 -0.9974126 -0.006544172 0.07273524 -0.9973304 -0.006458818 0.07513767 -0.99715 -0.006812572 0.07540869 -0.9971306 -0.006657719 0.0760563 -0.9970786 -0.007055759 0.07696604 -0.997007 -0.007309257 0.07801663 -0.9969261 -0.007196128 0.07830059 -0.9969048 -0.007072269 0.07868903 -0.9968726 -0.00728631 0.07943123 -0.996812 -0.007515609 0.08014774 -0.9967544 -0.007558822 0.08083236 -0.9967 -0.007442772 0.08118695 -0.9966723 -0.007287919 0.08183968 -0.9966168 -0.007572412 0.08366942 -0.9964641 -0.007657349 0.08308863 -0.9965117 -0.007801651 0.08375388 -0.9964818 -0.003086984 0.08455592 -0.9963842 -0.008307278 0.08604419 -0.9962563 -0.008362412 0.08678627 -0.9961935 -0.008178472 0.08731031 -0.9961474 -0.00820142 0.08707195 -0.996168 -0.008241772 0.08894187 -0.9959995 -0.008628308 0.08821463 -0.9960649 -0.008548438 0.08946216 -0.995953 -0.008616983 0.0889905 -0.9959946 -0.008687198 0.09052515 -0.9958522 -0.009145557 0.09128463 -0.9957834 -0.009094953 0.09122985 -0.9957882 -0.009109079 0.07389324 -0.9972419 -0.006958484 0.07273769 -0.9973302 -0.006460964 0.06553012 -0.9978388 -0.004851341 0.06404542 -0.997937 -0.004497289 0.0324155 -0.9994691 0.003292977 0.01651042 -0.999831 0.008095741 0.01265597 -0.9998765 0.009325385 -0.1100813 -0.9924101 0.05481171 -0.1102043 -0.992388 0.05496478 -0.1287603 -0.989706 0.0624727 0.002166807 -0.9999163 0.01275682 0.006347894 -0.9999155 0.01135295 4.57779e-4 -0.9999114 0.01330608 0.01503455 -0.99985 0.008607745 0.08866208 -0.9960459 -0.005626976 0.09191548 -0.9957476 -0.006187915 0.09113317 -0.9958205 -0.006036043 0.09086519 -0.9958429 -0.006358683 0.08980572 -0.9959427 -0.005755543 0.09414136 -0.9955383 -0.00640726 0.08756071 -0.9961388 -0.006385862 0.08705747 -0.9961837 -0.006247997 0.09006494 -0.9959157 -0.006344199 0.08913409 -0.9959999 -0.006268262 0.09856665 -0.9951066 -0.006881952 0.08742719 -0.9961512 -0.006268501 0.08890837 -0.9960203 -0.006239354 0.09232473 -0.9957089 -0.006322562 0.09131187 -0.9958038 -0.006086409 0.08894568 -0.9960186 -0.005978345 0.08771091 -0.9961307 -0.005511224 0.08596068 -0.996253 -0.009529232 0.08765566 -0.9961046 -0.009595453 0.09103846 -0.9957994 -0.009777843 0.09028369 -0.9958987 -0.005882501 0.0889253 -0.9960206 -0.005947947 0.08588796 -0.9962942 -0.004633247 0.08562815 -0.996317 -0.004507541 0.08428084 -0.9964355 -0.003643631 0.08383554 -0.9964742 -0.003296017 0.080388 -0.9967628 -0.001312315 0.08661299 -0.9962329 -0.004272639 0.08411097 -0.9964526 -0.002746701 0.08377391 -0.9964672 -0.005920588 0.08734661 -0.9961542 -0.006897389 0.08335477 -0.9964784 -0.009096205 0.07895129 -0.9968779 -0.001066505 0.0807349 -0.9966934 -0.009183704 0.08267658 -0.9965754 -0.001464903 0.07437366 -0.997224 0.003601133 0.08175981 -0.9966518 -8.24007e-4 0.08057004 -0.996749 2.74671e-4 0.08118027 -0.9966865 -0.005066096 0.07162743 -0.9974129 0.006103694 0.07925868 -0.9968527 0.001678526 0.07817232 -0.9968966 -0.009286403 0.07809871 -0.9969415 0.002899289 0.07880079 -0.996882 -0.004089534 0.07544738 -0.9971057 -0.009384572 0.06802666 -0.9976333 0.01001018 0.07672375 -0.9970428 0.00439465 0.06637847 -0.9977225 0.01199388 0.07550489 -0.9971287 0.005798637 0.0711711 -0.9974338 -0.007782399 0.07406926 -0.9972038 -0.00991863 0.07135409 -0.9974009 -0.0100103 0.06476211 -0.9978012 0.01409995 0.0741012 -0.997223 0.007446706 0.07294011 -0.9972962 0.008942008 0.0632041 -0.9978686 0.01623588 0.06164753 -0.9979273 0.01846373 0.07159644 -0.9973762 0.01071196 0.06848376 -0.9976234 -0.007599115 0.06866872 -0.9975888 -0.01007139 0.06009203 -0.9979733 0.02093607 0.07034581 -0.9974458 0.01239061 0.07126224 -0.9974576 -2.44153e-4 0.06839245 -0.9976576 0.001403808 0.06988888 -0.997519 -0.008453786 0.05853593 -0.9980102 0.02343875 0.06882113 -0.9975251 0.01440513 0.06438106 -0.9978654 -0.01095169 0.06543338 -0.9978287 -0.007507741 0.06528091 -0.9978612 0.003387629 0.06302082 -0.9979873 -0.007049739 0.06180149 -0.9980717 0.005798637 0.05029606 -0.9980172 0.03784412 0.06106817 -0.9978138 0.02526956 0.06268668 -0.9977687 0.02298104 0.06442654 -0.9977118 0.02050906 0.05203551 -0.9980444 0.03463947 0.05795586 -0.9982818 0.008636891 0.06021463 -0.9981657 -0.006286978 0.05603229 -0.9983881 -0.009033501 0.05951184 -0.9981814 -0.009613394 0.04483234 -0.9978182 0.04846411 0.05533057 -0.9979037 0.03357064 0.05740642 -0.9978834 0.03054958 0.05655103 -0.9983874 -0.004974484 0.05408012 -0.9984682 0.01168882 0.01090377 -0.9998558 0.01302272 -0.01913529 -0.9996146 0.02011191 -0.01324534 -0.9997486 0.01809787 -0.03671437 -0.9989804 0.02627688 -0.04156726 -0.9987437 0.02798616 -0.03250271 -0.9991622 0.02487295 -0.03943043 -0.9988244 0.02819949 -0.03235024 -0.9991648 0.02496457 -0.04016351 -0.9988088 0.02771162 -0.03459966 -0.9990667 0.02586174 -0.04339843 -0.9986228 0.02948164 -0.04153656 -0.9987101 0.02920687 -0.04843413 -0.9983479 0.03091603 -0.05771195 -0.9977365 0.03451728 -0.06213587 -0.9974091 0.03625607 -0.9162589 -1.22074e-4 0.4005867 -0.8999844 -0.003601253 0.4359075 -0.5574669 -0.7932596 0.2448874 -0.08334815 -0.9955088 0.04489386 -0.1099919 -0.9923997 0.05517905 -0.09726428 -0.9939762 0.05050909 -0.1145998 -0.9917535 0.05737614 -0.1285781 0.9897431 0.06225949 -0.1097145 0.9924659 0.05453675 -0.1285478 0.9897451 0.06229013 0.0126391 0.9998889 0.007907927 0.006256341 0.9999163 0.01132243 0.01739579 0.9998019 0.009674489 0.01043754 0.9999008 0.009460926 -0.06854599 -0.9969078 0.03842359 -0.05795556 -0.9977275 0.0343644 -0.06830137 0.9969316 0.03824019 -0.1590943 -0.9842609 0.07693779 0.04258966 -0.9990926 3.93864e-4 0.02976089 -0.9995502 0.003712594 0.02978479 -0.9995485 0.003973007 0.02654558 -0.9996352 0.004991531 0.003603219 -0.9999175 0.01233559 -0.02896225 -0.9993057 0.02343839 -0.02325558 -0.999502 0.02133285 -0.03006142 -0.9992609 0.02395755 0.09009051 0.9958951 -0.008755266 0.09102684 0.9958077 -0.009005844 0.08814966 0.9960899 -0.005867779 0.08767622 0.9961288 -0.006363213 0.09077823 0.9958478 -0.006833612 0.08744877 0.9961491 -0.006320238 0.08862131 0.9960252 -0.008952975 0.08934652 0.9959609 -0.008904874 0.08984881 0.9959191 -0.008517682 0.08921498 0.9959729 -0.008867561 0.08215284 0.9966106 -0.004280984 0.09069627 0.9958462 -0.008042454 0.08964723 0.9959385 -0.008360743 0.08889132 0.9960271 -0.005349755 0.09069472 0.9958464 -0.008041918 0.0878719 0.9961193 -0.005008161 0.08893245 0.9960233 -0.005357205 0.08725768 0.9961483 -0.008650422 0.08853691 0.996034 -0.008803665 0.08704626 0.9961615 -0.009236037 0.08806443 0.9960771 -0.008673369 0.08960074 0.9959408 -0.008578181 0.08806127 0.9960827 -0.008043587 0.08737003 0.996163 -0.005089521 0.08903205 0.996011 -0.005958139 0.08616763 0.9962707 -0.004471361 0.08754819 0.9961467 -0.005201697 0.08698058 0.9961737 -0.008500635 0.08580279 0.9962748 -0.008637964 0.08557325 0.9962909 -0.009034156 0.08517169 0.9963317 -0.008305609 0.0851733 0.9963269 -0.008851885 0.08617728 0.9962422 -0.008665204 0.08718085 0.9961573 -0.008383214 0.08207863 0.9966207 -0.003228187 0.08960044 0.995945 -0.008079349 0.0861786 0.9962469 -0.008093357 0.08474457 0.9963952 -0.003864884 0.08833593 0.996058 -0.008086025 0.08402657 0.9964569 -0.003642559 0.08436536 0.996428 -0.003739178 0.08439642 0.9963975 -0.008323609 0.08392459 0.9964327 -0.00886631 0.08442294 0.9963955 -0.008296191 0.08749848 0.9961463 -0.006073296 0.0871793 0.9961651 -0.00741434 0.08442288 0.9963968 -0.008149743 0.08279347 0.9965599 -0.003700971 0.08614099 0.9962615 -0.006550669 0.08402097 0.9964311 -0.008108079 0.08298736 0.9965164 -0.008273184 0.08233517 0.9965714 -0.008163869 0.08233356 0.9965713 -0.008173763 0.08281183 0.9965303 -0.008341014 0.08489501 0.9963532 -0.008565425 0.0828132 0.9965348 -0.007776379 0.08004832 0.9967896 -0.001677453 0.08579862 0.9962812 -0.007914006 0.08050131 0.9967526 -0.001967787 0.08144676 0.9966743 -0.002628862 0.08153903 0.9966385 -0.007951736 0.08119881 0.9966629 -0.008368074 0.08006387 0.9967598 -0.007726907 0.07580941 0.9971199 0.002227842 0.08489382 0.9963629 -0.007355332 0.08158999 0.9966323 -0.008206963 0.07816308 0.9969404 -6.452e-4 0.08335244 0.9965058 -0.005350768 0.07913339 0.9968634 -0.0011487 0.08016258 0.9967505 -0.007896184 0.07995331 0.9967687 -0.00773561 0.08262544 0.9965434 -0.008630394 0.08349329 0.9964788 -0.007679998 0.07758235 0.9969859 -3.77728e-4 0.07696956 0.9970335 6.10385e-5 0.0777933 0.9969694 -4.57787e-4 0.0783711 0.9968965 -0.007450044 0.07820862 0.9969047 -0.00802946 0.07820743 0.9969098 -0.007392406 0.08262383 0.9965555 -0.007109045 0.07952338 0.9967959 -0.008610844 0.08179128 0.9966329 -0.00576806 0.07464945 0.9972086 0.001586973 0.07571852 0.9971288 9.7662e-4 0.07674819 0.9970242 -0.00723946 0.08038526 0.9967234 -0.008987963 0.08015412 0.9967768 -0.003379285 0.07400757 0.9972558 0.002014219 0.07510477 0.9971521 -0.006856918 0.07538622 0.9971219 -0.008064508 0.07538342 0.9971303 -0.006973087 0.06662249 0.9977512 -0.007354974 0.08038258 0.9967381 -0.007198631 0.07733303 0.9969659 -0.008874118 0.07321602 0.9973132 0.002441525 0.08051496 0.9967269 -0.007271945 0.0790432 0.9968603 -0.004669308 0.07803481 0.9969038 -0.009665489 0.07552522 0.99711 -0.008223474 0.07260441 0.9973576 0.002533018 0.07243734 0.9973521 -0.006456732 0.07302409 0.9972941 -0.008481025 0.07302117 0.9973078 -0.006705284 0.07802402 0.9969274 -0.006937086 0.07411921 0.9972089 -0.008993923 0.07800948 0.9969286 -0.006928861 0.07657229 0.9970576 -0.003570675 0.07168918 0.9974227 0.002929806 0.07327634 0.9972727 -0.008819997 0.07184153 0.9973887 -0.007385551 0.07060599 0.9974856 -0.006107747 0.07532924 0.9971085 -0.01001536 0.07274711 0.9973146 -0.008464515 0.06997972 0.9975396 0.004211544 0.0695483 0.9975604 -0.006035029 0.07532948 0.997138 -0.006424844 0.07145285 0.9974014 -0.009226441 0.07394683 0.9972298 -0.008056938 0.06820917 0.9976546 0.005737483 0.06835097 0.9976454 -0.005655348 0.07282596 0.9972906 -0.01038843 0.07007408 0.9975043 -0.00865066 0.06692862 0.9977346 0.006805777 0.06170988 0.9979177 0.01876932 0.06670498 0.9977575 -0.005520045 0.07138359 0.9974173 -0.007965385 0.06549382 0.99782 0.008118033 0.06012213 0.9979664 0.02118003 0.07040774 0.9974585 0.01092582 0.06600177 0.9978054 -0.005292832 0.07021963 0.9974744 -0.010679 0.05856603 0.9980034 0.02365225 0.06424319 0.9978914 0.009247362 0.06737512 0.9976891 -0.00877875 0.06909608 0.9975293 0.01269608 0.0640456 0.9979344 -0.004999995 0.06259542 0.9980174 -0.006561636 0.06392568 0.9979424 -0.004959642 0.06762987 0.9976016 0.01474058 0.05697882 0.9980304 0.02624624 0.06228858 0.9979915 0.01153606 0.06230813 0.998046 -0.004684567 0.0553621 0.9980445 0.02902388 0.06613487 0.9976695 0.0167855 0.06460887 0.9977301 0.01898282 0.05929839 0.9981237 0.01525944 0.0613659 0.998106 -0.004330396 0.0596888 0.9982078 -0.004313409 0.06110197 0.9981228 -0.004194676 0.06072729 0.9981457 -0.004181325 0.060584 0.9981544 -0.004189252 0.05972629 0.9981954 -0.006225883 0.06115472 0.9981184 -0.00445044 0.06219708 0.9980223 -0.009125053 0.06295138 0.9979756 -0.009048461 0.05374443 0.9980414 0.03201466 0.06163901 0.9980888 -0.004395484 0.05882537 0.9982587 -0.004384517 0.05595654 0.9984288 -0.002994656 0.06070399 0.998147 -0.004196345 0.05945545 0.9982237 -0.003797352 0.05958074 0.998216 -0.003901362 0.059511 0.9982202 -0.003880977 0.06096392 0.9981313 -0.004158318 0.05969893 0.9981782 -0.008735358 0.05203473 0.9980295 0.03506618 0.06405925 0.9979394 0.003662228 0.06296062 0.9977874 0.02136325 0.06019181 0.9981788 -0.004016518 0.05797469 0.9983119 -0.003523528 0.05756884 0.9983356 -0.003444969 0.05793249 0.9983144 -0.003499031 0.05790615 0.9983154 -0.003636002 0.05811017 0.9983035 -0.003666341 0.05788528 0.9983167 -0.003618121 0.05795359 0.9983127 -0.003640413 0.05817532 0.9982993 -0.003773927 0.05804955 0.9983069 -0.003722012 0.06125104 0.99784 0.02374351 0.05029523 0.9980009 0.03827077 0.05725324 0.9982087 0.01736515 0.05740994 0.9983452 -0.003337562 0.05615204 0.9984176 -0.003068506 0.05628323 0.99841 -0.003142476 0.05591177 0.9984307 -0.003161787 0.05610591 0.9984197 -0.00322014 0.0564118 0.9984022 -0.003288328 0.05610197 0.9984204 -0.003044188 0.0561524 0.998417 -0.003258228 0.05615913 0.9984172 -0.003062248 0.05673497 0.9983844 -0.003127157 0.05615788 0.9984176 -0.002939343 0.06146532 0.9980946 0.005401849 0.05624306 0.9984117 -0.003307342 0.0594207 0.9978839 0.02639901 0.05496448 0.9982727 0.02075284 0.05479806 0.9984939 -0.002707064 0.05462819 0.9985034 -0.002620816 0.05604726 0.9984234 -0.003065645 0.05412006 0.9985311 -0.002634108 0.05441635 0.9985145 -0.002783775 0.05452984 0.998508 -0.002879142 0.05453401 0.9985079 -0.0028795 0.05385792 0.9985455 -0.002529144 0.05421233 0.998526 -0.002637267 0.05370932 0.9985537 -0.002427458 0.05439388 0.9985162 -0.002582728 0.05463397 0.9985021 -0.002935111 0.05513286 0.998475 -0.002832472 0.05587512 0.9984328 -0.003172814 0.05752867 0.9979174 0.02917635 0.04852563 0.9979503 0.04171985 0.05234032 0.9986177 -0.004822015 0.04669421 0.9978833 0.04525983 0.05270886 0.9986075 -0.002227783 0.05427241 0.9985224 -0.002789735 0.0532422 0.9985788 -0.002406656 0.05262559 0.9986115 -0.002433359 0.05256283 0.9986153 -0.002190291 0.05361789 0.9985578 -0.002740263 0.05256158 0.9986154 -0.002153158 0.05244207 0.9986215 -0.00227946 0.05294972 0.9983235 0.02337718 0.04483282 0.9977974 0.04889184 0.05560564 0.9979414 0.03195339 0.0525875 0.9986141 -0.002122938 0.05214613 0.9986367 -0.002348363 0.05060791 0.9987171 -0.001790046 0.05254751 0.9986156 -0.002403378 0.05090814 0.9987014 -0.002013921 0.05032145 0.9987317 -0.001647472 0.05069303 0.9987127 -0.001762628 0.05243873 0.998622 -0.00211656 0.05069178 0.9987129 -0.001689672 0.05098426 0.9986975 -0.002009332 0.05052161 0.9987217 -0.001637935 0.0498991 0.9987452 -0.004242181 0.0505259 0.9987211 -0.001832187 0.05191308 0.9986481 -0.002655148 0.05179023 0.9985722 0.01309251 0.05362242 0.9979508 0.03491407 0.04293978 0.9976866 0.05270576 0.05096697 0.9983425 0.02673476 0.04268491 0.999088 0.00117886 0.04963141 0.9987658 -0.001921951 0.04878509 0.9988086 -0.001218199 0.04431903 0.9990175 -9.7318e-5 0.01534122 0.9998567 0.007158219 0.04270893 0.9990875 -3.77538e-4 0.05059391 0.9987178 -0.001756668 0.05008369 0.9987432 -0.001916527 0.04859095 0.9988179 -0.00137639 0.04913371 0.9987913 -0.001376271 0.04902637 0.9987967 -0.001334726 0.04870545 0.9988126 -0.001169741 0.04861986 0.9988167 -0.001163363 0.04859161 0.9988181 -0.001154065 0.04859787 0.9988175 -0.001392602 0.04779243 0.9988504 -0.003723263 0.04937934 0.998757 -0.006805658 0.04878467 0.9988083 -0.001457929 0.05145537 0.9979476 0.03811848 0.04831153 0.9983366 0.03146505 0.04544097 0.9989671 -2.6972e-4 0.04696959 0.9988961 -7.55975e-4 0.03827178 0.9992665 0.001433134 0.03828901 0.9992658 0.001409649 0.02198791 0.9997429 0.005557775 -0.02077203 0.999724 0.01098656 -0.3236536 -0.9434328 0.07199424 -0.9855166 0.06515783 0.156562 0.03515803 0.9993804 0.001709043 0.04673045 0.9989073 -7.55855e-4 0.04673081 0.9989053 -0.002097725 0.9916526 -0.03909474 -0.1228693 0.04761004 0.9988657 -8.85059e-4 0.04904401 0.9987958 -0.001281797 0.05761969 0.998335 -0.002746701 0.04652088 0.9989172 -5.57028e-4 0.04664826 0.9989113 -6.57139e-4 0.0465936 0.9989136 -8.80655e-4 0.04658806 0.9989141 -6.37222e-4 0.04677516 0.9989051 -9.45097e-4 0.04721331 0.9988657 -0.006195366 0.0455957 0.9989551 -0.003143429 0.04095625 0.9975385 0.0569176 0.04922658 0.99793 0.04138326 0.03888142 0.9973667 0.06122142 0.04767781 0.9988623 -9.74845e-4 0.04690605 0.9988991 -7.97944e-4 0.04690361 0.9988992 -7.95728e-4 0.04468184 0.9990013 -1.70336e-4 0.04701453 0.9988939 -8.47709e-4 0.0472235 0.998884 -9.29506e-4 0.0446667 0.9990019 -3.03956e-4 0.0448383 0.9989943 -3.05018e-4 0.02404254 0.9996983 0.005036473 0.04467159 0.9990012 -0.001071393 0.04467183 0.9990017 -3.4626e-4 -0.0241481 0.9996367 0.01197624 -0.004364252 -0.9999392 -0.01013243 0.06115978 0.99812 -0.003997921 0.04577863 0.9989517 -6.10382e-5 0.0442565 0.9990202 -2.9803e-5 0.98739 -0.02594137 -0.1561671 0.9978594 -0.03924781 -0.05231004 0.04416322 0.9990244 -2.42626e-4 0.04491984 0.9989906 -2.70449e-4 0.04257357 0.9990903 -0.002471983 0.04455572 0.9990069 -4.07673e-4 0.04449629 0.9982681 0.03848409 0.04506331 0.9989841 -3.0938e-4 0.04368519 0.9990454 1.86526e-6 0.04308158 0.9990716 2.8471e-4 0.04063868 0.9991737 7.58264e-4 0.04451578 0.9990087 -1.76848e-4 0.04260063 0.9990922 2.91862e-4 0.04470354 0.9990003 -3.60274e-4 0.0429421 0.9990776 2.85626e-5 0.04228568 0.9991056 2.45788e-4 -0.03457188 -0.9994015 -0.001206278 -0.03009241 -0.99954 -0.003781378 -0.009220182 -0.9999414 -0.005695819 0.04150605 0.9991373 0.001464903 0.9899569 -0.03616541 -0.1366657 0.04238086 0.9991015 4.18786e-5 0.04330611 0.999062 -3.05188e-5 0.04120016 0.9991509 5.18817e-4 0.04275733 0.9990752 -0.004547297 0.04501581 0.9989858 9.76615e-4 0.04168891 0.9981544 0.04416096 0.03973162 0.9992097 0.001248955 0.0421195 0.9991126 3.81837e-4 0.0402224 0.9991903 9.22789e-4 0.04253256 0.9990952 2.24187e-4 0.03769844 0.9992871 0.002052366 0.04022258 0.9991905 7.98852e-4 0.04029929 0.9991874 7.85658e-4 0.04165774 0.9991313 0.001108944 0.0437777 0.9990413 3.37319e-4 0.04038274 0.9991841 6.62245e-4 -0.02387589 -0.9997147 -7.87799e-4 -0.03091818 -0.9995202 -0.001886606 0.04001969 0.9991886 0.004556357 0.9965097 -0.03585994 0.07538217 0.04014873 0.9991934 8.31896e-4 0.9855747 -0.03222787 -0.1661444 0.03924763 0.9992285 -0.001464903 0.0396437 0.9992119 0.002014219 0.04040771 0.9991764 -0.003723323 0.04071307 0.9991708 4.89936e-4 0.0423603 0.9990995 0.002410948 0.03473019 0.9969223 0.07028442 0.04119384 0.9991509 7.83986e-4 0.0328316 0.9994562 0.003108799 0.03802496 0.9992753 0.001754105 0.03866642 0.9992516 0.001135528 0.0379424 0.9992788 0.001517593 0.03754299 0.9992939 0.001541435 0.0380125 0.9992764 0.001344442 0.04306787 0.9990723 6.3071e-5 0.0379216 0.9992799 0.001353144 0.04391336 0.9990353 4.04667e-4 0.03734034 0.9993013 0.001637876 0.04381299 0.9990397 5.12941e-4 -0.02746707 -0.9996125 -0.004535496 -0.03237009 -0.9994746 -0.001647412 -0.03069609 -0.9995222 -0.003641366 -0.02625012 -0.9996517 -0.002747654 0.9981224 -0.03241109 0.05197376 -0.02307265 -0.9997237 -0.004516839 0.03787386 0.9992789 -0.002716124 0.0371719 0.999309 2.44151e-4 0.03845369 0.9992474 0.005096614 0.03885078 0.9980044 0.04977661 0.03882277 0.9992451 0.00146538 0.03525483 0.9993752 0.002542257 0.03534942 0.9993721 0.002404451 0.03534948 0.9993731 0.001925766 0.03812152 0.9992721 0.001421868 0.03483355 0.9993906 0.002299308 0.03542369 0.9993703 0.00204885 0.04201632 0.9991169 4.73349e-4 0.03521883 0.9993771 0.002275168 0.03904789 0.9992345 0.002388536 0.03574901 0.9993588 0.002024471 0.0353868 0.9993711 0.002323031 0.04165005 0.9991318 0.001011252 -0.02782231 -0.9996098 -0.002482593 0.03533446 0.9993581 0.005918681 0.9992453 -0.03045767 -0.02410978 0.1678875 -0.007446706 -0.9857781 0.03796577 0.9989517 0.02557498 0.03573775 0.9977582 0.05658221 0.03632086 0.9993379 0.002170979 0.03288227 0.9994546 0.003085553 0.03325718 0.9994424 0.003008902 0.0321725 0.9994775 0.003095269 0.03276741 0.999459 0.002843737 0.03200143 0.999483 0.003119885 0.03270065 0.9994612 0.002831339 0.0398488 0.9992051 0.001180648 0.04001599 0.9991982 0.001368224 0.03214973 0.9994774 0.003366947 0.03766345 0.9992889 0.001821041 -0.0263825 -0.9996412 -0.004619717 -0.02756655 -0.9996168 -0.002549171 -0.02865731 -0.9995886 -0.00125122 0.03149533 0.9994893 0.00540179 0.03314381 0.9989855 0.03048866 0.02952903 0.9995555 0.004123508 0.0299412 0.9995439 0.003966629 0.02897417 0.999572 0.004047513 0.02977705 0.9995496 0.003724813 0.03064286 0.9995245 0.003455519 0.02983272 0.999548 0.003752708 0.03252232 0.9994544 0.005757689 0.03256398 0.9994645 0.003202497 0.02957451 0.9995544 0.004070878 0.02987664 0.9995453 0.004076242 0.03760522 0.9992908 0.001922845 -0.04092586 -0.9991587 0.002624571 0.03137379 0.9993847 0.01568686 0.02843797 0.999587 0.004146277 0.02340328 0.9997082 0.005992174 0.026775 0.999631 0.004595518 0.02685064 0.999629 0.004583895 0.02587532 0.999652 0.005153954 0.02941811 0.9995389 0.007520198 0.02825772 0.9995914 0.004327714 0.03540015 0.9993703 0.002431094 0.02611833 0.9996455 0.005189657 0.03525209 0.9993754 0.002500474 0.02658206 0.9993456 0.02453726 0.02609348 0.9989079 0.03875875 0.02896249 0.9969646 0.07226902 0.02715003 0.9996206 0.004657387 0.02637326 0.9996393 0.005088806 0.02634078 0.9996417 0.004772245 0.02353584 0.9997075 0.005578219 0.02358329 0.9997065 0.005568206 0.02309769 0.9997166 0.005784988 0.02301454 0.9997164 0.006122469 0.02378654 0.999701 0.005673646 0.02641463 0.999614 0.008625805 0.02320957 0.9997123 0.006053745 0.03283888 0.9994558 0.003124773 0.03288805 0.9994544 0.003025293 0.02255326 0.9993322 0.02874851 0.02438485 0.9961786 0.08386689 0.02093571 0.9997584 0.006714046 0.02038711 0.9997683 0.006913244 0.019836 0.9997774 0.007191598 0.0199601 0.9997764 0.006994426 0.02189987 0.9997346 0.007158637 0.02151399 0.9997439 0.007030785 0.02335441 0.9997026 0.007020771 0.02011203 0.9997755 0.006673574 0.006408929 0.9999172 0.01116985 0.001953184 0.9999071 0.01348954 0.002014219 0.9999182 0.01263475 0.01958864 0.9997846 0.006863772 0.02011018 0.9997733 0.007003486 0.01996254 0.9997759 0.007054924 0.02315568 0.9996764 0.0105437 0.02320945 0.9997123 0.006053924 0.01941937 0.9997862 0.007101297 0.03061223 0.9995253 0.00348252 0.01864719 0.9992888 0.03277754 0.0202431 0.9997707 0.006986677 0.01676851 0.999827 0.008056402 0.01618289 0.9998367 0.008055448 0.01979893 0.999779 0.007071733 0.01584595 0.9998184 0.0105881 0.01987004 0.9997799 0.006728231 0.01649826 0.9998078 0.01059043 0.01271343 0.9998399 0.01259315 0.01740646 0.9998207 0.007471501 0.01658338 0.9998323 0.00777471 0.01677983 0.9998269 0.008050203 0.01626312 0.9998345 0.008155167 0.02830415 0.9995912 0.004036307 0.01963478 0.9997248 0.01284283 0.01745706 0.9998172 0.007802426 0.02832782 0.9995908 0.003971934 0.01583325 0.999843 0.007969081 -0.01022392 0.9983161 0.05710154 0.0200206 0.9952929 0.09482318 0.01640981 0.9998316 0.008221149 0.01280504 0.9998742 0.009370088 0.01727348 0.9998199 0.007873773 0.01536446 0.9998465 0.008437573 0.01052582 0.9998652 0.01259827 0.01265299 0.9998796 0.008987009 0.01272606 0.999879 0.008959352 0.01265186 0.9998768 0.009297311 0.01252001 0.999878 0.009349942 0.01593095 0.9998348 0.008758962 0.01944035 0.9997913 0.006286799 0.02621567 0.9996456 0.00463885 0.02124106 0.9997339 0.009002983 0.01246207 0.9998781 0.009405791 0.02707046 0.9996252 0.004089534 0.01432293 0.9998635 0.008237898 0.02325552 0.9996222 0.01464915 0.01538145 0.9941205 0.1071821 0.008470833 0.9999063 0.01076406 0.001069009 0.9999126 0.01318341 0.01019334 0.9998958 0.01022386 0.008601307 0.9999063 0.01065945 0.005435228 0.9998911 0.01372087 0.00866878 0.9998688 0.01368224 0.008576571 0.9999102 0.01030921 0.008653223 0.9999098 0.01027941 0.008575916 0.999907 0.01061767 0.008437275 0.9999075 0.01067376 0.01043748 0.9998964 0.009918689 0.006225824 0.9999173 0.0112614 0.01251941 0.9998776 0.009384393 0.001922667 0.999918 0.01266527 0.001861631 0.9999157 0.01284837 0.006500482 0.9998545 0.01577818 0.01263386 0.9998798 0.008997082 0.008367359 0.9999074 0.01073449 0.006836295 0.9995061 0.03067183 0.006958246 0.9982719 0.05835205 0.001983702 0.9998173 0.01901298 0.0107426 0.992653 0.1205185 0.00809586 0.9999074 0.01093959 0.002227842 0.999915 0.01284837 -0.002319395 0.9998901 0.01464903 0.002472043 0.9998968 0.01416081 0.006378471 0.9999014 0.01251286 -0.007996022 0.9998406 0.01596152 -0.01333665 0.999764 0.01715153 -0.01309281 0.9997538 0.01791483 0.006286799 0.9999155 0.01138347 0.008437037 0.9999071 0.01070815 -0.002807736 0.9998919 0.01443541 -0.003204464 0.9998894 0.01452696 0.001770019 0.9999095 0.01333659 0.002075254 0.9993796 0.03515803 0.002105772 0.997942 0.06408995 -0.002838253 0.9997417 0.0225535 0.005249202 0.9906962 0.135991 0.004455685 0.9999167 0.01211589 -0.004639387 0.9998742 0.01517057 -0.0032655 0.9998857 0.01477104 -0.008728325 0.999822 0.01672422 -0.01342839 0.9997444 0.01818937 -0.007782399 0.9998399 0.01611411 -0.01321482 0.9997506 0.01800632 0.002723693 0.9999163 0.01265627 -0.007141411 0.9998599 0.01513737 -0.002777218 0.9998902 0.01455748 -0.002533078 0.9998987 0.01400828 -0.002655148 0.9998955 0.01422184 -0.008056938 0.9996158 0.0265209 -0.007873892 0.9998075 0.01797574 -0.002899289 0.9998742 0.01559537 -0.00778234 0.999839 0.01617515 -0.007995963 0.9998382 0.01611411 -0.002929806 0.9991926 0.04007142 -0.003021299 0.9975353 0.07010149 -0.005981683 0.9915865 0.1293082 -0.009674608 0.9839462 0.1782029 -2.13631e-4 0.9883502 0.1521971 -4.88309e-4 0.9999039 0.01385575 -0.001220762 0.9999075 0.01355057 -0.009033501 0.9998224 0.01654112 -0.01199394 0.9998027 0.01583933 -0.007873952 0.9998455 0.01571744 -0.007782399 0.9998448 0.01580899 -0.01351994 0.999746 0.01803678 -0.008362293 0.9989279 0.04553478 -0.008667349 0.9969912 0.0770297 -0.01373338 0.9994277 0.03091543 -0.006348013 0.9853194 0.1706035 -0.005951166 0.9998579 0.01577818 -0.01393759 0.9997357 0.01829081 -0.01229906 0.9997655 0.01782298 -0.01269572 0.9997611 0.01779234 -0.01687705 0.9997146 0.01690757 -0.01947087 0.9996082 0.02011179 -0.01953184 0.9996058 0.02017277 -0.01342815 0.9996964 0.02066105 -0.01425212 0.9985674 0.05157637 -0.01458823 0.9963341 0.08429437 -0.01989835 0.999161 0.03579872 -0.01388621 0.9897378 0.1422194 -0.01974576 0.9786213 0.2047212 -0.02182108 0.9995909 0.01849454 -0.01922667 0.9996362 0.01892149 -0.02594131 0.9994118 0.02243155 -0.02597177 0.9994097 0.02249258 -0.01944065 0.9995306 0.02368277 -0.0205698 0.998093 0.0581997 -0.02102762 0.9955017 0.09238123 -0.02649062 0.9988009 0.04117035 -0.02041751 0.9879452 0.1534518 -0.01767241 0.9996401 0.02018243 -0.02711778 0.9993665 0.02305251 -0.02273684 0.999506 0.02169919 -0.03695857 0.9989502 0.0270704 -0.03988784 0.9988139 0.02792453 -0.01907444 0.9996225 0.01977634 -0.0268259 0.9994266 0.02066111 -0.02560573 0.9994484 0.02114987 -0.03289997 0.9991461 0.02499538 -0.02594077 0.9993003 0.02694785 -0.03305232 0.9991388 0.02508676 -0.02737528 0.9974755 0.06552374 -0.02792519 0.9944739 0.1012023 -0.03357058 0.9983294 0.04702937 -0.02719253 0.9858596 0.1653527 -0.02847433 0.973407 0.2273063 -0.01800632 0.9782631 0.2065846 -0.03514093 0.9990415 0.02610176 -0.03094613 0.9992191 0.02456766 -0.04010242 0.998807 0.02786415 -0.04339742 0.9986292 0.02926731 -0.04638904 0.9984636 0.03030544 -0.03152573 0.9992423 0.02282792 -0.03244149 0.9991865 0.02395725 -0.04034614 0.9987972 0.02786386 -0.04043769 0.9987961 0.0277723 -0.03286939 0.9989927 0.03054994 -0.0346089 0.9966998 0.07342946 -0.03524982 0.9932225 0.1107548 -0.04123061 0.9977147 0.05352962 -0.03421223 0.9834873 0.1777144 -0.03521895 0.9687966 0.2453426 -0.04152798 0.9987359 0.02832019 -0.05279773 0.9980612 0.03296041 -0.05612415 0.9978449 0.03399801 -0.05777257 0.9977298 0.0346086 -0.09500461 0.9942681 0.04904347 -0.1099614 0.9923997 0.05524009 -0.1174665 0.9913395 0.05871796 -0.03644007 0.9989895 0.02630764 -0.04187184 0.9987301 0.02801632 -0.04019296 0.9988127 0.02752774 -0.04849517 0.9983478 0.03082448 -0.04879951 0.998331 0.03088498 -0.04043781 0.9985858 0.0345171 -0.04242163 0.9957186 0.08212709 -0.04312348 0.9916883 0.1212219 -0.04968529 0.9969111 0.06082481 -0.04174983 0.9806329 0.1913534 -0.02771174 0.9711032 0.2370457 -0.04226905 0.9633388 0.2649372 -0.0479415 0.998378 0.03071171 -0.05073934 0.9982032 0.03187561 -0.06439483 0.9972354 0.0370804 -0.05908459 0.9958631 0.0690338 -0.05813896 0.9973353 0.04406964 -0.05804675 0.9977213 0.03439468 -0.05807709 0.9977184 0.03442507 -0.04880064 0.998048 0.03897333 -0.05099725 0.9944622 0.09189271 -0.05175977 0.989784 0.1328481 -0.05008262 0.9771456 0.206587 -0.04992938 0.9568381 0.2863007 -0.03790444 0.9619252 0.2706721 -0.1860415 0.9787629 0.086093 -0.1758516 0.9808871 0.08328688 -0.08008164 0.995863 0.04294008 -0.08026397 0.9958537 0.04281765 -0.06851559 0.9969099 0.03842365 -0.06854599 0.9969078 0.03842359 -0.06051939 0.9928479 0.1029105 -0.0612213 0.9874151 0.1458203 -0.06964373 0.9944838 0.07843315 -0.05923783 0.972862 0.2236755 -0.0581693 0.949051 0.3097074 -0.04800683 0.9512558 0.3046436 -0.06658214 0.9970653 0.03778582 -0.2258734 0.9686829 0.1031247 -0.2372252 0.9654728 0.107641 -0.233718 0.9663379 0.1075506 -0.3861882 0.9016551 0.19462 -0.9138782 -0.06793653 0.4002642 -0.8053631 -0.4530225 0.3823102 -0.08050793 0.9958208 0.0431227 -0.08054083 0.9958193 0.04309344 -0.06863814 0.9963975 0.04980766 -0.07111018 0.9907819 0.1153023 -0.07184153 0.9843882 0.1606822 -0.08169877 0.9926542 0.08923691 -0.06940114 0.9675569 0.2429345 -0.0672639 0.9395284 0.3358009 -0.2805047 0.9515367 0.126076 -0.2658849 0.9562945 0.1216807 -0.5539613 0.7943643 0.2492231 -0.6259534 0.718824 0.3024475 -0.5494027 0.7947753 0.2578548 -0.09439635 0.9943514 0.04852575 -0.1102644 0.9923796 0.05499482 -0.09460961 0.9934316 0.06436502 -0.09461015 0.9943221 0.04870891 -0.08066207 0.9951376 0.05652141 -0.0831651 0.9880626 0.1296765 -0.08374327 0.9805354 0.1775883 -0.09555608 0.9902005 0.1018431 -0.08081471 0.9608649 0.2649673 -0.07712221 0.9280914 0.3642781 -0.06045848 0.9359926 0.3467894 -0.09173107 0.9946412 0.04769033 -0.111854 0.9921591 0.05575913 -0.6655136 -0.6485751 0.3693805 -0.5572815 0.793409 0.2448254 -0.09418231 0.9943777 0.0484035 -0.1102045 0.9923897 0.05493438 -0.09396827 0.9944038 0.04828119 -0.09695869 0.9844806 0.1462774 -0.09717363 0.9755817 0.1969719 -0.1114556 0.9869254 0.1164302 -0.09372276 0.9523649 0.2902018 -0.07410061 0.9159729 0.3943386 -0.08865791 0.9128255 0.3986096 -0.1082548 0.9926471 0.05415588 -0.195934 0.9764047 0.09079498 -0.8497564 0.3561634 0.3886668 -0.7177836 0.5974766 0.3575032 -0.1101112 0.9924051 0.05484199 -0.1286967 0.9897164 0.06244093 -0.1291888 0.9896541 0.06241226 -0.1105086 0.9911591 0.07342821 -0.1125528 0.9798018 0.1652891 -0.1125246 0.9691097 0.2194642 -0.1297051 0.9825549 0.1332759 -0.1078867 0.9418348 0.3182889 -0.1011413 0.8946762 0.435115 -0.1526257 0.9856427 0.07220798 -0.1882137 0.9782717 0.08695 -0.1528393 0.9856119 0.07217746 -0.1528716 0.9855933 0.07236146 -0.1529002 0.9856113 0.07205533 -0.1290348 0.9880873 0.08386653 -0.1304066 0.9736093 0.1872936 -0.1300429 0.9606273 0.2455282 -0.1534184 0.975841 0.1555547 -0.1241537 0.927979 0.3513417 -0.09735685 0.873618 0.4767741 -0.1149041 0.8714703 0.4767984 -0.08804762 0.8921346 0.4431069 -0.4189356 -0.8872206 0.1932164 -0.5511378 -0.7940974 0.2562353 -0.4746928 -0.8547766 0.2098182 -0.2504701 -0.9612595 0.1150874 -0.3165445 -0.9374869 0.1446301 -0.2697896 -0.9550675 0.1227176 -0.1527803 0.9856254 0.07211738 -0.1880877 0.9639384 0.1882709 -0.189186 0.9746787 0.1192064 -0.1535095 0.9832547 0.0982095 -0.1533281 0.9642829 0.2159839 -0.1520171 0.9482069 0.2789167 -0.1440493 0.9084264 0.3924429 -0.1313245 0.8399212 0.5265797 -0.1062385 0.8543642 0.5086998 -0.2523049 0.9606323 0.1163098 -0.2125341 -0.9720598 0.09964442 -0.1881227 0.9783053 0.08676713 -0.1881781 0.978276 0.08697819 -0.2338955 0.9664672 0.1059916 -0.3182888 0.9373481 0.1416719 -0.2343876 0.9611723 0.1456377 -0.1885477 0.978202 0.08701026 -0.1864124 0.9480542 0.2577667 -0.1832965 0.9270421 0.3271015 -0.2313358 0.9456083 0.2287112 -0.1716069 0.8760408 0.4506704 -0.1525377 0.7913773 0.5919917 -0.1152709 0.8328986 0.541288 -0.1267451 0.8019459 0.5837966 -0.4305672 0.8795987 0.2022823 -0.2335005 0.9665659 0.1059618 -0.3616539 -0.9139011 0.1843672 -0.233717 0.9665167 0.1059326 -0.233502 0.9665721 0.1059014 -0.2271817 0.9234678 0.3091858 -0.2210524 0.895868 0.3854302 -0.3092244 0.9012432 0.3035477 -0.2035941 0.8316505 0.5166304 -0.1757299 0.7292273 0.6613219 -0.1406026 0.7597487 0.634833 -0.4923385 0.8429452 0.2169012 -0.3180415 0.9373999 0.1418842 -0.3179135 0.9374437 0.1418815 -0.3189868 0.927143 0.1966047 -0.2970446 0.8673593 0.3993149 -0.2830308 0.8280344 0.4839966 -0.5012222 0.7195894 0.4805909 -0.2508696 0.7454673 0.6175299 -0.205639 0.6249129 0.7531245 -0.1548565 0.7097029 0.687271 -0.1679771 0.6550924 0.7366395 -0.6075097 -0.7259537 0.3223714 -0.2294768 -0.9676849 0.1045296 -0.1493611 -0.9862291 0.07101821 -0.5572573 0.7933874 0.2449502 -0.5489173 0.767648 0.3307664 -0.4516232 0.6664174 0.5932323 -0.4076746 0.6135262 0.6763041 -0.7473219 -1.22077e-4 0.6644624 -0.3360783 0.5285329 0.779554 -0.1821385 0.5852361 0.7901419 -0.2510529 0.410456 0.8766404 -0.5341101 -0.8113433 0.2375891 -0.3294808 -0.9297547 0.1643131 -0.1735935 -0.9814074 0.08188313 -0.165078 -0.9830214 0.08011269 -0.9161497 -9.1557e-5 0.4008364 -0.5011883 -0.7196761 0.4804962 -0.4515938 -0.6665717 0.5930813 -0.624937 -9.15569e-5 0.7806753 -0.5354035 -6.1039e-5 0.8445965 -0.4306206 0 0.9025331 -0.8737958 -3.05192e-5 0.4862932 -0.2949993 0 0.9554975 -0.2067663 0.4238482 0.8818166 -0.2929181 -0.9470552 0.1314744 -0.1014763 -0.9934602 0.05234038 -0.1070615 -0.9927905 0.05389696 -0.1881496 -0.9782868 0.08691811 -0.1528382 -0.9856053 0.07226854 -0.5571631 -0.7934447 0.2449796 -0.557164 -0.7934155 0.2450716 -0.5573769 -0.793445 0.2444914 -0.318036 -0.9373836 0.1420037 -0.3182523 -0.937361 0.1416692 -0.5488294 -0.7676836 0.3308297 -0.4077108 -0.6136263 0.6761914 -0.309191 -0.9012349 0.303606 -0.3360461 -0.5284693 0.7796111 -0.2264193 -0.1733776 0.9584752 -0.2510784 -0.4104782 0.8766228 -0.2270314 0.1768885 0.9576885 -0.3179501 -0.9374309 0.1418842 -0.1217101 -0.9907414 0.06015312 -0.3178614 -0.93747 0.1418245 -0.2313326 -0.9455951 0.228769 -0.2343834 -0.9611552 0.1457571 -0.3189536 -0.9271353 0.1966946 -0.2970434 -0.8674167 0.3991912 -0.2830684 -0.8280858 0.4838867 -0.2508706 -0.7454397 0.6175628 -0.2055764 -0.624756 0.7532718 -0.2064605 -0.4255864 0.8810507 -0.182839 -0.9794753 0.08484268 -0.1926648 -0.9772098 0.08911466 -0.2335644 -0.966547 0.1059936 -0.2335317 -0.9665684 0.1058705 -0.2335301 -0.9665622 0.1059309 -0.233932 -0.9664614 0.1059637 -0.2272129 -0.9235007 0.3090645 -0.2210832 -0.8958996 0.3853391 -0.1881195 -0.9639141 0.1883636 -0.2035329 -0.8317415 0.516508 -0.1757282 -0.7290675 0.6614985 -0.1825029 -0.5833989 0.7914155 -0.167578 -0.6568837 0.7351336 -0.1098263 -0.9924392 0.05479586 -0.08731412 -0.9950945 0.04651057 -0.1881222 -0.9783028 0.08679747 -0.1890041 -0.978103 0.08713167 -0.1890339 -0.9747119 0.1191762 -0.1864394 -0.9480668 0.2577009 -0.1833887 -0.9270451 0.3270416 -0.1534505 -0.9758211 0.1556479 -0.1716411 -0.8760291 0.4506801 -0.1525052 -0.7912753 0.5921365 -0.1550984 -0.708594 0.6883597 -0.1304687 -0.989426 0.06335741 -0.09356266 -0.9944382 0.04836261 -0.07125926 -0.9966652 0.03975653 -0.05353105 -0.998016 0.03314405 -0.05005079 -0.9982393 0.03183108 -0.1526568 -0.9856469 0.07208621 -0.09454691 -0.9943296 0.04867726 -0.153692 -0.9831895 0.09857529 -0.1288218 -0.9897096 0.06228983 -0.15336 -0.9642911 0.2159247 -0.1521371 -0.9482247 0.2787908 -0.1297075 -0.9825419 0.1333698 -0.1441107 -0.9083371 0.392627 -0.1310479 -0.8402752 0.5260838 -0.1404216 -0.7604619 0.6340184 -0.1265034 -0.8026636 0.5828619 -0.05960267 -0.997603 0.03515636 -0.1283648 -0.9897766 0.06216812 -0.1286984 -0.9897295 0.06222808 -0.1293107 -0.9880356 0.08405047 -0.1304681 -0.9736129 0.1872332 -0.1300421 -0.9606824 0.2453131 -0.1114845 -0.9869115 0.1165201 -0.1241811 -0.9279555 0.3513938 -0.1157576 -0.8314834 0.5433559 -0.114935 -0.8715652 0.4766172 -0.09189337 -0.9946213 0.04779309 -0.1099914 -0.9924252 0.05472099 -0.1107843 -0.9911078 0.07370358 -0.09558546 -0.9901884 0.1019334 -0.09704983 -0.9844763 0.1462462 -0.1126471 -0.9797953 0.1652626 -0.09436613 -0.9943543 0.04852592 -0.1125853 -0.9691374 0.219311 -0.1079782 -0.9417419 0.3185326 -0.1015055 -0.8938954 0.4366323 -0.1064506 -0.8538327 0.5095468 -0.07861775 -0.995998 0.04251337 -0.05527108 -0.9979074 0.03355652 -0.09436351 -0.9943575 0.04846352 -0.09393805 -0.9944067 0.04828131 -0.08041721 -0.9958307 0.04306209 -0.08054083 -0.9958193 0.04309344 -0.09497642 -0.9933767 0.06467062 -0.09738636 -0.9755423 0.1970617 -0.0817309 -0.992643 0.08933019 -0.09375596 -0.9523313 0.2903017 -0.08756029 -0.892755 0.4419522 -0.08865791 -0.9128255 0.3986096 -0.09766066 -0.8729037 0.4780187 -0.08081936 -0.9957879 0.04329746 -0.06628727 -0.9970862 0.03775197 -0.08020335 -0.9958585 0.04281783 -0.05798625 -0.99773 0.03424239 -0.06842452 -0.9969173 0.03839343 -0.08102709 -0.9950925 0.05679523 -0.08328634 -0.9880526 0.1296752 -0.08389735 -0.9805216 0.1775913 -0.08090513 -0.9607909 0.2652078 -0.07718217 -0.9279565 0.3646088 -0.07428318 -0.9156304 0.3950987 -0.06813389 -0.9969384 0.03836488 -0.06830155 -0.996934 0.03817927 -0.06897342 -0.9963607 0.05008202 -0.06970626 -0.9944744 0.07849586 -0.07120126 -0.9907754 0.1153015 -0.07196515 -0.9843786 0.1606855 -0.05914521 -0.9958553 0.0690943 -0.06949168 -0.9674823 0.2432057 -0.06729537 -0.9394806 0.3359277 -0.06021505 -0.9361874 0.3463054 -0.0462051 -0.998476 0.03018283 -0.05774128 -0.9977463 0.03418087 -0.0486474 -0.9983403 0.03082424 -0.06064099 -0.9928405 0.1029097 -0.06140476 -0.9873901 0.1459126 -0.04974609 -0.9969062 0.06085503 -0.05932986 -0.9727785 0.2240131 -0.05823075 -0.9489668 0.3099539 -0.04762971 -0.9983963 0.03059935 -0.02504706 -0.9994381 0.02227735 -0.0401014 -0.998813 0.02764981 -0.04864752 -0.9983431 0.03073281 -0.04800701 -0.9983816 0.03048884 -0.0402854 -0.9988047 0.02768099 -0.04043769 -0.9987961 0.0277723 -0.04910469 -0.9980247 0.03918606 -0.0511493 -0.9944517 0.09192228 -0.0519129 -0.9897635 0.132941 -0.04129272 -0.9977105 0.05356156 -0.05020445 -0.9770491 0.2070133 -0.04901427 -0.9574577 0.2843807 -0.04846394 -0.9507539 0.3061346 -0.01755422 -0.999653 0.01964104 -0.04821985 -0.9983649 0.03070199 -0.03189206 -0.9992136 0.0235604 -0.03998017 -0.9988329 0.02710103 -0.03289997 -0.9991461 0.02499538 -0.03274655 -0.9991527 0.02493375 -0.04074347 -0.9985669 0.03470063 -0.04257386 -0.9957097 0.08215683 -0.04327565 -0.9916782 0.1212512 -0.03363156 -0.9983272 0.04702925 -0.04187202 -0.9805442 0.1917812 -0.03711158 -0.9626129 0.2683267 -0.03790438 -0.9663789 0.2543134 -0.02983003 -0.9992628 0.02417117 -0.03601199 -0.9989986 0.02655124 -0.0120626 -0.9997705 0.01771003 -0.02685642 -0.9994252 0.02069163 -0.03259402 -0.9991838 0.02386564 -0.02658212 -0.9987986 0.04117023 -0.0275591 -0.9974684 0.06555581 -0.0347613 -0.9966945 0.07342904 -0.02600222 -0.9994089 0.02249252 -0.0258193 -0.9994156 0.02240115 -0.03317409 -0.998977 0.03073257 -0.03549379 -0.9931865 0.1109983 -0.03430366 -0.9834235 0.1780496 -0.03252303 -0.999158 0.02501356 -0.02282452 -0.9995052 0.0216422 -0.02642965 -0.9993837 0.02310305 -0.006462216 -0.9998549 0.01576036 -0.02508682 -0.9994451 0.02191281 -0.02182108 -0.9995909 0.01849454 -0.0257582 -0.9994439 0.02118033 -0.01937937 -0.9996106 0.02008128 -0.01953184 -0.9996058 0.02017277 -0.02621591 -0.9992889 0.02710098 -0.02823007 -0.9944312 0.1015367 -0.0199899 -0.9991602 0.03576821 -0.0273447 -0.9857533 0.1659606 -0.02725315 -0.9713187 0.2362147 -0.02551364 -0.9750744 0.2204065 -0.028535 -0.9993064 0.02392667 -0.01931875 -0.9996019 0.02057003 -0.02401864 -0.9994767 0.02166867 -0.03051429 -0.9992435 0.02411079 -0.01687705 -0.9997141 0.01693809 -0.01934927 -0.9996326 0.01898306 -0.01303178 -0.9997552 0.01788437 -0.01351994 -0.999746 0.01803678 -0.01974564 -0.9995216 0.02380466 -0.02075278 -0.9980876 0.05822986 -0.02130222 -0.9954675 0.09268605 -0.02053928 -0.9878718 0.1539077 -0.01623612 -0.9794194 0.201182 -0.02157711 -0.999537 0.02145504 -0.01052337 -0.9997948 0.01731425 -0.01358085 -0.9997368 0.01849442 -0.01907444 -0.9996225 0.01977634 -0.01199394 -0.9998022 0.01586985 -0.01342821 -0.9997623 0.01718199 -0.007812857 -0.9998387 0.01617515 -0.007995963 -0.9998382 0.01611411 -0.01382499 -0.9994292 0.03082394 -0.01373362 -0.9996897 0.0207836 -0.01443564 -0.9985647 0.0515778 -0.01486283 -0.9963017 0.08462995 -0.00814855 -0.9996183 0.02639889 -0.01437437 -0.989546 0.1435 -0.01440495 -0.9815817 0.1904994 -0.01605302 -0.999684 0.01934909 -0.007995963 -0.9998318 0.01651072 -0.009308159 -0.9998183 0.01663261 -0.007141411 -0.9998599 0.01513737 -0.007904469 -0.9998453 0.01571744 -0.007873952 -0.9998431 0.01587003 -0.007996022 -0.9998406 0.01596152 -0.003143429 -0.9998905 0.01446592 -0.002807736 -0.9998919 0.01443541 -0.008179068 -0.9998039 0.01803672 -0.008575856 -0.9989247 0.04556518 -0.008881032 -0.996968 0.07730489 -0.002929806 -0.9997442 0.02243149 -0.008606314 -0.9910087 0.13352 -0.006988823 -0.9850607 0.1720659 -0.009705066 -0.9998053 0.01718223 3.71394e-4 -0.9999033 0.01390737 -0.004303097 -0.9998795 0.01492357 -0.002319395 -0.9998901 0.01464903 -0.002807736 -0.9998902 0.01455748 -0.005076527 -0.9998721 0.01517492 -0.002533078 -0.9998987 0.01400828 -0.002655148 -0.9998955 0.01422184 -0.003143429 -0.9998731 0.01562583 -0.003143429 -0.9991907 0.04010188 -0.003326475 -0.9975 0.07058948 -0.003235042 -0.9921889 0.1247026 -0.005554378 -0.9859364 0.1670287 8.24008e-4 -0.9888702 0.1487791 -0.005096673 -0.9998673 0.01547318 0.00412631 -0.9999102 0.01274859 0.001739561 -0.9999129 0.01309245 5.01518e-4 -0.9998971 0.01434355 -2.49536e-4 -0.9998918 0.01471346 0.001861631 -0.9999074 0.01348954 0.002014219 -0.9999182 0.01263475 0.001861631 -0.9999157 0.01284837 0.001678466 -0.9999105 0.01327556 0.001892149 -0.9998204 0.01886045 0.001892149 -0.9999181 0.01266527 0.001861631 -0.999379 0.03518849 0.006408929 -0.9998579 0.01559507 0.001770079 -0.9979131 0.06454783 0.001739561 -0.9932152 0.1162779 -0.001068174 -0.9998745 0.01580899 0.008681237 -0.9998978 0.01136165 0.007019221 -0.9999099 0.01144444 0.005438029 -0.9998914 0.01370239 0.004303634 -0.9998885 0.01429766 0.006256401 -0.9999018 0.01254338 0.008576154 -0.9999068 0.01062536 0.006408929 -0.9999172 0.01116985 0.006256282 -0.9999157 0.01138347 0.008430898 -0.9999071 0.01071459 0.004087388 -0.9999221 0.01179689 0.008367538 -0.9999074 0.01073217 0.006225824 -0.9999173 0.0112614 0.006592154 -0.9995068 0.03070241 0.01101732 -0.9998618 0.0124517 0.006256341 -0.9999174 0.01123088 0.006439566 -0.994046 0.108771 8.24009e-4 -0.988658 0.1501832 0.006958365 -0.9982575 0.05859714 0.005371212 -0.9907249 0.1357772 0.004944026 -0.9999155 0.01202434 0.01352626 -0.9998661 0.009206295 0.008693754 -0.9999058 0.01062119 0.004058957 -0.9999199 0.01199388 0.01053273 -0.9998654 0.01259142 0.008553445 -0.9998695 0.01371389 0.008535802 -0.9999104 0.01031512 0.008431553 -0.9999076 0.01066058 0.0124424 -0.9998784 0.009409189 0.01141411 -0.9995904 0.02624636 0.004255771 -0.9999218 0.01176047 0.01684623 -0.99982 0.008728265 0.01043754 -0.999902 0.009338855 0.01086467 -0.9947602 0.1016581 0.005096673 -0.99023 0.1393512 0.01361161 -0.9985919 0.05127245 0.01068162 -0.9926609 0.1204584 0.0087049 -0.9999056 0.01064145 0.01676493 -0.9998244 0.008389711 0.01266592 -0.999876 0.009356558 0.02138137 -0.9997403 0.007885158 0.008369743 -0.9999077 0.01070624 0.005264461 -0.999931 0.01050889 0.01210933 -0.9998749 0.01017856 0.01584231 -0.9998182 0.01060944 0.0126 -0.999841 0.01262396 0.008576929 -0.9999102 0.01030415 0.02355092 -0.9997072 0.005566418 0.01261478 -0.99988 0.008991837 0.01265221 -0.9998796 0.008982181 0.01251822 -0.9998782 0.009335994 0.01251739 -0.9998776 0.009389042 0.01244914 -0.9998815 0.00906074 0.008373737 -0.9999111 0.01038336 0.01467961 -0.9998641 0.007507622 0.008541464 -0.9999101 0.01034837 0.01262873 -0.9998908 0.007672369 0.01522886 -0.995401 0.09457772 0.01754856 -0.9996288 0.02084463 0.01538175 -0.9940477 0.1078556 0.01651632 -0.9998307 0.008127987 0.02236741 -0.9997212 0.007575631 0.01279056 -0.999875 0.009301066 0.01265591 -0.9998721 0.009790658 0.0215013 -0.9997437 0.007097363 0.01640683 -0.999809 0.01062226 0.01265126 -0.9998768 0.009303867 0.01647549 -0.9998342 0.007759749 0.01651704 -0.9998336 0.007749319 0.01637262 -0.9998332 0.008105158 0.01637214 -0.9998328 0.008158028 0.01630771 -0.9998364 0.007829308 0.01630139 -0.9998337 0.008177101 0.021577 -0.9988603 0.04257416 0.01262342 -0.9998796 0.009025335 0.01916587 -0.995894 0.08847439 0.00878936 -0.9914337 0.1303153 0.01709604 -0.999841 0.005069911 0.01245176 -0.9925436 0.1212525 0.01652354 -0.9998305 0.008126914 0.02399814 -0.9996942 0.005976021 0.02747952 -0.9996072 0.005517125 0.0165162 -0.9998309 0.008094549 0.0165103 -0.9998255 0.00873816 0.01767528 -0.999804 0.008928 0.02432155 -0.9996787 0.007147252 0.01988393 -0.9997798 0.006711721 0.01651591 -0.9998311 0.008071482 0.02014082 -0.9997732 0.006933748 0.01999872 -0.9997779 0.006655871 0.02014142 -0.9997752 0.006626546 0.02000606 -0.9997757 0.006964385 0.02000522 -0.9997753 0.007016837 0.02315169 -0.9997153 0.005779385 0.02399545 -0.9996952 0.005812466 0.01992189 -0.9997768 0.007038891 0.02386569 -0.9997057 0.004364192 0.02487277 -0.9995816 0.01477104 0.01704519 -0.9998252 0.0076828 0.0200507 -0.9952428 0.09534013 0.01571726 -0.9934241 0.1134086 0.02304148 -0.9963405 0.08230865 0.02027285 -0.9997704 0.006949901 0.02355384 -0.999705 0.00593394 0.02960371 -0.9995515 0.004540264 0.02001583 -0.9997752 0.006995856 0.02013033 -0.9997707 0.007311046 0.02369767 -0.999704 0.005536198 0.0234273 -0.9997085 0.005846619 0.02342522 -0.9997079 0.00595951 0.01993101 -0.9997797 0.00659269 0.02062821 -0.9997796 0.003920376 0.03018283 -0.9995442 7.01927e-4 0.02306437 -0.9997171 0.005817174 0.02283453 -0.9997367 0.002281069 0.02664303 -0.9966893 0.07681626 0.01892197 -0.9941998 0.1058717 0.0290234 -0.9989732 0.03479146 0.02438449 -0.9961633 0.08404868 0.02584385 -0.9996524 0.005230009 0.02692604 -0.9996253 0.00491333 0.03388535 -0.9994177 0.004016518 0.02379411 -0.9996998 0.005846619 0.0226919 -0.9997209 0.006580948 0.02640289 -0.9996401 0.004747152 0.0234909 -0.9997085 0.005595088 0.02680093 -0.9996303 0.004586517 0.02600526 -0.9996491 0.005070924 0.02684527 -0.9996291 0.004579663 0.0266385 -0.999633 0.00493288 0.02663737 -0.9996327 0.005014657 0.02652317 -0.999637 0.004763782 0.02801603 -0.9996051 0.002197325 0.02654641 -0.9996363 0.004758954 0.02664577 -0.9996447 6.92647e-4 0.03003054 -0.9969903 0.07147514 0.0219435 -0.9948753 0.0987001 0.03170877 -0.9994521 0.009491264 0.02819925 -0.996802 0.0747708 0.02675688 -0.9996298 0.004954278 0.03265911 -0.9994605 0.003494083 0.02978456 -0.9995482 0.00405693 0.02964192 -0.9995527 0.004003703 0.02978152 -0.9995496 0.003722548 0.02909708 -0.9995687 0.003996193 0.03267019 -0.9994621 0.002866387 0.02980768 -0.9995477 0.003997862 0.02980846 -0.9995489 0.003702521 0.02968096 -0.9995514 0.004024982 0.02967977 -0.9995511 0.004105448 0.02956151 -0.9995555 0.003856837 0.0378735 -0.9992696 0.005096554 0.02955508 -0.9995546 0.00413531 0.02958166 -0.999555 0.003852546 0.03317445 -0.9972185 0.06674569 0.03100699 -0.9995186 0.001037597 0.03570681 -0.998967 0.02810764 0.02475082 -0.9954359 0.09216713 0.03003281 -0.9995409 0.004019439 0.03265386 -0.9994617 0.003190696 0.03267002 -0.999462 0.002918064 0.03268891 -0.9994606 0.003153622 0.03268957 -0.9994615 0.002862393 0.03255909 -0.9994648 0.003180623 0.03255802 -0.9994646 0.003259718 0.03242248 -0.9994697 0.003017544 0.03378427 -0.9994292 9.15564e-5 0.03192251 -0.9973202 0.0658288 0.02746689 -0.9959189 0.08597135 0.03634804 -0.9974208 0.06189244 0.03282541 -0.9994561 0.003166496 0.03539776 -0.9993704 0.002428829 0.0337637 -0.9994257 0.002860426 0.03535437 -0.9993734 0.001702785 0.03299456 -0.9994515 0.00287652 0.03325062 -0.9994438 0.002558112 0.03486615 -0.9993889 0.002483069 0.03214216 -0.9994788 0.0030303 0.03639566 -0.9993357 0.001888036 0.03546798 -0.9993687 0.002089381 0.03541719 -0.9993705 0.002079606 0.03539699 -0.9993712 0.00210148 0.03540849 -0.9993701 0.002370178 0.03540951 -0.9993708 0.002081215 0.03528171 -0.9993746 0.002395927 0.03515839 -0.9993786 0.002500653 0.03528064 -0.9993744 0.002472877 0.03246653 -0.9994684 0.003008782 0.03516477 -0.9993791 0.00222969 0.0416581 -0.9988801 0.02243131 0.03915554 -0.997567 0.05768042 0.02993899 -0.996319 0.08032566 0.03543305 -0.9977114 0.05759018 0.03575682 -0.9993578 0.002368271 0.03792279 -0.9992792 0.001707673 0.04204386 -0.9991155 6.94542e-4 0.03535419 -0.999372 0.002402603 0.03789806 -0.9992809 0.001151382 0.03782421 -0.9992833 0.001506447 0.03580528 -0.9993563 0.002268075 0.03833484 -0.999264 0.00143218 0.03738445 -0.9992997 0.001601696 0.03796809 -0.999278 0.001366317 0.03784143 -0.9992824 0.001671075 0.03790575 -0.9992805 0.001378357 0.03796756 -0.9992777 0.001646339 0.03768467 -0.9992881 0.001781702 0.0351963 -0.999378 0.00222361 0.0378406 -0.9992823 0.00174719 0.03769057 -0.9992884 0.001516997 0.04187172 -0.9976897 0.0534994 0.03891122 -0.9992416 -0.001525878 0.04297095 -0.9990747 0.001831114 0.03888165 -0.9979835 0.05017381 0.03815692 -0.9992703 0.001673698 0.0453943 -0.9989692 -1.60271e-4 0.03789848 -0.9992803 0.00168097 0.03885447 -0.9992442 0.001212477 0.04023706 -0.9991898 8.87654e-4 0.04030704 -0.9991871 7.6223e-4 0.04075366 -0.999169 6.77413e-4 0.04036152 -0.999185 7.05134e-4 0.04022461 -0.9991902 0.001007497 0.0403611 -0.999185 7.05033e-4 0.04036104 -0.9991847 9.8143e-4 0.04009944 -0.9991952 0.001108407 0.03772819 -0.9992869 0.001509964 0.04022371 -0.9991902 0.001081466 0.04010534 -0.9991951 8.49149e-4 0.04126226 -0.999146 -0.002227902 0.04345905 -0.9990403 -0.005462884 0.0323807 -0.9966611 0.0749548 0.04431414 -0.9977707 0.04989922 0.03469997 -0.9969618 0.0697357 0.04066205 -0.9991725 9.80903e-4 0.04594403 -0.9989441 -3.11583e-4 0.04012781 -0.999194 0.001063048 0.03814893 -0.999271 0.001479685 0.04256629 -0.9990936 3.11522e-4 0.0421108 -0.9991129 3.19502e-4 0.04267776 -0.9990889 2.67319e-4 0.04228889 -0.9991055 2.47712e-4 0.04258555 -0.9990929 1.43118e-4 0.04259383 -0.9990925 1.05658e-4 0.04248571 -0.9990971 3.91418e-4 0.04253417 -0.999095 1.16528e-4 0.04259324 -0.9990925 3.71393e-4 0.04234397 -0.999103 4.92871e-4 0.04014247 -0.9991936 8.42135e-4 0.04248476 -0.999097 4.63334e-4 0.04235053 -0.9991028 2.40148e-4 0.04672414 -0.9989079 -3.66225e-4 0.04345953 -0.999051 -0.002899289 0.04678499 -0.9978358 0.0462051 0.03683596 -0.997197 0.06512677 0.04220747 -0.9981778 0.043123 0.04730254 -0.9988803 -8.34475e-4 0.04917269 -0.9987896 -0.001242041 0.04463875 -0.9990032 -2.41176e-4 0.04471307 -0.9989998 -3.80214e-4 0.04442763 -0.9990127 -3.22076e-4 0.04475539 -0.9989979 -4.64873e-4 0.04462039 -0.999004 -1.81425e-4 0.04471272 -0.9989998 -4.57353e-4 0.04475498 -0.998998 -2.05703e-4 0.04449027 -0.9990099 -8.3764e-5 0.04237401 -0.9991018 2.35647e-4 0.04461938 -0.9990041 -1.1048e-4 0.04449617 -0.9990096 -3.3089e-4 0.04907459 -0.9978808 0.04272663 0.04556518 -0.9989553 -0.0035097 0.04532074 -0.9982784 0.03723323 0.04696166 -0.9988965 -7.9027e-4 0.04678386 -0.9989047 -9.1827e-4 0.04673904 -0.9989068 -9.09347e-4 0.04683232 -0.9989023 -0.001001477 0.04671853 -0.9989079 -7.32009e-4 0.04678392 -0.9989046 -9.93279e-4 0.04683154 -0.9989026 -7.52002e-4 0.04655712 -0.9989155 -6.30777e-4 0.04454147 -0.9990075 -3.38947e-4 0.04671734 -0.9989081 -6.63061e-4 0.04661571 -0.9989126 -8.78121e-4 0.05258417 -0.9986112 -0.003296017 0.0531032 -0.9985541 -0.008362174 0.04779237 -0.998849 -0.004089474 0.03885066 -0.9973922 0.06082439 0.05121046 -0.997902 0.0396133 0.04086452 -0.9975649 0.05652064 0.04855018 -0.9988201 -0.001207888 0.0487973 -0.9988077 -0.001430451 0.04874658 -0.9988102 -0.001420617 0.04885393 -0.9988049 -0.001512169 0.0487287 -0.9988113 -0.001250088 0.04879766 -0.9988076 -0.001502752 0.0506739 -0.9987137 -0.001742005 0.04885327 -0.9988052 -0.001271486 0.04872786 -0.9988114 -0.001183569 0.04882657 -0.9988062 -0.001445651 0.04656296 -0.998915 -8.68947e-4 0.04816627 -0.9988388 -0.001073539 0.04894971 -0.9988002 -0.001461088 0.05026429 -0.9987246 -0.004760861 0.05337774 -0.9979116 0.03637868 0.04294067 -0.9977073 0.0523101 0.04767131 -0.9983212 0.03289991 0.05017322 -0.9987394 -0.001518964 0.05085867 -0.9987043 -0.001795947 0.05103212 -0.9986954 -0.001827597 0.05066114 -0.9987141 -0.001875638 0.05094939 -0.9986994 -0.001969873 0.05250447 -0.9986179 -0.002374351 0.05070507 -0.9987118 -0.001974582 0.05079984 -0.9987074 -0.001763164 0.05080151 -0.9987068 -0.001992106 0.05067193 -0.9987139 -0.001701176 0.05106365 -0.9986938 -0.001779556 0.05015778 -0.9987396 -0.001831412 0.04998958 -0.9983271 0.02905374 0.05274945 -0.9986052 -0.002260267 0.052868 -0.9985986 -0.002417385 0.05241602 -0.9986228 -0.002234816 0.0526787 -0.9986085 -0.0024513 0.05268174 -0.9986089 -0.002228558 0.05268186 -0.9986084 -0.002451956 0.05257517 -0.9986146 -0.00221163 0.05257517 -0.9986147 -0.002148747 0.05247128 -0.9986198 -0.002290844 0.05203229 -0.9986433 -0.002048075 0.05298095 -0.9985812 -0.005340814 0.0466634 -0.9979083 0.04474073 0.05236488 -0.9986258 -0.002125799 0.05454438 -0.9985079 -0.002657413 0.05443513 -0.9985139 -0.002620935 0.05454033 -0.9985079 -0.00274533 0.05427926 -0.9985224 -0.00263983 0.05452597 -0.9985083 -0.002859592 0.05412143 -0.9985308 -0.002713263 0.05436182 -0.9985172 -0.002853453 0.05449485 -0.9985105 -0.002666592 0.05449581 -0.9985099 -0.002876341 0.05439418 -0.9985161 -0.002650976 0.05426096 -0.9985235 -0.002589285 0.05439329 -0.9985162 -0.002614557 0.05135047 -0.9986783 -0.002238869 0.05426496 -0.9985227 -0.002796888 0.05633777 -0.998394 -0.005981683 0.05454176 -0.9985076 -0.002813816 0.05234032 -0.9983126 0.02514779 0.04846417 -0.9979723 0.04126173 0.05917662 -0.9978544 0.02801656 0.056266 -0.998411 -0.003106892 0.05605572 -0.9984232 -0.003021776 0.05642312 -0.9984017 -0.003253877 0.0560342 -0.9984241 -0.003091573 0.05600905 -0.9984251 -0.003204643 0.05618727 -0.9984149 -0.003272414 0.05594503 -0.9984294 -0.003010332 0.05680227 -0.9983799 -0.00334376 0.05621397 -0.9984142 -0.003030478 0.05659782 -0.9983922 -0.003138244 0.05629807 -0.9984083 -0.003364503 0.05490332 -0.9982703 0.02102744 0.05806237 -0.998307 -0.003476142 0.05764514 -0.9983314 -0.003407657 0.05791211 -0.9983155 -0.003523051 0.05813342 -0.9983021 -0.003691673 0.05764007 -0.9983313 -0.003502726 0.05792522 -0.9983143 -0.003667354 0.05788838 -0.9983165 -0.003616273 0.05759382 -0.9983339 -0.003523707 0.0592668 -0.9982364 -0.00343424 0.0579515 -0.9983126 -0.00368613 0.08252418 -0.9965435 -0.009532094 0.05799162 -0.9983103 -0.003686726 0.06202757 -0.9980144 -0.01094692 0.05737638 -0.9981973 0.01760965 0.05957543 -0.9982165 -0.003825545 0.0597226 -0.9982075 -0.003865957 0.05938702 -0.9982277 -0.003855586 0.05963349 -0.9982126 -0.003949999 0.05943095 -0.9982244 -0.004004538 0.06100481 -0.9981282 -0.004309713 0.06394743 -0.9979425 -0.004652261 0.05983179 -0.9982011 -0.003852009 0.05963492 -0.9981989 -0.006531119 0.06431901 -0.9978696 -0.01092588 0.06277793 -0.9979774 -0.01001024 0.06125664 -0.9980667 -0.01051521 0.05368268 -0.9980584 0.031587 0.06119763 -0.9981169 -0.004201889 0.06102317 -0.9981278 -0.004141807 0.06080073 -0.9981414 -0.004141569 0.06280803 -0.9980012 -0.006988823 0.06119453 -0.9981164 -0.004345297 0.05984842 -0.9981053 0.01428306 0.05536097 -0.9980542 0.02868759 0.06592023 -0.9976541 0.01846373 0.06270414 -0.9980218 -0.00456506 0.06056362 -0.9981558 -0.004157841 0.06059455 -0.9981533 -0.004307627 0.06687593 -0.9977015 -0.01092922 0.06585925 -0.9977772 -0.01016271 0.06747841 -0.9975882 0.01626682 0.05697923 -0.9980376 0.02597177 0.06781315 -0.9976653 -0.008087515 0.0610677 -0.9980502 0.01290935 0.06231069 -0.9980459 -0.00466901 0.06573736 -0.9978106 -0.007263422 0.06436818 -0.997914 -0.004947662 0.06885361 -0.9975605 -0.01150548 0.06219726 -0.9979947 0.01174968 0.06666547 -0.9977604 -0.005473256 0.06393939 -0.9979416 -0.004948973 0.06726115 -0.9976792 -0.01059538 0.06384557 -0.9979078 0.01019328 0.06703186 -0.9977359 -0.005461752 0.07129263 -0.9973928 -0.01117932 0.07239168 -0.9973389 -0.008636951 0.07391655 -0.997263 -0.001709043 0.07004189 -0.9974887 -0.01050335 0.06555438 -0.9978125 0.008545219 0.06971442 -0.9975494 -0.005934536 0.07371217 -0.9972199 -0.01091694 0.06711083 -0.9977204 0.007080316 0.07452762 -0.9971811 -0.008697926 0.07638806 -0.9970738 -0.002990782 0.0694912 -0.9975649 -0.005942523 0.0756148 -0.9970822 -0.01045966 0.07269787 -0.9972988 -0.01049411 0.06894242 -0.9976056 0.005493402 0.07179218 -0.9973995 -0.006354331 0.07400757 -0.9972257 -0.007995843 0.07250833 -0.9973475 -0.006385684 0.0765419 -0.9970285 -0.008697926 0.07016396 -0.9975249 0.004608392 0.07777667 -0.99692 -0.01007539 0.07544749 -0.9970955 -0.01041221 0.07086467 -0.9974769 0.00427258 0.06967437 -0.9975368 0.008117973 0.07414537 -0.997224 -0.006850779 0.07538914 -0.9971103 -0.009359896 0.07538408 -0.997131 -0.006866931 0.07889181 -0.9968451 -0.008728444 0.08022791 -0.9967467 -0.007720291 0.07184082 -0.9974095 0.003631711 0.08026635 -0.9967253 -0.009802937 0.0781725 -0.9968879 -0.01017552 0.07300126 -0.9973281 0.002746701 0.07404011 -0.9972532 0.002075314 0.07682657 -0.9970183 -0.007238984 0.07820695 -0.9968938 -0.009300649 0.07820546 -0.9969097 -0.007418632 0.08026438 -0.9967436 -0.007738113 0.08254122 -0.9965562 -0.007926583 0.07522839 -0.9971655 0.001342773 0.07838487 -0.9968957 -0.00740385 0.08949112 -0.9959517 -0.008476316 0.07742691 -0.9969978 8.24016e-4 0.08073484 -0.9966864 -0.009907007 0.07620632 -0.9970918 6.71422e-4 0.07580959 -0.997122 8.85056e-4 0.0810973 -0.9966733 -0.008097767 0.08091944 -0.9966778 -0.009254574 0.08091682 -0.9966902 -0.007815361 0.08252322 -0.9965577 -0.007917046 0.07670462 -0.9970538 4.52009e-4 0.08279192 -0.9965372 -0.007709741 0.08374035 -0.9964506 -0.008598506 0.08078408 -0.9967007 -0.007856249 0.08482831 -0.9963519 -0.009340524 0.08511841 -0.996365 -0.003418147 0.08335548 -0.9964728 -0.009692966 0.08553194 -0.9963034 -0.008006155 0.07869875 -0.9968981 -8.5912e-4 0.07799339 -0.9969539 -3.81886e-4 0.08556783 -0.9962919 -0.00898081 0.08400547 -0.996429 -0.008512079 0.08402585 -0.9964199 -0.009342849 0.08402478 -0.9964297 -0.008240044 0.08881723 -0.9960018 -0.009590268 0.08482533 -0.9963622 -0.008204817 0.08180785 -0.9966449 -0.002548635 0.08199113 -0.9966295 -0.00266838 0.08046442 -0.9967559 -0.001812875 0.08719301 -0.9961513 -0.008944749 0.08400577 -0.9964312 -0.008246898 0.08713573 -0.9961605 -0.008472025 0.08596247 -0.9962561 -0.009183704 0.0871368 -0.9961526 -0.009342432 0.08856683 -0.9960569 -0.005157709 0.08190715 -0.9966368 -0.002542734 0.08258903 -0.99658 -0.002769291 0.08955568 -0.9959411 -0.009016215 0.08765691 -0.9961128 -0.008695662 0.08962535 -0.9959399 -0.008432447 0.08881849 -0.9960039 -0.009355068 0.08949202 -0.9959665 -0.006471395 0.08962678 -0.9959306 -0.009446084 0.09006088 -0.9959194 -0.005798518 0.08713287 -0.996184 -0.005035698 0.08289211 -0.9965543 -0.002932548 0.087493 -0.9961494 -0.005607128 0.08955705 -0.9959715 -0.004514157 0.08335351 -0.9965151 -0.003155946 0.08761727 -0.9961162 -0.008701443 0.09082263 -0.995844 -0.006801664 0.08629757 -0.9962583 -0.004727184 0.08450806 -0.9964129 -0.004450023 0.08955764 -0.9959607 -0.006468594 0.0854119 -0.9963354 -0.00454694 0.09002357 -0.9958986 -0.009048283 0.09019821 -0.9958783 -0.009519875 0.09019857 -0.9958783 -0.009520232 0.09083819 -0.9958207 -0.009459018 0.09083771 -0.9958279 -0.008680939 0.0911675 -0.9957982 -0.008628726 0.09116739 -0.9958127 -0.006768524 0.09082001 -0.9958515 -0.005628824 0.08770406 -0.996133 -0.005201339 0.08789509 -0.9961158 -0.005285561 0.09098631 -0.9958101 -0.009151041 0.08808642 -0.9960734 -0.00887072 0.09012687 -0.9958901 -0.008956193 0.08769118 -0.9961079 -0.00890702 0.08792096 -0.9960919 -0.008432388 0.09096944 -0.9958086 -0.009473741 0.09440714 -0.9954969 -0.00857222 0.09545236 -0.995392 -0.009152472 0.09821099 -0.9951297 -0.008468866 0.09634357 -0.9953195 -0.007556736 0.09571957 -0.9953788 -0.007683098 0.08954524 -0.9959662 -0.005759 0.0892803 -0.99599 -0.0057258 -0.1072458 -8.53417e-5 0.9942325 -0.1072669 3.21785e-5 0.9942303 -0.1072182 2.23396e-6 0.9942355 -0.1072292 0 0.9942344 -0.1072733 3.27304e-5 0.9942296 -0.107244 0 0.9942328 -0.1072425 0 0.9942329 -0.107204 -4.635e-5 0.9942371 -0.1072527 0 0.9942319 -0.1072733 5.79782e-5 0.9942296 -0.1071787 -4.6856e-5 0.9942398 -0.1072329 6.91491e-6 0.994234 -0.1072737 5.80515e-5 0.9942296 -0.1072447 0 0.9942327 -0.1072465 4.61769e-6 0.9942325 -0.1072733 1.70898e-4 0.9942296 -0.1072106 0 0.9942364 -0.1072244 0 0.9942349 -0.1072564 1.65972e-4 0.9942315 -0.1072384 2.398e-6 0.9942334 -0.1072199 -2.00694e-4 0.9942353 -0.107222 2.04345e-4 0.9942352 -0.1073026 5.31269e-4 0.9942263 -0.1072657 -2.32212e-4 0.9942304 -0.1072294 -1.72018e-4 0.9942343 -0.1072725 -1.29578e-4 0.9942297 -0.1072677 2.3334e-4 0.9942302 -0.1071884 1.21736e-4 0.9942388 -0.1072081 -2.58944e-4 0.9942367 -0.1072552 -4.2503e-5 0.9942315 -0.1072145 -2.00442e-4 0.994236 -0.1072462 -5.54811e-6 0.9942325 -0.1072315 -3.83466e-5 0.9942342 -0.1072636 1.93426e-5 0.9942307 -0.1072266 -9.6928e-5 0.9942346 -0.107396 1.78399e-4 0.9942164 -0.1072784 2.0641e-4 0.994229 -0.1072405 0 0.9942332 -0.1075611 4.33272e-4 0.9941985 -0.1072248 -2.92166e-5 0.9942348 -0.1075497 -2.80894e-4 0.9941997 -0.1072239 -1.31761e-4 0.9942349 -0.107272 3.34724e-4 0.9942297 -0.1073145 4.03263e-4 0.9942251 -0.107247 1.48332e-5 0.9942324 -0.106781 -0.001813232 0.9942809 -0.1072409 -4.13549e-5 0.9942331 -0.1072559 4.31995e-5 0.9942315 -0.1072347 4.15501e-6 0.9942337 -0.1072447 5.54813e-6 0.9942327 -0.1071519 1.7385e-4 0.9942427 -0.1072621 -1.93426e-5 0.9942309 -0.107329 -7.34699e-5 0.9942236 -0.106946 4.68673e-4 0.9942648 -0.1076161 -4.19024e-4 0.9941925 -0.1074003 -1.80875e-4 0.9942159 -0.1066876 6.17962e-4 0.9942924 -0.1077939 -4.94092e-4 0.9941732 -0.1071214 1.46587e-4 0.994246 -0.1073168 -3.98225e-4 0.9942248 -0.1077985 4.90463e-4 0.9941726 -0.1075497 2.80894e-4 0.9941997 -0.1071102 -1.46587e-4 0.9942472 -0.1076251 4.19021e-4 0.9941915 -0.1066779 -6.19192e-4 0.9942935 -0.1069468 -4.72273e-4 0.9942647 -0.1073342 7.34699e-5 0.994223 -0.1071445 -1.73849e-4 0.9942435 -0.1072335 -4.155e-6 0.9942339 -0.1075513 -4.28293e-4 0.9941995 -0.1067714 0.001767039 0.9942821 -0.107253 -1.24622e-4 0.9942318 -0.1072153 1.544e-4 0.9942358 -0.107226 1.0173e-4 0.9942347 -0.1072728 -3.34748e-4 0.9942296 -0.1072154 2.86572e-4 0.9942359 -0.1072592 -1.72563e-4 0.9942312 -0.107223 1.82137e-4 0.994235 -0.1072147 2.63517e-4 0.9942359 -0.1072967 -5.31271e-4 0.994227 0.1698135 1.04178e-4 0.9854762 0.1702189 3.41445e-5 0.9854063 0.1690667 0.001714348 0.9856032 0.1702455 -2.9619e-4 0.9854017 0.1694163 0.001033842 0.9855442 0.1705675 -0.001019656 0.9853456 0.1691971 0.001118957 0.9855816 0.1698076 -7.52591e-5 0.9854772 0.1695984 2.5781e-4 0.9855133 0.1695113 5.11232e-4 0.9855281 0.1702881 -7.09118e-4 0.9853941 0.169434 5.63276e-4 0.9855414 0.1699661 -1.64175e-4 0.98545 0.1698164 -3.315e-5 0.9854757 0.1694723 5.31329e-4 0.9855348 0.1701244 -3.12834e-4 0.9854226 0.1692646 7.79706e-4 0.9855704 0.1694849 6.36621e-4 0.9855326 0.172156 -0.003896594 0.9850621 0.1698579 -6.90409e-5 0.9854686 0.1697231 1.26486e-4 0.9854918 0.1686328 0.001555919 0.9856778 0.1692641 8.03424e-4 0.9855704 0.1700128 -1.05944e-4 0.9854419 0.1706057 -0.001004099 0.9853389 0.1697768 3.33206e-5 0.9854826 0.1702663 -5.8179e-4 0.985398 0.1698538 3.57579e-5 0.9854693 0.1699125 -6.84028e-5 0.9854592 0.1693569 6.81618e-4 0.9855546 0.1701154 -3.23013e-4 0.9854241 0.1700124 -1.79442e-4 0.9854419 0.1704056 -7.97234e-4 0.9853738 0.1697998 6.16476e-5 0.9854786 0.1694722 5.15477e-4 0.9855349 0.1701748 -4.64457e-4 0.9854138 0.9716519 -0.1668505 -0.1674914 0.9854665 0 -0.1698701 0.9854665 -3.05192e-5 -0.1698701 0.7780532 -0.6137385 -0.1340092 0.7723564 -0.6211019 -0.1330344 0.8659474 -0.4773789 -0.1491465 0.8632731 -0.4823294 -0.1487212 0.9310079 -0.3278029 -0.1605291 0.9315461 -0.3262838 -0.1605019 0.5398235 -0.8366227 -0.09302246 0.3959935 -0.915714 -0.06824213 0.3834455 -0.9211969 -0.06607443 0.6601586 -0.7424687 -0.1137142 0.6683655 -0.7348663 -0.1151481 0.5288345 -0.8438218 -0.09109938 -0.09534066 -0.9953093 0.01641911 0.08115047 -0.9966039 -0.01397776 -0.08163791 -0.9965628 0.01406913 0.06723362 -0.9976702 -0.01156669 0.2282547 -0.9728063 -0.03933948 0.2416787 -0.9694617 -0.04165822 -0.5383356 -0.8376111 0.09274911 -0.5490175 -0.8304389 0.09461081 -0.3960193 -0.915703 0.06824129 -0.2421377 -0.9693446 0.04171943 -0.4086549 -0.9099668 0.0704388 -0.2558122 -0.9657202 0.04410028 -0.8698894 -0.4699044 0.1499409 -0.8671737 -0.475032 0.1495137 -0.9332575 -0.3211573 0.1608991 -0.7834993 -0.6065467 0.1350187 -0.6670359 -0.7361018 0.1149672 -0.7780315 -0.6137455 0.1341023 -0.972427 0.1620864 0.1676714 -0.9854614 6.10382e-5 0.1698997 -0.9854614 -1.52595e-4 0.1698997 -0.9717115 -0.1664483 0.1675469 -0.9724363 -0.1619659 0.167734 -0.9323444 -0.3238439 0.1608079 -0.8672873 0.4748442 0.1494512 -0.7834585 0.6065998 0.1350169 -0.8699054 0.4698661 0.1499689 -0.9717212 0.1663279 0.1676096 -0.93238 0.323774 0.1607425 -0.9332392 0.3211815 0.1609569 -0.549019 0.8304413 0.09458053 -0.5381737 0.8377187 0.09271699 -0.408718 0.9099408 0.07040864 -0.6745621 0.729008 0.1162469 -0.7780348 0.6137481 0.1340724 -0.6670256 0.7361208 0.1149044 -0.09537094 0.9953065 0.01641905 -0.2413418 0.9695483 0.04159694 -0.08081459 0.996632 0.01391667 -0.2558126 0.9657215 0.04406982 -0.3958067 0.9157972 0.06821095 0.06723362 0.9976702 -0.01156669 0.0814864 0.996576 -0.01400834 0.2282549 0.9728075 -0.03930902 0.2419517 0.9693936 -0.04165792 0.3834975 0.9211754 -0.06607288 0.5288345 0.8438218 -0.09109938 0.3961958 0.9156267 -0.06824016 0.5399407 0.836554 -0.09296059 0.6601908 0.74244 -0.1137144 0.6669275 0.7362052 -0.1149338 0.7722815 0.6211823 -0.1330931 0.8633853 0.4821102 -0.1487806 0.7781558 0.6135946 -0.1340721 0.867103 0.4752098 -0.1493595 0.9310169 0.3278366 -0.1604086 0.9314235 0.3265888 -0.1605934 0.9716421 0.1668488 -0.1675508 0.9721917 0.1635528 -0.1676118 -0.6745162 -0.7290549 0.1162191 0.9722176 -0.1633689 -0.1676416 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + -0.9993399 0.0256862 -0.02568598 -0.237433 -1.50896e-7 -0.7071066 -0.7071069 -0.0200237 -0.03632561 -0.7066402 0.70664 -0.0060656 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_tail_collision.stl b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_tail_collision.stl new file mode 100644 index 0000000000000000000000000000000000000000..7b95f3cf0e41bb1565cb69e3ad0e6a6e308b21a3 GIT binary patch literal 20384 zcmbW8d0bE1_y2d4N+cO0AtW^SE~@uA$2DKmHOoAcnGBJk%$YJ1WvY}R2`PG?y*3(< zsGH2Qd#`zxG4fmQKHvNOuH*at>*ufcqrIN{wbt6h*^~BjrcDi=Ic9W&vB6U(H)u0y z%#_h%f?d7b{Jhne;GB&jD?)0BO!xXdim;GqTut`yH5UsM8Emt>Y?*titPvmQmSk|Rx zno*->{7K&-cAH=umR#OBSEU54iLw1bp6N!SpRc7KC8!nkkTEgTCDlk6({Sy>a>zlA zt9DHc;?i=+#^2}LxTrKf##(>adBRBi93h{ibx|uyGu9+0r7Tw^TkX<3&62?a^K&3> zow|J3NqB)8gFPaD(J*tgD2u$-9lLZ|FO7rNgmDywiSvICN*kVAol}Bp7=NF$h*yJ9 z?>~ew>dyZM@voJ!rt?UYV#_i%>ga6#+l%?BmMg;)nk%ZOB}O1&)cC)Mf9o~YbQ(2o zVb;sMQjUDJOuKZUxd*)Tuid>x(2+Q3|HfB!UcF8Yt`i4)EBLD8+}Ek5r_v$9%pR(kmPm|A z{5KIbKM87#ts-d2qC>H;cV|0w$c9Mu#``q*E2h=cV{bZUdOk?LO?cEfX=?V2U7MXz$Y_L1J*-=JT- zGfYrVZq42abK_*SwD+%GeJ-jdy^3s;(dnu-yXzui;aa)=YEjQfwK`@RFun?wt5IWM z(F*;XCx02nebjnIJ)tyXZp+j3nO9G#ckhJ>S{JpVG-Kv4M*8_8iBCyhC};`I8;uEj z;*dxw&2@7??(i@{OQ;^L3FpKElH9sOp}xlad4jer)rh&c95{YgYWH!)$j`+1D|YkT z)gONDqF#d#aPzCgU!GXx-=}>j+&X5%=LA(ZjP4#%HuF8bUdx{`o7w}EO5I`%Uk;dS z2x|3d(JbhfU4aihGbVts#~*@};A`em%-$a!AJ7*@i_5Y!+D|ZG7 zs|n+kQJzfNb>L5+R+OfCjJ2y6qWn{DpjzKh_W-bRICzdCqxuaw@X zQ9z*=&I~x07~8qmBdrys8QWROL%vdHntyYT`5FycFZGr&)3mnous=@e3w-AZ>N~Zf zG-FRYe>(o}8gAgs9Jq*HRXef7VCBfmJnS&SPCeg02XgW6S+yEt96b%Q%T|3^k57A1 zE4q5ou9klOeg3~SY#xMzz`EY}-89g(i2eHoWq+UYa|ia4uk(+W5gYGc*HJ44i77qBQjoiD^y#dreKPXuXp6 z%rfn^Tkqh^aC>K?|Mn_0Wky+vbt_vvwW2h}v0-VM#;E)31oet$)ZxEYeb?R@SAB;n z4=p2hopsdFwkwJmr8 z*9u1KEqAMP+DDDQhgQ8))?Yh~%z@J;h3a$0FpkszMYvwn64Yw-#2n}|CR1J9^)&Vp zBe5=7-!k!>mY`Nkr{%!5+iB{v>bsCokyzHba?4@)T7p_F$C2h+H(os!u^5TQxz%w6 z#26rH%+;aq|ET|tyMN=LIb_WHzX;>bg_h9BX-57hax0AE3$|L!)30imW|3-#>KxXu zd9Bt|JE^oa89R%08@BC}K1(jH#;--L0tGsdLVsJ1WG@N#UIfCsoY zFqYgwt6neGs&{b*5rMy}7p_x3;NN}Kuj&MM<61Om(qO~J#HEH>xYDOq9Utt2n*Ggr z)xckg2a^l+K^1(&MJ18`4{4!s@tHqSvWUOucV{6&QB)EiE?d2%b5=vCx7Y~N^Bh@`N#=XIABsR<` z;eWJqlxa!Uq6F|b_*3n?r=t4UF#-OmXT}SAjz(f45*KHe@MfJIWm-bpoYsV^a3m(8 zR~?a{^-?S9A!8xMzstV;y%g^)9>UT(9o)y(gCQngr4AL+;c1!!{2cK~@^DXw=Y{t0 z(exWeUbAgC+2f*z;_{EDFuQ&d)_B=N%b{PT3H?q&#p`up*8XpjS$sNV)v<>oZ;ZrO z`>t~Dcuys&p_ZUlT8(XsyU4Chy_EU~JTw~At9uns!I^XRu(=)M{*q=pw&&_EMfEcnDe-r8{6>Xn=ho6Z-;VGcJXSYV%8^4jmm~;O=-xxcFIZ zH{_7vU}P-V`;So5hDE9aX2!$bX^bEGVTvs{6NwAKCDPf>jzCK&F++#FB+-=nO>T=s z7bLQgDC(}&P_R8L3=S}Uz$b~)jCoxS72}_mNRKQXftFBWu~j;_ZLJ5@;*9(Aov2Yg zq(pLT?+8?#(sVb;n0~h4PiM{%7bcF9XF)XF)0=b04RuuW_;|Q{@rzpT&H+Q+{5UAL z#DcF^jq{c7{!u*T+;KRVt;mMCh7T{AF0M$Q`yv981+;BYE0ZoD0K1P5k$MwyU^aJbcfJ4`Vcye$u#&H7)Pb8ioK})8z*a1mR2lAXt7t6kI z|JKAIb2wFMif1GXxvY9LSgn3t77cxTEcmAaS9MiTG@L3a&u1ODiEE!m zNOZR?<%^D|N|gskgNMra2d9k&N^6N4NO;#Q<(rPBN`<)FTAyIWpI%t0(V#SA4oDc# zt8(a-U+o>>l#}LuuM2Y+eSA7k=pQve*YpZJdQDC-D)fMAT8(IhEK)lXKP5AGeU0bKxLg)=v?Y49*HIp+u2)Ce&S;r)EbOH3Ekn=57155+1!g6k1{) zr^5KrxoUt(Q{sLlzroO^lr!c9w@!Dgp}_ry=e< zI|%S5OCA2%_Y|cW8`gvK@a^evE^o3zt*)2sg$i>s)uR1Z{k6p40~tKnuoH472P@R- z?WP@Y?PsQ1;aIx>En%9S&Tn?ihv#@=M6Ci>Z-Kz06-TZ6 z83TW^@qqgL?m~r@EIc{`Y|Z1<2On(pv?j)Wo5*?Cg>cvuJ6oak4!79=w#Uz_HKuI) zMPvMO&YPGlgjsiIYcweF`s^B5V}D7_?{PQ)_k;Zn{H*f^7&v^ULQ7_SkASS*h3eWD z{1=S{?N0IzzPq62h+vHdCB{!#221wcR6~a4qQ)HSG+wKD9CY6@T|-c-h3{v8+mL7K znU>#>aM><+W@awzx-nj%C6uV0wHUe_f1vh`$w%Vcy|a9>RxzK$Az|HP z)w0M)4DSK_!DkEc`cpp*L9N2W7r?uEZ`HUK=a2|(c!X!}wiW5AJv0QhDh-_p)gS** z-<$*_R`)h=+w*qfe$Ot-grIpayV4i6>ECGq)QZyht-ZIG&x{%a)z=@GNw`RfY2 zyBHqO#X204R#)H-7UcudVK%t9Tk)(1=kSzMY>MISPmULDd@sqX6V}4kK^6G$8x0LM zUUT4R3v0f<#rjj70$0M_Y3988$kQ2&oq7|_H@=xK&gpFAc2Cwq!X+E73m&ezheShA zWpkcZV52_58T_v;R@|qW@l4+*e>Bg$won{7u~VWY3UJ z-xi3EU(Dpso4JHOG8CUk4`eJ%i1{{u9VvH%(a;Ys?FHow>$Wv>r;f8OR79LIuu^y+3>9kJBFSdDjk`MTth;(73MO&rvU(u@^Mi{gD3 zO%o9Thcp_Lu*UDa4!`q{nr=jmk(*2Orfo-;)jWt46<%=vC}d z-lSu1(fWq9=Bq}(SM>XcYoEb8xm&|=;?uSpGVP<(_wD6vpAPlaKmy ztWaLvlr>glOlXPxC2{=OoDpIndn414vn*^e?Al_^gQoZL*AiDnJm3BMU~%9)Qz${l zAf*`_lzo(+jP4;~(rlGBBj&@lDW-g6=lpEyJ$^}9q+x8htv)hkM6|E4@V`ykOC9ltAevidyKZ1%-BAf zM~#{-nwvz(%kc~;eCJp7^~6ZE^TT~`I@X-0_^ng5M7^TT{KU^t@w$0{Os%M%mMHDD zoF@#QBT`OJk!^-7fXe~4e0Tgh%}Avq7;oCoujYw+W{EeSS8E75g0-VIbnX$}dg~+J zeBJ_ue#7ZHLHj*FpSM7)?YB;PKkyO1jBB;O7U!uyHs%`Aan-jd|B_m%XMrK%WF~a{ zr$n6t9dV{!Q?Nkv8M#S{J#>%LlHgOBkhb=l`n1SCgVw}YgkLj$WVcTFS;t3oop~Pq zjJJYDSFT7`{Iel@yCuXlxh@S|e+J5*w1PaFLfo+^t()N-hHo5>1F35XbIJz+KkQm>CAiW(RXyX(w__a3>-q@lFD0_T3)M3wK4SGVowDsgF07VaAbUV1 zIi_(gSS7o_ozGTsFUMSHKHCM}xmS{L1u&pcU4SQ$H~-cWOMm7<=f7Owz%eTg&DhN; zg=$Yc9sK!Nr=WPm>2Ypx833< zrd(*HIHG!nmkZoS^{B^rkX*|J8aJ#Ym!h|Fu?yJ5SRr9KryCS^>?qRO)>dc* z6Mw%4^3FHlTe-bL)u|Pw@y*2M`l5k;q}>LzYLW#BC@}YGTCwSAP`eUg=Xl?uwnDUYSPG^#x*VPPEh-u4xEr)dLCF zMo!SShf$*no->5udC6xyFX`Pm4i?u+D%w|02?>+35HrySWr9!2Cv{bpFOef z;=WdK!c&|gBxp%aP#iof-OfMt>@U%p7^}A54y^GEARf;EqI)F3wb5I6#0ER5<&*^2 zwLgLKB`}tv4ZCndupsGjlBfDI)>+0M-Qg* zov7iB8s|3JN#8;e;Q8{6Tz|8gv~)`X94cJKr%JA<5s1Vs^HRy?NGhi#zUY;7AcBuG z^_FN&cxH*`CB=ANvJ}rtzGA)0S8U{FH>yd2)8irQ#0Fl|#8$ezE*?flFXcg=E~rs_ z*iN2<#0w;h8dXp|QFfImttG0XS3hc%N_A3Fxv|~>X&d;9pH-z#VjuWt1oM7}&+4Du z-3Qk{2J#@+Pq5D-!RJIEn=Igj!J=*Kl}V5{0KY1xHh*h3LCsP8WX6>6yMC zooxC_(jb=apzDH^=O5z{vZeC&jzxbBFVdHTNpT zkGI0boKXJCsS)<85eas(I}*`I(7PK-YwvNMV&u>3mGaZ+sZ!$ZtpFu!`PV6xC3@CJ zPYv;I8zY~9MA9KGLG>uj*e=xQ(yWwsIFqXJeUjJ;qk4w(8p2u9#*u}@h=!%yQD_P3 zA*C5Bmt+UO<6Po{bIIm?QIJq~9nUymE#1kE0uR4MymWkXX+OqS9^(t1RvB|O>98GS z;9PP930fDmqBLVwG4fTlOZmo>RH-;?8$9l~nU_D^U5Z4#fe!2V>Ue9(K5-kgbJ)vw z)$&1&YDhfCv%ZnP5RcHSt-g!+u&K>8G~T{q9D0nSHG0((=Uu1TiTrgVNixo&op2VF zd-s>3s_uqX&inZ9nSQ8o6$t~zk%q)`kKNGn=r*2{)JJ1QX?(+yUO(|95@hboRl~22 zZnf-W5}bVTLG|esXE3gPX5-rDeA(J(5E2dEew0chwFI?lgKMp2&&^@Pm>cNT`AG}- zlP6xndXlf`Q?3AjHHEvD738J(9Xzne3eI)9D(&_?2RYyBLsiB2&T>OqPu^Vi!LtmV zpe2)}%i!~{1=NVHDDR(;4?j(sgU>$}_#K?F){@`q<0K}HZzCen_u6kis5gei8J0Sy z!-4Dv>bptj3`6k-^G?V|)u+`F+;f^wl=*rmf05qTT`a~m?u3x&RU2$eNkO^Au*s2&cUvG=kwP&jmze%R#~BZ zQ8VMb`|cuFM}&AOkEXTM5PqLFL(iAl>ZtLHH8f*w8l2~?_3p~vx2=@=*N#B!Z#k;2 zAU30_ArqWme^pa{U7;mIYYXV^cTvr+7H_zYd${3v-X6Bnc;4<&be}&f)hS-M+a9|s zAGZJA44Uk+kYC=+hSjMK(C9Ohzp?^|igN8GUi>RG5Auan>{RyFVy)QZlJ)LX{<7N1oQts95i>(y1Ab;3EtN25UrS`*%wysFF-zIcm4H++Qk_)D;Rr3+MawUVjt z*LG&Wpc##U_cOtsII-q!!_6k`gk4x;L9J*^TB6~lld8>0ooME-op;++NQYQ_2VjQp z0O%ad*oiUS)Mi^1@h-EOfLVD^|FH`Mtg(`*hguD@nE~oly^rX7PABMWY1}~s;$CDK z?nS5`p2IzjRHq%(iIzQm1fBKk;yU`qLB@Y1Y%*x)_5;I`4dqw*2(K`mpmk9zs?FH3 zqwfsYruv93+jN3@@&k8UwQ;v~5O-U&CY%!cFUtsg=p$w})rlUsF8P7`!GOk+bl2(_ zjQUm^if%lYD9zaSPpJW|oBN7^cf2)TQ7cO0$%NDUfR)1n#PUgQnqESChBmujcKmtj z-XLEQa>!dm25p7q70YwS!(j&cm8pRz!Z(0%*RIAB;iU7G)SBb{#gkxnjaRf@s)w&E zo;NcTnEQ%eO#2XR1wi~EYZpjnJEIRd^r>p;T`uYYMl zmn)7^he5xImmy6BwW5)0+kBBBPTw!fS1fk(7Br(Y)AYNGYwCb6`db%!3g0kWLF=u6 z->7#_nthn+Uz#{zFo>$?=K$d-87L? zg065FOWn0VI;iU?W|=e)Q~Ml&ODF0>dSHn}+lJ;4R{$Z4r6yfEiP=#OniizAHjc^J z`O>zk9mR~B4jQkhCzQsQ92c(1bCTPL-WPtr`GkeQD^%bzs~_OzI1l1hm*XodFAea& z6$i!TYrs%=foq1R0f(hS0TaZma=Ad&;g|uOT%5siqPa}7j_*r8e34FE(F;?{=9=uj z!W&oT1asc0iq4;Uh%X?{D{`?(Yq5Wnqo7tNz4853dNmkt^+eJVyKH;Q4R*8^r(GIo z2pSWm@jUU-c=>V7Kv6R63(yE@ezY1hYj`PxYzN7`*1Ico9Yxnyt8dSP2Y-H4XZ%nD z@GiCDM0siVULt*$nV=f9UaeP`JNK2_6!jK&7Mf{#38i%t4nf_z4zO?WcWjS5s{!(o zgo)xo<^4cQCb%7kQI3saT|+aOwiCV@3T?HhJqD=k+!Sh@wUD)uzfSHe*LLYF#vHDu z$rZJtG_K*swO8gRJ%_0Fk7OD-je}-^v9*6TR2sZbm7=S)*X%#&SfMnoENg$1*ZBzfip4Ye@$>=8 ztEvZJ#L!wWZqpZudNQD5Jk07<6}Dv=XSi#%66G7MZpd>N1Zp&>6{Q)Q8gW>DKHNev zL9eJfC1@6KM?a;r{QIgkl4aje z{GrjH_5MQK-z|BzXs!(Qk(Dby7lY%w`|8*2`2qLK9fZ<7w&1YuokVGDk3eTR!u6cI zrjj;S)I)9L(>vSC%6Lbm&yU|UZBF&H8r=?UmWIx*tCU~WS<@4#S5yz@#9{f8?!CS8 z+vZLRt&0-c$o~qfEuY*H1T%-vR%l;xs&f%4`ny0X-eA(X5=ZT@wNi^ZEtHv@;S7EvoAmH1SYOPy1;! z8jEO{RJw()Y1&H~QY!^6OsfHxIvU^UuaTz)SWov*de8Gys1@~)YBP4H{X6~JhK-e! z9_=(5v|ep5*<<>LzM+|i()_lcrUhvnT8)WaJ@k{8Stuu01!`K5W|y`NV;QrH0_qHE ztkiGUPN7!R6Y3$J?;gJGf9{xv;wAYhG>gWiB$ zO4M<^Li0|os2*br`?cV;2YM^>2l;9=C_!t&m&?xmc&oeK%Go3zO?JQIonYk4Kz>8{ zq^Ft2GcxDC93KZO`Ds21wW4j~9J&+Eg=VV$8ye!*d1d`@p1rx5(zULlX%FiAp%pps zN3|vp{=Nc6zVCK051XS?I=MxY8n&1s`KehHz=2X^cT9CHdSf2#w^eR)0@b8ZAMc*&j z#y6Y#C{@gL3N4`?YP~wTKZe`9@lcL`ZK-Jwda_MDWUOxdUS6(Pr%WvNR;U%t57omL zzh{$p_vQXdyosCUgr1(`Q*ZH2>eeJaW~`6WH_%(5R|&MRxmvFszklTHxmO?p4-+-xzN&Ap?Rm#&YXT3_PDly>GzFqaqO?;@=|jj#lg>8 zp(T`PT@zo6jA#zs9$6ysG19MxCj_pA; zhQG;&;%804%)wly_aeAA@J^H-e)SeZZ|RikHW^U7*gc(6>Tm>J zCf!l<8Wm-%#XG1~oAD0HBBT|Ki7{KpM9KWEw-}G}6|IYEyl8O*%GY_K?&_mQjXs+a zrL=N7;ZcAZr;?$o?H%=Rk82s>bCYoI0N+%|3|S~qGX0dm)qL*pu~g+$&dn1)HYY!qgVax6Qo9VI?-C_ z6l$f>Tbv9%vj0(+t_?sUx<{gPwS`W&?$>J2dbN?i8k{I)W3H||(rSd0dMS->AX_F# zHy(M5zi|el5z<^y5AnrT<3!1|*ju!Dpv^9&Y0KhEj;4uHl!;EF~y%X=D)O>RoUh8w!@pkD3ldNQLwz{aY(H9JR#wSCnd`Xp`T*O@6mAk--$(~|z zkf%aR`ZY?1c6oU!tC4M>H8D2rz5BN~~?uzNVWGD#CQD1F6Ww`HO1b5M!<`yKR@RRBW!a!N_SzrJ+Y)$Ao`W>%u0KG+b5xhU%xl&i;q{UOIbhcfaZr1v?hGNyM2n%u!gmC@aRdIMoaTXJ;XIb|DmFC;TyTm On + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-04T11:52:29 + 2023-07-04T11:52:29 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.647059 0.619608 0.584314 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.498039 0.498039 0.498039 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.65098 0.619608 0.584314 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + + + + + + + -0.001516163 0.001999974 -0.002456486 0.001369297 0 -0.002541303 0.001369297 0.001999974 -0.002541303 -0.001516163 0 -0.002456486 -0.00288546 0.001999974 8.48154e-5 -0.001516163 0 -0.002456486 -0.001516163 0.001999974 -0.002456486 -0.00288546 0 8.48154e-5 -0.001369297 0.001999974 0.002541303 -0.00288546 0 8.48154e-5 -0.00288546 0.001999974 8.48154e-5 -0.001369297 0 0.002541303 0.001516163 0.001999974 0.002456486 -0.001369297 0 0.002541303 -0.001369297 0.001999974 0.002541303 0.001516163 0 0.002456486 0.00288546 0.001999974 -8.48154e-5 0.001516163 0 0.002456486 0.001516163 0.001999974 0.002456486 0.00288546 0 -8.48154e-5 0.001369297 0.001999974 -0.002541303 0.00288546 0 -8.48154e-5 0.00288546 0.001999974 -8.48154e-5 0.001369297 0 -0.002541303 -9.96591e-4 0.001999974 -8.22544e-5 -9.96534e-4 0.001999974 8.29121e-5 -0.00288546 0.001999974 8.48154e-5 9.694e-4 0.001999974 -2.45485e-4 0.00288546 0.001999974 -8.48154e-5 9.96584e-4 0.001999974 -8.25793e-5 -0.001369297 0.001999974 0.002541303 -6.1399e-4 0.001999974 7.8928e-4 -4.75747e-4 0.001999974 8.79555e-4 6.14213e-4 0.001999974 -7.89141e-4 4.75947e-4 0.001999974 -8.79474e-4 0.001369297 0.001999974 -0.002541303 0.001516163 0.001999974 0.002456486 0 0.001999974 0.000999987 -3.24786e-4 0.001999974 -9.45786e-4 -4.76066e-4 0.001999974 -8.79406e-4 -0.001516163 0.001999974 -0.002456486 -3.24545e-4 0.001999974 9.45851e-4 -1.6464e-4 0.001999974 9.86353e-4 -8.36967e-4 0.001999974 5.47201e-4 -7.35502e-4 0.001999974 6.7748e-4 -9.15613e-4 0.001999974 4.01991e-4 -9.69292e-4 0.001999974 2.45808e-4 -9.15874e-4 0.001999974 -4.01432e-4 -9.69459e-4 0.001999974 -2.45185e-4 -8.37295e-4 0.001999974 -5.46732e-4 -6.1435e-4 0.001999974 -7.89027e-4 -7.35865e-4 0.001999974 -6.77117e-4 0 0.001999974 -0.000999987 -1.6464e-4 0.001999974 -9.86353e-4 3.24699e-4 0.001999974 -9.45817e-4 1.64595e-4 0.001999974 -9.86361e-4 8.37167e-4 0.001999974 -5.46948e-4 7.35724e-4 0.001999974 -6.77282e-4 9.15773e-4 0.001999974 -4.01695e-4 9.96584e-4 0.001999974 8.25793e-5 9.15773e-4 0.001999974 4.01695e-4 9.694e-4 0.001999974 2.45485e-4 8.37167e-4 0.001999974 5.46948e-4 6.14213e-4 0.001999974 7.89141e-4 7.35724e-4 0.001999974 6.77282e-4 3.24699e-4 0.001999974 9.45817e-4 4.75947e-4 0.001999974 8.79474e-4 1.64595e-4 0.001999974 9.86361e-4 -6.1435e-4 0 7.89027e-4 -0.001369297 0 0.002541303 -4.76066e-4 0 8.79406e-4 0 0 0.000999987 0.001516163 0 0.002456486 -9.96591e-4 0 8.22544e-5 -9.96534e-4 0 -8.29121e-5 -0.00288546 0 8.48154e-5 0.00288546 0 -8.48154e-5 9.694e-4 0 -2.45485e-4 9.96584e-4 0 -8.25793e-5 -3.24545e-4 0 -9.45851e-4 -0.001516163 0 -0.002456486 -4.75747e-4 0 -8.79555e-4 0.001369297 0 -0.002541303 4.75947e-4 0 -8.79474e-4 6.14213e-4 0 -7.89141e-4 -3.24786e-4 0 9.45786e-4 -1.6464e-4 0 9.86353e-4 -7.35865e-4 0 6.77117e-4 -8.37295e-4 0 5.46732e-4 -9.15874e-4 0 4.01432e-4 -9.69459e-4 0 2.45185e-4 -9.69292e-4 0 -2.45808e-4 -9.15613e-4 0 -4.01991e-4 -8.36967e-4 0 -5.47201e-4 -6.1399e-4 0 -7.8928e-4 -7.35502e-4 0 -6.7748e-4 -1.6464e-4 0 -9.86353e-4 0 0 -0.000999987 1.64595e-4 0 -9.86361e-4 3.24699e-4 0 -9.45817e-4 7.35724e-4 0 -6.77282e-4 8.37167e-4 0 -5.46948e-4 9.15773e-4 0 -4.01695e-4 9.96584e-4 0 8.25793e-5 9.694e-4 0 2.45485e-4 9.15773e-4 0 4.01695e-4 8.37167e-4 0 5.46948e-4 6.14213e-4 0 7.89141e-4 7.35724e-4 0 6.77282e-4 3.24699e-4 0 9.45817e-4 4.75947e-4 0 8.79474e-4 1.64595e-4 0 9.86361e-4 1.64595e-4 0.001999974 -9.86361e-4 0 0 -0.000999987 0 0.001999974 -0.000999987 6.14213e-4 0.001999974 -7.89141e-4 4.75947e-4 0 -8.79474e-4 4.75947e-4 0.001999974 -8.79474e-4 3.24699e-4 0.001999974 -9.45817e-4 3.24699e-4 0 -9.45817e-4 1.64595e-4 0 -9.86361e-4 8.37167e-4 0 -5.46948e-4 8.37167e-4 0.001999974 -5.46948e-4 9.15773e-4 0.001999974 -4.01695e-4 6.14213e-4 0 -7.89141e-4 7.35724e-4 0.001999974 -6.77282e-4 7.35724e-4 0 -6.77282e-4 9.96584e-4 0.001999974 -8.25793e-5 9.96584e-4 0.001999974 8.25793e-5 9.96584e-4 0 -8.25793e-5 9.694e-4 0.001999974 -2.45485e-4 9.694e-4 0 -2.45485e-4 9.15773e-4 0 -4.01695e-4 8.37167e-4 0.001999974 5.46948e-4 9.15773e-4 0 4.01695e-4 9.15773e-4 0.001999974 4.01695e-4 9.694e-4 0 2.45485e-4 9.96584e-4 0 8.25793e-5 9.694e-4 0.001999974 2.45485e-4 6.14213e-4 0 7.89141e-4 6.14213e-4 0.001999974 7.89141e-4 4.75947e-4 0.001999974 8.79474e-4 8.37167e-4 0 5.46948e-4 7.35724e-4 0.001999974 6.77282e-4 7.35724e-4 0 6.77282e-4 1.64595e-4 0.001999974 9.86361e-4 0 0.001999974 0.000999987 1.64595e-4 0 9.86361e-4 3.24699e-4 0.001999974 9.45817e-4 3.24699e-4 0 9.45817e-4 4.75947e-4 0 8.79474e-4 -4.75747e-4 0.001999974 8.79555e-4 -3.24786e-4 0 9.45786e-4 -3.24545e-4 0.001999974 9.45851e-4 -1.6464e-4 0 9.86353e-4 0 0 0.000999987 -1.6464e-4 0.001999974 9.86353e-4 -7.35865e-4 0 6.77117e-4 -7.35502e-4 0.001999974 6.7748e-4 -8.36967e-4 0.001999974 5.47201e-4 -4.76066e-4 0 8.79406e-4 -6.1399e-4 0.001999974 7.8928e-4 -6.1435e-4 0 7.89027e-4 -9.69292e-4 0.001999974 2.45808e-4 -9.96534e-4 0.001999974 8.29121e-5 -9.69459e-4 0 2.45185e-4 -9.15613e-4 0.001999974 4.01991e-4 -9.15874e-4 0 4.01432e-4 -8.37295e-4 0 5.46732e-4 -9.96591e-4 0.001999974 -8.22544e-5 -9.69459e-4 0.001999974 -2.45185e-4 -9.96534e-4 0 -8.29121e-5 -9.96591e-4 0 8.22544e-5 -9.69292e-4 0 -2.45808e-4 -9.15874e-4 0.001999974 -4.01432e-4 -8.37295e-4 0.001999974 -5.46732e-4 -9.15613e-4 0 -4.01991e-4 -7.35865e-4 0.001999974 -6.77117e-4 -8.36967e-4 0 -5.47201e-4 -7.35502e-4 0 -6.7748e-4 -6.1435e-4 0.001999974 -7.89027e-4 -4.76066e-4 0.001999974 -8.79406e-4 -6.1399e-4 0 -7.8928e-4 -3.24786e-4 0.001999974 -9.45786e-4 -4.75747e-4 0 -8.79555e-4 -3.24545e-4 0 -9.45851e-4 -1.6464e-4 0.001999974 -9.86353e-4 -1.6464e-4 0 -9.86353e-4 -0.001513063 0.002999961 -0.002275943 -0.001513063 0 -0.002275943 0.001372396 0 -0.002360761 0.001372396 0.002999961 -0.002360761 0.001372396 0.002999961 -0.002360761 0.001372396 0 -0.002360761 0.002888619 0 9.57383e-5 0.002888619 0.002999961 9.57386e-5 0.002888619 0.002999961 9.57386e-5 0.002888619 0 9.57383e-5 0.001519322 0 0.002637028 0.001519322 0.002999961 0.002637028 0.001519322 0.002999961 0.002637028 0.001519322 0 0.002637028 -0.001366138 0 0.002721846 -0.001366138 0.002999961 0.002721846 -0.001366138 0.002999961 0.002721846 -0.001366138 0 0.002721846 -0.002882361 0 2.65372e-4 -0.002882361 0.002999961 2.65373e-4 -0.002882361 0.002999961 2.65373e-4 -0.002882361 0 2.65372e-4 -0.001513063 0 -0.002275943 -0.001513063 0.002999961 -0.002275943 -0.001513063 0 -0.002275943 -0.004611909 0 -0.001930892 -0.004231274 0 -0.002663552 0.004138171 0 -0.002806365 0.004543602 0 -0.002086937 0.001372396 0 -0.002360761 -0.003735184 0 -0.003323614 -0.002882361 0 2.65372e-4 -0.00313735 0 -0.003892958 -0.004989027 0 -3.28781e-4 -0.004866838 0 -0.001145482 -0.00497508 0 4.96934e-4 -0.004825472 0 0.001309096 -0.001703798 0 -0.004700601 -0.002453982 0 -0.004356205 -0.004544138 0 0.002085626 -9.07922e-4 0 -0.004916846 7.38009e-4 0 -0.004945218 0.001541852 0 -0.004756331 -0.004138767 0 0.002805233 0.00361979 0 -0.003449201 -0.00154227 0 0.004756152 -0.002304255 0 0.004437267 -0.001366138 0 0.002721846 0.004825174 0 -0.001310646 0.002888619 0 9.57383e-5 0.001519322 0 0.002637028 8.60456e-5 0 0.00499922 0.004989266 0 3.27084e-4 0.004867374 0 0.001143813 0.003138482 0 0.003892242 0.002455055 0 0.004355728 0.004612743 0 0.001929342 0.004232227 0 0.002662241 0.003736317 0 0.003322541 0.00497508 0 -4.98588e-4 0.001704633 0 0.004700422 -7.38209e-4 0 0.004945158 0.003002703 0 -0.003997921 0.002303719 0 -0.004437625 -0.003003358 0 0.003997385 -0.003620505 0 0.003448367 -8.60158e-5 0 -0.00499922 9.07724e-4 0 0.004916846 -0.001513063 0.002999961 -0.002275943 -0.004232823 0.002999961 -0.002661228 -0.004613161 0.002999961 -0.001928031 0.004138171 0.002999961 -0.002806365 0.00361979 0.002999961 -0.003449201 0.001372396 0.002999961 -0.002360761 -0.003736972 0.002999961 -0.003321766 -0.003139138 0.002999961 -0.003891706 -0.004867613 0.002999961 -0.001142323 -0.004989266 0.002999961 -3.25488e-4 -0.002882361 0.002999961 2.65373e-4 -0.004974782 0.002999961 5.00217e-4 -0.004824578 0.002999961 0.001312196 -0.002455592 0.002999961 -0.00435543 -0.004542768 0.002999961 0.002088367 -0.00170499 0.002999961 -0.004700243 -8.60156e-5 0.002999961 -0.00499922 7.38009e-4 0.002999961 -0.004945218 -0.004137098 0.002999961 0.002807557 0.003002703 0.002999961 -0.003997921 -0.003618657 0.002999961 0.003450155 -0.00300157 0.002999961 0.003998577 -0.001366138 0.002999961 0.002721846 0.002888619 0.002999961 9.57386e-5 0.004825174 0.002999961 -0.001310646 0.004543602 0.002999961 -0.002086937 -7.38209e-4 0.002999961 0.004945158 8.60457e-5 0.002999961 0.00499922 0.004867374 0.002999961 0.001143813 0.004989266 0.002999961 3.27084e-4 0.002455055 0.002999961 0.004355728 0.001519322 0.002999961 0.002637028 0.001704633 0.002999961 0.004700422 0.004612743 0.002999961 0.001929342 0.004232227 0.002999961 0.002662241 0.003138482 0.002999961 0.003892242 0.003736317 0.002999961 0.003322541 0.00497508 0.002999961 -4.98587e-4 9.07724e-4 0.002999961 0.004916846 -0.001541078 0.002999961 0.00475645 0.002303719 0.002999961 -0.004437625 0.001541852 0.002999961 -0.004756331 -9.07922e-4 0.002999961 -0.004916846 -0.002302646 0.002999961 0.004438042 0.00497508 0 -4.98588e-4 0.00497508 0.002999961 -4.98587e-4 0.004989266 0.002999961 3.27084e-4 -7.38209e-4 0.002999961 0.004945158 8.60456e-5 0 0.00499922 8.60457e-5 0.002999961 0.00499922 0.004825174 0 -0.001310646 0.004825174 0.002999961 -0.001310646 0.004543602 0.002999961 -0.002086937 0.004543602 0 -0.002086937 0.004138171 0 -0.002806365 0.004138171 0.002999961 -0.002806365 0.00361979 0 -0.003449201 0.00361979 0.002999961 -0.003449201 0.003002703 0.002999961 -0.003997921 0.003002703 0 -0.003997921 0.002303719 0 -0.004437625 0.002303719 0.002999961 -0.004437625 0.001541852 0 -0.004756331 0.001541852 0.002999961 -0.004756331 7.38009e-4 0.002999961 -0.004945218 7.38009e-4 0 -0.004945218 -8.60158e-5 0 -0.00499922 -8.60156e-5 0.002999961 -0.00499922 0.004989266 0 3.27084e-4 0.004867374 0.002999961 0.001143813 0.004867374 0 0.001143813 0.004612743 0.002999961 0.001929342 0.004612743 0 0.001929342 0.004232227 0 0.002662241 0.004232227 0.002999961 0.002662241 0.003736317 0.002999961 0.003322541 0.003736317 0 0.003322541 0.003138482 0.002999961 0.003892242 0.003138482 0 0.003892242 0.002455055 0 0.004355728 0.002455055 0.002999961 0.004355728 0.001704633 0.002999961 0.004700422 0.001704633 0 0.004700422 9.07724e-4 0.002999961 0.004916846 9.07724e-4 0 0.004916846 -0.00300157 0.002999961 0.003998577 -0.002304255 0 0.004437267 -0.002302646 0.002999961 0.004438042 -0.001541078 0.002999961 0.00475645 -0.00154227 0 0.004756152 -7.38209e-4 0 0.004945158 -0.004138767 0 0.002805233 -0.004137098 0.002999961 0.002807557 -0.004542768 0.002999961 0.002088367 -0.003003358 0 0.003997385 -0.003618657 0.002999961 0.003450155 -0.003620505 0 0.003448367 -0.004974782 0.002999961 5.00217e-4 -0.004989266 0.002999961 -3.25488e-4 -0.00497508 0 4.96934e-4 -0.004824578 0.002999961 0.001312196 -0.004825472 0 0.001309096 -0.004544138 0 0.002085626 -0.004232823 0.002999961 -0.002661228 -0.004611909 0 -0.001930892 -0.004613161 0.002999961 -0.001928031 -0.004866838 0 -0.001145482 -0.004989027 0 -3.28781e-4 -0.004867613 0.002999961 -0.001142323 -0.00313735 0 -0.003892958 -0.003735184 0 -0.003323614 -0.003139138 0.002999961 -0.003891706 -0.004231274 0 -0.002663552 -0.003736972 0.002999961 -0.003321766 -0.002455592 0.002999961 -0.00435543 -0.002453982 0 -0.004356205 -0.00170499 0.002999961 -0.004700243 -0.001703798 0 -0.004700601 -9.07922e-4 0 -0.004916846 -9.07922e-4 0.002999961 -0.004916846 -0.01209574 -3.20492e-4 0.2339668 -0.147539 1.56396e-4 -0.03371787 -0.01197266 1.55388e-4 0.2339045 -0.1509075 -0.002131402 -0.03201156 -0.01534104 -0.002131402 0.2356107 -0.01575392 -0.001954615 0.2358199 -0.01192116 6.47486e-4 0.2338784 -0.1474876 6.48512e-4 -0.03374385 -0.1475092 0.001143336 -0.03373295 -0.01194262 0.001142382 0.2338892 -0.1476032 0.001627445 -0.03368538 -0.01203644 0.001626551 0.2339367 -0.01220005 0.002086818 0.2340196 -0.1477669 0.002087593 -0.03360241 -0.147996 0.002511203 -0.03348642 -0.01242899 0.002510607 0.2341356 -0.148284 0.002886831 -0.03334051 -0.01271706 0.002886414 0.2342815 -0.01305639 0.003203928 0.2344534 -0.1486232 0.003204166 -0.03316867 -0.1490041 0.003454446 -0.03297573 -0.01343774 0.003454446 0.2346466 -0.1494171 0.003631293 -0.03276652 -0.01385062 0.003631234 0.2348558 -0.1476619 -3.19554e-4 -0.03365558 -0.01228702 -7.67175e-4 0.2340637 -0.1478531 -7.66351e-4 -0.03355878 -0.01254129 -0.001172423 0.2341925 -0.1481073 -0.001171767 -0.03342998 -0.1484175 -0.001524806 -0.03327286 -0.01285159 -0.001525282 0.2343497 -0.01320946 -0.001816093 0.2345309 -0.1487754 -0.001815736 -0.03309154 -0.01360511 -0.002036929 0.2347314 -0.1491711 -0.00203669 -0.03289109 -0.149594 -0.002181589 -0.03267693 -0.01402783 -0.002181708 0.2349455 -0.01446604 -0.002246499 0.2351675 -0.1500322 -0.002246499 -0.0324549 -0.01490777 -0.002229571 0.2353913 -0.1504741 -0.002229571 -0.03223109 -0.1517017 -0.001704037 -0.03160923 -0.1513204 -0.001954615 -0.03180241 -0.01613527 -0.001704037 0.2360131 -0.1525581 -5.86958e-4 -0.03117543 -0.1523291 -0.001010715 -0.03129142 -0.01699161 -5.86965e-4 0.2364469 -0.152041 -0.001386523 -0.03143733 -0.0164746 -0.001386523 0.236185 -0.01676267 -0.001010775 0.2363309 -0.1528155 3.57499e-4 -0.03104501 -0.0172705 8.52389e-4 0.2365881 -0.1528369 8.52396e-4 -0.03103417 -0.01715523 -1.26688e-4 0.2365297 -0.01724904 3.57492e-4 0.2365773 -0.1527217 -1.26681e-4 -0.03109252 -0.01690465 0.002267003 0.2364028 -0.1524711 0.002267003 -0.03121948 -0.1526623 0.001820325 -0.03112262 -0.01709592 0.001820325 0.2364997 -0.1527854 0.001344442 -0.03106027 -0.01721894 0.001344442 0.236562 -0.1515487 0.003315985 -0.03168672 -0.1519066 0.003025174 -0.03150546 -0.01598221 0.003315985 0.2359355 -0.1522168 0.002672314 -0.03134828 -0.01665037 0.002672314 0.236274 -0.01634007 0.003025174 0.2361168 -0.01516383 0.00368154 0.235521 -0.151153 0.00353676 -0.03188717 -0.01558655 0.00353676 0.2357351 -0.01472562 0.00374639 0.235299 -0.1507303 0.00368154 -0.03210133 -0.150292 0.00374639 -0.0323233 -0.01428389 0.003729462 0.2350752 -0.1498503 0.003729462 -0.03254705 -0.147539 1.56396e-4 -0.03371787 -0.1483792 6.81032e-4 -0.03329223 -0.1474876 6.48512e-4 -0.03374385 -0.150541 0.002704381 -0.03219723 -0.1507303 0.00368154 -0.03210133 -0.1502488 0.002747535 -0.03234517 -0.1475092 0.001143336 -0.03373295 -0.1483934 0.001010954 -0.03328508 -0.1476619 -3.19554e-4 -0.03365558 -0.1484137 3.52951e-4 -0.03327482 -0.1476032 0.001627445 -0.03368538 -0.1484559 0.001333832 -0.03325343 -0.1478531 -7.66351e-4 -0.03355878 -0.1484958 3.57126e-5 -0.03323316 -0.1481073 -0.001171767 -0.03342998 -0.1486234 -2.62022e-4 -0.03316855 -0.1484175 -0.001524806 -0.03327286 -0.148793 -5.32143e-4 -0.03308266 -0.1477669 0.002087593 -0.03360241 -0.1485649 0.001640796 -0.03319817 -0.1489999 -7.67276e-4 -0.03297781 -0.1487754 -0.001815736 -0.03309154 -0.1487175 0.001923441 -0.03312087 -0.147996 0.002511203 -0.03348642 -0.1490041 0.003454446 -0.03297573 -0.1491359 0.002385795 -0.03290897 -0.1493902 0.002552926 -0.03278017 -0.1491711 -0.00203669 -0.03289109 -0.1492385 -9.61026e-4 -0.032857 -0.150292 0.00374639 -0.0323233 -0.1499543 0.00273627 -0.03249436 -0.150076 -0.001247644 -0.03243273 -0.149594 -0.002181589 -0.03267693 -0.1500322 -0.002246499 -0.0324549 -0.1519066 0.003025174 -0.03150546 -0.1515487 0.003315985 -0.03168672 -0.1513251 0.002266764 -0.03179997 -0.1508228 0.002607822 -0.03205448 -0.151153 0.00353676 -0.03188717 -0.1524711 0.002267003 -0.03121948 -0.151829 0.001463532 -0.03154474 -0.1526623 0.001820325 -0.03112262 -0.1516068 -4.23863e-4 -0.03165727 -0.152041 -0.001386523 -0.03143733 -0.1523291 -0.001010715 -0.03129142 -0.151911 0.001146256 -0.0315032 -0.1527854 0.001344442 -0.03106027 -0.1528369 8.52396e-4 -0.03103417 -0.1519454 8.18245e-4 -0.03148579 -0.1519311 4.88317e-4 -0.031493 -0.1527217 -1.26681e-4 -0.03109252 -0.1517595 -1.41323e-4 -0.03157997 -0.1525581 -5.86958e-4 -0.03117543 -0.1518685 1.6552e-4 -0.03152471 -0.1528155 3.57499e-4 -0.03104501 -0.151532 0.002031505 -0.03169518 -0.1522168 0.002672314 -0.03134828 -0.1517015 0.001761317 -0.03160935 -0.1513204 -0.001954615 -0.03180241 -0.1509343 -0.001053094 -0.03199791 -0.1509075 -0.002131402 -0.03201156 -0.1514148 -6.74389e-4 -0.03175455 -0.1511886 -8.86051e-4 -0.03186917 -0.1517017 -0.001704037 -0.03160923 -0.1504741 -0.002229571 -0.03223109 -0.1503702 -0.001236379 -0.03228372 -0.1510865 0.002460598 -0.03192085 -0.1498503 0.003729462 -0.03254705 -0.1496655 0.002670824 -0.03264069 -0.1494171 0.003631293 -0.03276652 -0.1495023 -0.001108109 -0.03272336 -0.149784 -0.00120449 -0.03258067 -0.148284 0.002886831 -0.03334051 -0.1489096 0.002174019 -0.03302359 -0.1486232 0.003204166 -0.03316867 -0.1506591 -0.001170933 -0.03213739 -0.01197266 1.55388e-4 0.2339045 -0.012847 3.54237e-4 0.2343474 -0.01209574 -3.20492e-4 0.2339668 -0.01558655 0.00353676 0.2357351 -0.01525628 0.002607822 0.2355678 -0.01497447 0.002704322 0.2354251 -0.01228702 -7.67175e-4 0.2340637 -0.01292896 3.69378e-5 0.2343889 -0.01192116 6.47486e-4 0.2338784 -0.01281273 6.82317e-4 0.23433 -0.01305639 -2.60926e-4 0.2344534 -0.01254129 -0.001172423 0.2341925 -0.01194262 0.001142382 0.2338892 -0.01282715 0.001012206 0.2343373 -0.01203644 0.001626551 0.2339367 -0.0128898 0.001334905 0.234369 -0.01220005 0.002086818 0.2340196 -0.01299893 0.00164169 0.2344243 -0.01322585 -5.31222e-4 0.2345393 -0.01285159 -0.001525282 0.2343497 -0.01242899 0.002510607 0.2341356 -0.01315158 0.001924097 0.2345017 -0.01320946 -0.001816093 0.2345309 -0.01343268 -7.66564e-4 0.2346441 -0.01360511 -0.002036929 0.2347314 -0.01393508 -0.001107811 0.2348985 -0.01421695 -0.001204431 0.2350413 -0.01367127 -9.60535e-4 0.2347649 -0.01446604 -0.002246499 0.2351675 -0.01450914 -0.001247644 0.2351893 -0.0148037 -0.001236438 0.2353386 -0.01356983 0.002386033 0.2347135 -0.01343774 0.003454446 0.2346466 -0.01382368 0.002552926 0.2348421 -0.01536792 -0.001053094 0.2356243 -0.01575392 -0.001954615 0.2358199 -0.01534104 -0.002131402 0.2356107 -0.01438784 0.00273627 0.2351279 -0.01472562 0.00374639 0.235299 -0.01468235 0.002747535 0.2352771 -0.0163021 1.65513e-4 0.2360976 -0.01699161 -5.86965e-4 0.2364469 -0.01619303 -1.4133e-4 0.2360423 -0.01598221 0.003315985 0.2359355 -0.01634007 0.003025174 0.2361168 -0.01575869 0.002266764 0.2358223 -0.0163446 0.001146256 0.2361191 -0.01709592 0.001820325 0.2364997 -0.01721894 0.001344442 0.236562 -0.01690465 0.002267003 0.2364028 -0.01626253 0.001463532 0.2360776 -0.01636463 4.8831e-4 0.2361292 -0.01724904 3.57492e-4 0.2365773 -0.0172705 8.52389e-4 0.2365881 -0.01637893 8.18238e-4 0.2361365 -0.01665037 0.002672314 0.236274 -0.01596552 0.002031505 0.2359271 -0.01613503 0.001761317 0.2360129 -0.01584833 -6.74396e-4 0.2358677 -0.01613527 -0.001704037 0.2360131 -0.01562213 -8.86058e-4 0.2357531 -0.01604038 -4.2387e-4 0.235965 -0.01676267 -0.001010775 0.2363309 -0.0164746 -0.001386523 0.236185 -0.01516383 0.00368154 0.235521 -0.01552009 0.002460598 0.2357015 -0.01428389 0.003729462 0.2350752 -0.01409906 0.002670824 0.2349816 -0.01490777 -0.002229571 0.2353913 -0.01385062 0.003631234 0.2348558 -0.01402783 -0.002181708 0.2349455 -0.01271706 0.002886414 0.2342815 -0.01334363 0.002174496 0.2345989 -0.01305639 0.003203928 0.2344534 -0.01509261 -0.001170933 0.2354849 -0.01715523 -1.26688e-4 0.2365297 -0.1499543 0.00273627 -0.03249436 -0.1496655 0.002670824 -0.03264069 -0.01409906 0.002670824 0.2349816 -0.1508228 0.002607822 -0.03205448 -0.150541 0.002704381 -0.03219723 -0.01497447 0.002704322 0.2354251 -0.1502488 0.002747535 -0.03234517 -0.01438784 0.00273627 0.2351279 -0.01468235 0.002747535 0.2352771 -0.01575869 0.002266764 0.2358223 -0.151532 0.002031505 -0.03169518 -0.1513251 0.002266764 -0.03179997 -0.01525628 0.002607822 0.2355678 -0.01552009 0.002460598 0.2357015 -0.1510865 0.002460598 -0.03192085 -0.151829 0.001463532 -0.03154474 -0.01626253 0.001463532 0.2360776 -0.151911 0.001146256 -0.0315032 -0.1517015 0.001761317 -0.03160935 -0.01596552 0.002031505 0.2359271 -0.01613503 0.001761317 0.2360129 -0.1518685 1.6552e-4 -0.03152471 -0.1519311 4.88317e-4 -0.031493 -0.01636463 4.8831e-4 0.2361292 -0.01637893 8.18238e-4 0.2361365 -0.1519454 8.18245e-4 -0.03148579 -0.0163446 0.001146256 0.2361191 -0.01604038 -4.2387e-4 0.235965 -0.1514148 -6.74389e-4 -0.03175455 -0.1516068 -4.23863e-4 -0.03165727 -0.0163021 1.65513e-4 0.2360976 -0.01619303 -1.4133e-4 0.2360423 -0.1517595 -1.41323e-4 -0.03157997 -0.1509343 -0.001053094 -0.03199791 -0.01536792 -0.001053094 0.2356243 -0.1506591 -0.001170933 -0.03213739 -0.1511886 -8.86051e-4 -0.03186917 -0.01584833 -6.74396e-4 0.2358677 -0.01562213 -8.86058e-4 0.2357531 -0.149784 -0.00120449 -0.03258067 -0.150076 -0.001247644 -0.03243273 -0.01450914 -0.001247644 0.2351893 -0.0148037 -0.001236438 0.2353386 -0.1503702 -0.001236379 -0.03228372 -0.01509261 -0.001170933 0.2354849 -0.01367127 -9.60535e-4 0.2347649 -0.1489999 -7.67276e-4 -0.03297781 -0.1492385 -9.61026e-4 -0.032857 -0.01421695 -0.001204431 0.2350413 -0.01393508 -0.001107811 0.2348985 -0.1495023 -0.001108109 -0.03272336 -0.1486234 -2.62022e-4 -0.03316855 -0.01305639 -2.60926e-4 0.2344534 -0.1484958 3.57126e-5 -0.03323316 -0.148793 -5.32143e-4 -0.03308266 -0.01343268 -7.66564e-4 0.2346441 -0.01322585 -5.31222e-4 0.2345393 -0.1484137 3.52951e-4 -0.03327482 -0.012847 3.54237e-4 0.2343474 -0.1483792 6.81032e-4 -0.03329223 -0.01292896 3.69378e-5 0.2343889 -0.01281273 6.82317e-4 0.23433 -0.1483934 0.001010954 -0.03328508 -0.1484559 0.001333832 -0.03325343 -0.01282715 0.001012206 0.2343373 -0.0128898 0.001334905 0.234369 -0.1485649 0.001640796 -0.03319817 -0.01299893 0.00164169 0.2344243 -0.1487175 0.001923441 -0.03312087 -0.1489096 0.002174019 -0.03302359 -0.01315158 0.001924097 0.2345017 -0.01334363 0.002174496 0.2345989 -0.1491359 0.002385795 -0.03290897 -0.01356983 0.002386033 0.2347135 -0.1493902 0.002552926 -0.03278017 -0.01382368 0.002552926 0.2348421 0.003062307 -0.002549111 0.03723132 0.009840667 -0.002549111 0.05061244 0.009695887 -0.00190854 0.05068576 0.00964719 -0.001249969 0.05071043 0.00286889 -0.001249969 0.03732931 0.002917587 -0.00190854 0.03730463 0.01039999 -0.003707408 0.05032908 0.004020988 -0.004193425 0.03674572 0.01079934 -0.004193425 0.05012685 0.003621697 -0.003707408 0.03694796 0.01007747 -0.003154218 0.05049246 0.003299176 -0.003154218 0.03711134 0.005562245 -0.005127847 0.03596496 0.0123406 -0.005127847 0.04934608 0.01178306 -0.004913508 0.04962849 0.005004763 -0.004913508 0.03624737 0.01126456 -0.004599153 0.04989111 0.004486262 -0.004599153 0.03651005 0.01409262 -0.005127131 0.04845857 0.01351135 -0.005236089 0.04875302 0.007314264 -0.005127131 0.03507745 0.01292198 -0.005236327 0.04905158 0.006143629 -0.005236327 0.03567045 0.006733 -0.005236089 0.03537189 0.01516807 -0.004597842 0.04791378 0.008854627 -0.004191994 0.03429722 0.01563292 -0.004191994 0.04767829 0.007871568 -0.004912436 0.03479516 0.00838977 -0.004597842 0.03453266 0.01464992 -0.004912436 0.04817628 0.009812235 -0.002548158 0.0338121 0.01659059 -0.002548158 0.04719322 0.01635402 -0.003152966 0.04731303 0.009575664 -0.003152966 0.03393191 0.01603186 -0.003705918 0.04747623 0.009253561 -0.003705918 0.0340951 0.01673513 -5.91634e-4 0.04711997 0.01678377 -0.001249969 0.04709535 0.009956777 -5.91632e-4 0.03373885 0.01673507 -0.00190854 0.04712003 0.009956777 -0.00190854 0.03373891 0.01000547 -0.001249969 0.03371423 0.01635372 6.53778e-4 0.04731321 0.009253084 0.001206815 0.03409534 0.01603138 0.001206815 0.04747647 0.009812116 4.87897e-5 0.03381216 0.009575426 6.5378e-4 0.03393208 0.01659047 4.87884e-5 0.04719328 0.007870554 0.002413034 0.0347957 0.01464885 0.002413034 0.04817682 0.01516717 0.002098619 0.04791426 0.008388817 0.002098619 0.03453314 0.01563227 0.001692831 0.04767864 0.008853912 0.001692831 0.03429758 0.01292085 0.00273627 0.04905217 0.01351016 0.00273627 0.04875361 0.006142497 0.00273633 0.03567105 0.01409149 0.002627551 0.04845917 0.007313132 0.002627551 0.03507804 0.006731808 0.00273633 0.03537249 0.005561172 0.002627551 0.0359655 0.005003809 0.002413034 0.03624784 0.01233953 0.002627551 0.04934662 0.0117821 0.002413034 0.04962897 0.004485487 0.002098619 0.0365104 0.004020392 0.001692831 0.03674602 0.01126384 0.002098619 0.04989153 0.00362128 0.001206815 0.0369482 0.01079875 0.001692831 0.05012714 0.01039958 0.001206815 0.05032932 0.003298938 6.53779e-4 0.03711146 0.003062188 4.87894e-5 0.03723138 0.01007723 6.53778e-4 0.05049258 0.002917528 -5.91633e-4 0.03730469 0.009840548 4.87881e-5 0.0506125 0.009695827 -5.91634e-4 0.05068582 0.01222401 -0.006124854 0.04940515 0.01292198 -0.005236327 0.04905158 0.01288354 -0.006236016 0.04907107 0.009944975 0.002149701 0.05055958 0.01039958 0.001206815 0.05032932 0.009529531 0.001565337 0.05077004 0.01098531 -0.005580127 0.05003261 0.01178306 -0.004913508 0.04962849 0.01158648 -0.005904555 0.04972809 0.0123406 -0.005127847 0.04934608 0.01355034 -0.006235778 0.04873329 0.01351135 -0.005236089 0.04875302 0.01126456 -0.004599153 0.04989111 0.01043528 -0.005159676 0.05031126 0.01079934 -0.004193425 0.05012685 0.01039999 -0.003707408 0.05032908 0.009946823 -0.004651844 0.05055868 0.01409262 -0.005127131 0.04845857 0.01420933 -0.006124138 0.04839944 0.01007747 -0.003154218 0.05049246 0.00953108 -0.004067897 0.05076926 0.01464992 -0.004912436 0.04817628 0.01484584 -0.005903899 0.04807704 0.01516807 -0.004597842 0.04791378 0.01563292 -0.004191994 0.04767829 0.01599693 -0.005158722 0.04749393 0.0154457 -0.005580127 0.04777318 0.01723474 -0.003417789 0.04686695 0.01690155 -0.004065275 0.04703569 0.01635402 -0.003152966 0.04731303 0.009695887 -0.00190854 0.05068576 0.008805036 -0.001995801 0.05113703 0.00964719 -0.001249969 0.05071043 0.01762598 -0.001995801 0.04666876 0.01747798 -0.002722263 0.04674369 0.01673507 -0.00190854 0.04712003 0.0091964 9.18178e-4 0.05093878 0.009840548 4.87881e-5 0.0506125 0.008953094 2.22738e-4 0.05106204 0.01747751 2.24418e-4 0.04674392 0.01673513 -5.91634e-4 0.04711997 0.01659047 4.87884e-5 0.04719328 0.01079875 0.001692831 0.05012714 0.01043361 0.002658247 0.0503121 0.01126384 0.002098619 0.04989153 0.01599544 0.002659916 0.0474947 0.01516717 0.002098619 0.04791426 0.01544457 0.003080666 0.04777371 0.01222252 0.003624439 0.04940593 0.01292085 0.00273627 0.04905217 0.01233953 0.002627551 0.04934662 0.01464885 0.002413034 0.04817682 0.014844 0.003404676 0.04807794 0.01409149 0.002627551 0.04845917 0.01420724 0.003624677 0.04840052 0.01288199 0.003735959 0.04907184 0.01351016 0.00273627 0.04875361 0.01354855 0.003735959 0.04873418 0.01723372 9.20278e-4 0.04686743 0.01635372 6.53778e-4 0.04731321 0.01690018 0.001567542 0.0470364 0.01648432 0.002151787 0.04724705 0.01603138 0.001206815 0.04747647 0.01563227 0.001692831 0.04767864 0.0117821 0.002413034 0.04962897 0.01098448 0.003079473 0.05003303 0.01158523 0.003404021 0.04972869 0.01767587 -0.001249969 0.04664343 0.01678377 -0.001249969 0.04709535 0.01762598 -5.0445e-4 0.0466687 0.01007723 6.53778e-4 0.05049258 0.01659059 -0.002548158 0.04719322 0.009695827 -5.91634e-4 0.05068582 0.008804976 -5.0445e-4 0.05113708 0.01648586 -0.004649937 0.04724627 0.01603186 -0.003705918 0.04747623 0.008755087 -0.001249969 0.05116236 0.009840667 -0.002549111 0.05061244 0.00895363 -0.002724826 0.0510618 0.009197473 -0.00342077 0.05093824 -0.001371145 -0.002724409 0.03067994 0.003062307 -0.002549111 0.03723132 0.002917587 -0.00190854 0.03730463 0.00286889 -0.001249969 0.03732931 -0.001569449 -0.001249969 0.03078043 -0.00151962 -0.001995563 0.03075516 0.003621697 -0.003707408 0.03694796 -3.77921e-4 -0.004651784 0.03017681 0.004020988 -0.004193425 0.03674572 -7.93807e-4 -0.00406754 0.03038746 0.003299176 -0.003154218 0.03711134 -0.001127362 -0.003420293 0.03055644 6.6181e-4 -0.005580723 0.02965009 0.001262307 -0.005904674 0.02934592 0.005004763 -0.004913508 0.03624737 0.004486262 -0.004599153 0.03651005 1.10935e-4 -0.005159974 0.02992916 0.006733 -0.005236089 0.03537189 0.006143629 -0.005236327 0.03567045 0.003224313 -0.006235957 0.02835202 0.005562245 -0.005127847 0.03596496 0.001899063 -0.006124734 0.02902334 0.007871568 -0.004912436 0.03479516 0.005121886 -0.005579531 0.02739083 0.00838977 -0.004597842 0.03453266 0.003883838 -0.006124496 0.02801793 0.004521071 -0.005904018 0.02769517 0.007314264 -0.005127131 0.03507745 0.006161332 -0.004649758 0.02686429 0.006576836 -0.004065334 0.02665382 0.009253561 -0.003705918 0.0340951 0.005672693 -0.005158245 0.02711176 0.008854627 -0.004191994 0.03429722 0.00730133 -0.001995563 0.02628678 0.009956777 -0.00190854 0.03373891 0.007153213 -0.00272274 0.02636182 0.009812235 -0.002548158 0.0338121 0.009575664 -0.003152966 0.03393191 0.006909906 -0.003418147 0.02648508 0.009956777 -5.91632e-4 0.03373885 0.00730133 -5.04448e-4 0.02628678 0.007152855 2.2442e-4 0.026362 0.007351219 -0.001249969 0.0262615 0.01000547 -0.001249969 0.03371423 0.006575524 0.001567542 0.02665448 0.006159663 0.002151787 0.02686512 0.009253084 0.001206815 0.03409534 0.006909072 9.2028e-4 0.0264855 0.009575426 6.5378e-4 0.03393208 0.009812116 4.87897e-5 0.03381216 0.004519343 0.003404676 0.02769601 0.007870554 0.002413034 0.0347957 0.005119919 0.003080666 0.02739179 0.008388817 0.002098619 0.03453314 0.008853912 0.001692831 0.03429758 0.005670785 0.002659916 0.02711278 0.006731808 0.00273633 0.03537249 0.003223896 0.003735959 0.02835226 0.002557337 0.003735959 0.02868992 0.007313132 0.002627551 0.03507804 0.003882646 0.003624677 0.02801859 0.006142497 0.00273633 0.03567105 0.001897871 0.003624498 0.029024 0.005561172 0.002627551 0.0359655 0.001260578 0.003404021 0.02934676 0.005003809 0.002413034 0.03624784 0.004485487 0.002098619 0.0365104 6.59848e-4 0.003079473 0.0296511 1.09e-4 0.002658247 0.02993017 0.004020392 0.001692831 0.03674602 -3.79616e-4 0.002149701 0.03017765 0.00362128 0.001206815 0.0369482 0.003298938 6.53779e-4 0.03711146 -7.951e-4 0.001565337 0.03038811 -0.001128196 9.1818e-4 0.03055685 0.003062188 4.87894e-5 0.03723138 -0.001371502 2.2274e-4 0.03068011 0.002917528 -5.91633e-4 0.03730469 -0.00151962 -5.04448e-4 0.03075516 0.002557814 -0.006235957 0.02868968 0.01288354 -0.006236016 0.04907107 0.006771981 -0.006235778 0.03535217 0.006105244 -0.006236016 0.03568994 0.01767587 -0.001249969 0.04664343 0.01084768 -5.04448e-4 0.03328758 0.01089757 -0.001249969 0.03326231 0.005445659 -0.006124854 0.03602403 0.01222401 -0.006124854 0.04940515 0.004808127 -0.005904555 0.03634697 0.01158648 -0.005904555 0.04972809 0.01098531 -0.005580127 0.05003261 0.004206955 -0.005580127 0.03665149 0.003656923 -0.005159676 0.03693014 0.01043528 -0.005159676 0.05031126 0.003168523 -0.004651844 0.03717756 0.009946823 -0.004651844 0.05055868 0.00953108 -0.004067897 0.05076926 0.00275278 -0.004067897 0.03738814 0.002419173 -0.00342077 0.03755712 0.009197473 -0.00342077 0.05093824 0.002175271 -0.002724826 0.03768068 0.00895363 -0.002724826 0.0510618 0.008805036 -0.001995801 0.05113703 0.002026677 -0.001995801 0.03775596 0.008755087 -0.001249969 0.05116236 0.001976788 -0.001249969 0.03778123 0.01355034 -0.006235778 0.04873329 0.01420933 -0.006124138 0.04839944 0.00743103 -0.006124138 0.03501832 0.008067488 -0.005903899 0.03469592 0.01484584 -0.005903899 0.04807704 0.0154457 -0.005580127 0.04777318 0.008667349 -0.005580127 0.03439205 0.01599693 -0.005158722 0.04749393 0.009218573 -0.005158722 0.03411281 0.00970751 -0.004649937 0.03386515 0.01648586 -0.004649937 0.04724627 0.01690155 -0.004065275 0.04703569 0.01012319 -0.004065275 0.03365457 0.01723474 -0.003417789 0.04686695 0.01045638 -0.003417789 0.03348582 0.01069968 -0.002722263 0.03336256 0.01747798 -0.002722263 0.04674369 0.01762598 -0.001995801 0.04666876 0.01084762 -0.001995801 0.03328764 0.01747751 2.24418e-4 0.04674392 0.01069921 2.2442e-4 0.0333628 0.01762598 -5.0445e-4 0.0466687 0.01648432 0.002151787 0.04724705 0.00970596 0.002151787 0.03386592 0.01690018 0.001567542 0.0470364 0.01723372 9.20278e-4 0.04686743 0.01012188 0.001567542 0.03365528 0.01045542 9.2028e-4 0.0334863 0.01544457 0.003080666 0.04777371 0.014844 0.003404676 0.04807794 0.0080657 0.003404676 0.03469681 0.009217083 0.002659916 0.03411358 0.01599544 0.002659916 0.0474947 0.008666217 0.003080666 0.03439265 0.006103694 0.003735959 0.03569072 0.01354855 0.003735959 0.04873418 0.01288199 0.003735959 0.04907184 0.006770193 0.003735959 0.03535306 0.007428944 0.003624677 0.03501939 0.01420724 0.003624677 0.04840052 0.01098448 0.003079473 0.05003303 0.00420612 0.003079473 0.0366519 0.01158523 0.003404021 0.04972869 0.01222252 0.003624439 0.04940593 0.004806935 0.003404021 0.03634756 0.005444169 0.003624498 0.0360248 0.009944975 0.002149701 0.05055958 0.002751171 0.001565337 0.03738892 0.003166675 0.002149701 0.03717845 0.003655314 0.002658247 0.03693097 0.01043361 0.002658247 0.0503121 0.0024181 9.18179e-4 0.03755766 0.009529531 0.001565337 0.05077004 0.0091964 9.18178e-4 0.05093878 0.002174794 2.22739e-4 0.03768092 0.008953094 2.22738e-4 0.05106204 0.002026677 -5.04449e-4 0.03775596 0.008804976 -5.0445e-4 0.05113708 0.007153213 -0.00272274 0.02636182 -0.001884996 -0.002724826 0.008520603 -0.001736402 -0.001995801 0.008445322 -0.001686513 -0.001249969 0.00842005 0.007351219 -0.001249969 0.0262615 0.00730133 -0.001995563 0.02628678 -0.002462506 -0.004067897 0.008813083 0.006161332 -0.004649758 0.02686429 -0.002878189 -0.004651844 0.009023725 0.006576836 -0.004065334 0.02665382 -0.002128899 -0.00342077 0.008644104 0.006909906 -0.003418147 0.02648508 0.004521071 -0.005904018 0.02769517 -0.004517853 -0.005904555 0.009854257 -0.00391668 -0.005580127 0.009549736 0.005121886 -0.005579531 0.02739083 -0.003366649 -0.005159676 0.009271085 0.005672693 -0.005158245 0.02711176 -0.006481707 -0.006235778 0.01084905 -0.005814909 -0.006236016 0.01051133 0.002557814 -0.006235957 0.02868968 -0.005155384 -0.006124854 0.01017719 0.003883838 -0.006124496 0.02801793 0.003224313 -0.006235957 0.02835202 -0.007777214 -0.005903899 0.01150536 6.6181e-4 -0.005580723 0.02965009 -0.008377075 -0.005580127 0.01180917 0.001899063 -0.006124734 0.02902334 0.001262307 -0.005904674 0.02934592 -0.007140696 -0.006124138 0.0111829 -7.93807e-4 -0.00406754 0.03038746 -0.009832918 -0.004065275 0.01254665 -0.009417235 -0.004649937 0.01233607 -3.77921e-4 -0.004651784 0.03017681 -0.008928298 -0.005158722 0.01208841 1.10935e-4 -0.005159974 0.02992916 -0.01055735 -0.001995801 0.01291364 -0.01040935 -0.002722263 0.01283866 -0.00151962 -0.001995563 0.03075516 -0.0101661 -0.003417789 0.01271545 -0.001127362 -0.003420293 0.03055644 -0.001371145 -0.002724409 0.03067994 -0.01055735 -5.04446e-4 0.01291364 -0.001371502 2.2274e-4 0.03068011 -0.01040887 2.24422e-4 0.01283842 -0.001569449 -0.001249969 0.03078043 -0.00151962 -5.04448e-4 0.03075516 -0.01060724 -0.001249969 0.01293891 -3.79616e-4 0.002149701 0.03017765 -0.009415686 0.002151787 0.0123353 -0.009831547 0.001567542 0.012546 -7.951e-4 0.001565337 0.03038811 -0.01016509 9.20282e-4 0.01271492 -0.001128196 9.1818e-4 0.03055685 -0.007775366 0.003404676 0.01150441 -0.008375942 0.003080666 0.01180863 0.001260578 0.003404021 0.02934676 -0.008926808 0.002659916 0.01208764 1.09e-4 0.002658247 0.02993017 6.59848e-4 0.003079473 0.0296511 -0.006479918 0.003735959 0.01084816 0.003223896 0.003735959 0.02835226 -0.00581336 0.003735959 0.01051056 0.001897871 0.003624498 0.029024 0.002557337 0.003735959 0.02868992 -0.007138669 0.003624677 0.01118189 0.003882646 0.003624677 0.02801859 0.004519343 0.003404676 0.02769601 -0.005153894 0.003624498 0.01017647 0.005119919 0.003080666 0.02739179 -0.004516601 0.003404021 0.009853661 -0.003915846 0.003079473 0.009549319 0.005670785 0.002659916 0.02711278 0.006159663 0.002151787 0.02686512 -0.00336498 0.002658247 0.00927031 0.006575524 0.001567542 0.02665448 -0.0028764 0.002149701 0.009022772 -0.002460896 0.001565337 0.008812308 0.006909072 9.2028e-4 0.0264855 0.007152855 2.2442e-4 0.026362 -0.002127766 9.18182e-4 0.008643567 0.00730133 -5.04448e-4 0.02628678 -0.00188446 2.22742e-4 0.008520305 -0.001736342 -5.04446e-4 0.008445262 0.005445659 -0.006124854 0.03602403 0.006105244 -0.006236016 0.03568994 0.002372086 -0.007221579 0.02878373 0.01089757 -0.001249969 0.03326231 0.008191525 -4.17799e-4 0.02583587 0.008243322 -0.001249969 0.02580964 0.001639425 -0.007083535 0.02915489 0.004808127 -0.005904555 0.03634697 9.30387e-4 -0.006832897 0.02951407 0.004206955 -0.005580127 0.03665149 2.58779e-4 -0.006474316 0.02985429 -3.62176e-4 -0.006014645 0.03016883 -9.19483e-4 -0.0054636 0.03045111 0.003656923 -0.005159676 0.03693014 -0.001402974 -0.00483179 0.03069609 0.003168523 -0.004651844 0.03717756 0.00275278 -0.004067897 0.03738814 -0.001804232 -0.004130482 0.03089934 -0.00211519 -0.003373146 0.03105682 0.002419173 -0.00342077 0.03755712 -0.002329468 -0.002574443 0.03116542 0.002175271 -0.002724826 0.03768068 0.002026677 -0.001995801 0.03775596 -0.002442955 -0.001749992 0.03122287 0.001976788 -0.001249969 0.03778123 -0.002461552 -0.001249969 0.03123229 0.006771981 -0.006235778 0.03535217 0.003114044 -0.007244765 0.02840787 0.00743103 -0.006124138 0.03501832 0.003853619 -0.00715208 0.02803325 0.004574477 -0.006945371 0.02766811 0.008067488 -0.005903899 0.03469592 0.008667349 -0.005580127 0.03439205 0.005262434 -0.006628692 0.02731961 0.009218573 -0.005158722 0.03411281 0.005904257 -0.006208539 0.02699452 0.006487548 -0.005693316 0.02669906 0.00970751 -0.004649937 0.03386515 0.01012319 -0.004065275 0.03365457 0.007001936 -0.005092144 0.02643847 0.01045638 -0.003417789 0.03348582 0.007437527 -0.00441581 0.02621781 0.007785141 -0.00367856 0.02604174 0.01069968 -0.002722263 0.03336256 0.01084762 -0.001995801 0.03328764 0.008038103 -0.002894878 0.02591359 0.008191525 -0.002082169 0.02583587 0.01069921 2.2442e-4 0.0333628 0.008037328 3.9814e-4 0.02591395 0.01084768 -5.04448e-4 0.03328758 0.00970596 0.002151787 0.03386592 0.007001161 0.00259298 0.02643883 0.01012188 0.001567542 0.03365528 0.01045542 9.2028e-4 0.0334863 0.007436096 0.001918196 0.02621853 0.00778383 0.00118184 0.0260424 0.008666217 0.003080666 0.03439265 0.0080657 0.003404676 0.03469681 0.005259573 0.004130303 0.0273211 0.006486773 0.003194153 0.02669942 0.009217083 0.002659916 0.03411358 0.005902171 0.003710269 0.02699553 0.003851711 0.004652321 0.02803421 0.006770193 0.003735959 0.03535306 0.003114044 0.004744768 0.02840787 0.004571557 0.004446327 0.0276696 0.007428944 0.003624677 0.03501939 9.27381e-4 0.004331529 0.02951556 0.001636505 0.004582762 0.02915638 0.004806935 0.003404021 0.03634756 0.005444169 0.003624498 0.0360248 0.002370178 0.004721462 0.02878475 0.006103694 0.003735959 0.03569072 0.003655314 0.002658247 0.03693097 0.003166675 0.002149701 0.03717845 -9.20294e-4 0.002962768 0.03045153 2.56567e-4 0.003972768 0.02985537 0.00420612 0.003079473 0.0366519 -3.62988e-4 0.003513813 0.03016924 0.002751171 0.001565337 0.03738892 -0.001404643 0.002329528 0.03069692 -0.001805841 0.001627326 0.03090012 0.0024181 9.18179e-4 0.03755766 0.002174794 2.22739e-4 0.03768092 -0.002116143 8.6997e-4 0.03105735 0.002026677 -5.04449e-4 0.03775596 -0.002329468 7.44701e-5 0.03116542 -0.002442955 -7.5001e-4 0.03122287 -0.004517853 -0.005904555 0.009854257 -0.004466116 -0.006946325 0.00982809 -0.003778159 -0.006630361 0.009479582 -0.004516601 0.003404021 0.009853661 -0.003915846 0.003079473 0.009549319 -0.003775238 0.004128694 0.009478092 -0.00391668 -0.005580127 0.009549736 -0.005155384 -0.006124854 0.01017719 -0.005186021 -0.007152378 0.01019275 -0.003366649 -0.005159676 0.009271085 -0.003135561 -0.006210267 0.009154081 -0.005923628 -0.007244765 0.01056641 -0.005814909 -0.006236016 0.01051133 -0.006481707 -0.006235778 0.01084905 -0.006667554 -0.007221519 0.01094323 -0.007401227 -0.007082819 0.01131486 -0.007140696 -0.006124138 0.0111829 -0.002878189 -0.004651844 0.009023725 -0.002550899 -0.00569421 0.008857905 -0.007777214 -0.005903899 0.01150536 -0.008110344 -0.006831526 0.0116741 -0.002462506 -0.004067897 0.008813083 -0.002036511 -0.005092978 0.008597314 -0.009400725 -0.00601387 0.01232773 -0.008377075 -0.005580127 0.01180917 -0.008928298 -0.005158722 0.01208841 -0.008781194 -0.006472826 0.01201391 -0.009832918 -0.004065275 0.01254665 -0.01044237 -0.004829525 0.01285541 -0.009417235 -0.004649937 0.01233607 -0.009958028 -0.005462765 0.01261007 -0.0101661 -0.003417789 0.01271545 -0.01040935 -0.002722263 0.01283866 -0.01115393 -0.003369987 0.01321583 -0.01084357 -0.004127323 0.01305866 -0.01136726 -0.002574443 0.0133239 -0.01055735 -0.001995801 0.01291364 -0.01105219 -0.001749992 0.01316428 -0.01060724 -0.001249969 0.01293891 -0.002128899 -0.00342077 0.008644104 -0.001601636 -0.004418194 0.008377015 -0.01148068 -0.001749992 0.01338136 -0.01115292 8.73172e-4 0.01321536 -0.01040887 2.24422e-4 0.01283842 -0.01016509 9.20282e-4 0.01271492 -9.9964e-4 3.94862e-4 0.008072078 -0.001252591 0.001178562 0.008200228 -0.00188446 2.22742e-4 0.008520305 -0.01084202 0.001630485 0.01305782 -0.009831547 0.001567542 0.012546 -0.01044076 0.002331793 0.01285457 -0.01105219 -7.50008e-4 0.01316428 -0.01136726 7.44718e-5 0.0133239 -0.01148068 -7.50008e-4 0.01338136 -0.008375942 0.003080666 0.01180863 -0.008778989 0.003974318 0.01201277 -0.00939989 0.003514647 0.01232731 -0.009957194 0.002963602 0.01260966 -0.009415686 0.002151787 0.0123353 -0.008926808 0.002659916 0.01208764 -0.007138669 0.003624677 0.01118189 -0.007398307 0.004583537 0.01131337 -0.007775366 0.003404676 0.01150441 -0.008107364 0.0043329 0.01167255 -0.006479918 0.003735959 0.01084816 -0.00581336 0.003735959 0.01051056 -0.005923628 0.004744768 0.01056641 -0.006665587 0.004721581 0.01094222 -0.004463255 0.004445314 0.0098266 -0.005153894 0.003624498 0.01017647 -0.005184054 0.004652082 0.01019173 -0.00336498 0.002658247 0.00927031 -0.003133475 0.003708541 0.009153008 -0.002035796 0.002592086 0.008596956 -0.002550184 0.003193318 0.008857548 -0.0028764 0.002149701 0.009022772 -0.001600146 0.001915812 0.0083763 -0.002127766 9.18182e-4 0.008643567 -0.002460896 0.001565337 0.008812308 -0.001736342 -5.04446e-4 0.008445262 -8.46195e-4 -4.17797e-4 0.007994353 -0.001736402 -0.001995801 0.008445322 -8.46195e-4 -0.002082169 0.007994353 -0.001686513 -0.001249969 0.00842005 -0.001253902 -0.003681898 0.008200883 -0.001884996 -0.002724826 0.008520603 -0.001000404 -0.002898156 0.008072495 -7.94445e-4 -0.001249969 0.007968127 -0.01055735 -5.04446e-4 0.01291364 -7.94445e-4 -0.001249969 0.007968127 0.008243322 -0.001249969 0.02580964 -8.46195e-4 -4.17797e-4 0.007994353 0.008191525 -4.17799e-4 0.02583587 -9.9964e-4 3.94862e-4 0.008072078 -0.001252591 0.001178562 0.008200228 0.008037328 3.9814e-4 0.02591395 0.00778383 0.00118184 0.0260424 -0.001600146 0.001915812 0.0083763 0.007436096 0.001918196 0.02621853 -0.002035796 0.002592086 0.008596956 -0.002550184 0.003193318 0.008857548 0.007001161 0.00259298 0.02643883 0.006486773 0.003194153 0.02669942 -0.003133475 0.003708541 0.009153008 0.005902171 0.003710269 0.02699553 -0.003775238 0.004128694 0.009478092 -0.004463255 0.004445314 0.0098266 0.005259573 0.004130303 0.0273211 0.004571557 0.004446327 0.0276696 -0.005184054 0.004652082 0.01019173 0.003851711 0.004652321 0.02803421 -0.005923628 0.004744768 0.01056641 -0.006665587 0.004721581 0.01094222 0.003114044 0.004744768 0.02840787 0.002370178 0.004721462 0.02878475 -0.007398307 0.004583537 0.01131337 0.001636505 0.004582762 0.02915638 -0.008107364 0.0043329 0.01167255 -0.008778989 0.003974318 0.01201277 9.27381e-4 0.004331529 0.02951556 2.56567e-4 0.003972768 0.02985537 -0.00939989 0.003514647 0.01232731 -3.62988e-4 0.003513813 0.03016924 -0.009957194 0.002963602 0.01260966 -0.01044076 0.002331793 0.01285457 -9.20294e-4 0.002962768 0.03045153 -0.001404643 0.002329528 0.03069692 -0.01084202 0.001630485 0.01305782 -0.001805841 0.001627326 0.03090012 -0.01115292 8.73172e-4 0.01321536 -0.01136726 7.44718e-5 0.0133239 -0.002116143 8.6997e-4 0.03105735 -0.002329468 7.44701e-5 0.03116542 -0.01148068 -7.50008e-4 0.01338136 -0.002442955 -7.5001e-4 0.03122287 0.008191525 -0.002082169 0.02583587 0.008038103 -0.002894878 0.02591359 -8.46195e-4 -0.002082169 0.007994353 -0.001000404 -0.002898156 0.008072495 0.007785141 -0.00367856 0.02604174 -0.001253902 -0.003681898 0.008200883 0.007437527 -0.00441581 0.02621781 0.007001936 -0.005092144 0.02643847 -0.001601636 -0.004418194 0.008377015 -0.002036511 -0.005092978 0.008597314 0.006487548 -0.005693316 0.02669906 -0.002550899 -0.00569421 0.008857905 0.005904257 -0.006208539 0.02699452 0.005262434 -0.006628692 0.02731961 -0.003135561 -0.006210267 0.009154081 -0.003778159 -0.006630361 0.009479582 0.004574477 -0.006945371 0.02766811 -0.004466116 -0.006946325 0.00982809 0.003853619 -0.00715208 0.02803325 0.003114044 -0.007244765 0.02840787 -0.005186021 -0.007152378 0.01019275 -0.005923628 -0.007244765 0.01056641 0.002372086 -0.007221579 0.02878373 -0.006667554 -0.007221519 0.01094323 0.001639425 -0.007083535 0.02915489 9.30387e-4 -0.006832897 0.02951407 -0.007401227 -0.007082819 0.01131486 -0.008110344 -0.006831526 0.0116741 2.58779e-4 -0.006474316 0.02985429 -0.008781194 -0.006472826 0.01201391 -3.62176e-4 -0.006014645 0.03016883 -9.19483e-4 -0.0054636 0.03045111 -0.009400725 -0.00601387 0.01232773 -0.009958028 -0.005462765 0.01261007 -0.001402974 -0.00483179 0.03069609 -0.01044237 -0.004829525 0.01285541 -0.001804232 -0.004130482 0.03089934 -0.00211519 -0.003373146 0.03105682 -0.01084357 -0.004127323 0.01305866 -0.01115393 -0.003369987 0.01321583 -0.002329468 -0.002574443 0.03116542 -0.01136726 -0.002574443 0.0133239 -0.002442955 -0.001749992 0.03122287 -0.01148068 -0.001749992 0.01338136 -0.002461552 -0.001249969 0.03123229 -0.01093518 -7.5001e-4 0.03552466 -0.002442955 -7.5001e-4 0.03122287 -0.002442955 -0.001749992 0.03122287 -0.01093518 -0.001749992 0.03552466 -8.05847e-4 -0.002749979 5.91829e-4 -8.92385e-4 -0.001749992 4.51155e-4 -8.92385e-4 -0.002749979 4.51155e-4 -4.26742e-4 -0.002749979 9.03785e-4 -5.69776e-4 -0.001749992 8.21318e-4 -5.69776e-4 -0.002749979 8.21318e-4 -6.97326e-4 -0.002749979 7.16329e-4 -6.97326e-4 -0.001749992 7.16329e-4 -8.05847e-4 -0.001749992 5.91829e-4 -1.0991e-4 -0.001749992 9.9327e-4 -1.0991e-4 -0.002749979 9.9327e-4 5.51818e-5 -0.002749979 9.97748e-4 -4.26742e-4 -0.001749992 9.03785e-4 -2.72051e-4 -0.002749979 9.61624e-4 -2.72051e-4 -0.001749992 9.61624e-4 3.76372e-4 -0.002749979 9.25623e-4 5.23743e-4 -0.002749979 8.50968e-4 3.76372e-4 -0.001749992 9.25623e-4 2.18762e-4 -0.002749979 9.74972e-4 2.18762e-4 -0.001749992 9.74972e-4 5.51818e-5 -0.001749992 9.97748e-4 8.65904e-4 -0.002749979 4.98965e-4 7.71892e-4 -0.001749992 6.34693e-4 7.71892e-4 -0.002749979 6.34693e-4 6.56771e-4 -0.001749992 7.53094e-4 5.23743e-4 -0.001749992 8.50968e-4 6.56771e-4 -0.002749979 7.53094e-4 9.81193e-4 -0.001749992 1.90586e-4 9.81193e-4 -0.002749979 1.90586e-4 9.99296e-4 -0.002749979 2.64943e-5 8.65904e-4 -0.001749992 4.98965e-4 9.36364e-4 -0.002749979 3.49492e-4 9.36364e-4 -0.001749992 3.49492e-4 9.53941e-4 -0.002749979 -2.99606e-4 8.91782e-4 -0.002749979 -4.5263e-4 9.53941e-4 -0.001749992 -2.99606e-4 9.90159e-4 -0.002749979 -1.3848e-4 9.90159e-4 -0.001749992 -1.3848e-4 9.99296e-4 -0.001749992 2.64943e-5 5.69143e-4 -0.002749979 -8.22671e-4 6.96702e-4 -0.001749992 -7.17796e-4 6.96702e-4 -0.002749979 -7.17796e-4 8.05179e-4 -0.001749992 -5.93279e-4 8.91782e-4 -0.001749992 -4.5263e-4 8.05179e-4 -0.002749979 -5.93279e-4 2.71456e-4 -0.001749992 -9.63107e-4 2.71456e-4 -0.002749979 -9.63107e-4 1.09262e-4 -0.002749979 -9.94723e-4 5.69143e-4 -0.001749992 -8.22671e-4 4.26093e-4 -0.002749979 -9.05242e-4 4.26093e-4 -0.001749992 -9.05242e-4 -2.19351e-4 -0.002749979 -9.76462e-4 -3.76958e-4 -0.002749979 -9.27113e-4 -2.19351e-4 -0.001749992 -9.76462e-4 -5.57862e-5 -0.002749979 -9.99231e-4 -5.57862e-5 -0.001749992 -9.99231e-4 1.09262e-4 -0.001749992 -9.94723e-4 -5.2433e-4 -0.002749979 -8.52458e-4 -6.57359e-4 -0.002749979 -7.54584e-4 -5.2433e-4 -0.001749992 -8.52458e-4 -3.76958e-4 -0.001749992 -9.27113e-4 -6.57359e-4 -0.001749992 -7.54584e-4 -7.72497e-4 -0.002749979 -6.36175e-4 -8.66552e-4 -0.002749979 -5.00418e-4 -7.72497e-4 -0.001749992 -6.36175e-4 -9.36958e-4 -0.002749979 -3.50975e-4 -8.66552e-4 -0.001749992 -5.00418e-4 -9.36958e-4 -0.001749992 -3.50975e-4 -9.81842e-4 -0.002749979 -1.92039e-4 -9.99928e-4 -0.002749979 -2.78465e-5 -9.81842e-4 -0.001749992 -1.92039e-4 -9.90783e-4 -0.002749979 1.37012e-4 -9.99928e-4 -0.001749992 -2.78465e-5 -9.90783e-4 -0.001749992 1.37012e-4 -9.54609e-4 -0.002749979 2.98157e-4 -9.54609e-4 -0.001749992 2.98157e-4 -0.01093518 -7.5001e-4 0.03552466 -0.02562159 -0.001749992 0.006532251 -0.02562159 -7.50007e-4 0.006532251 -0.01093518 -0.001749992 0.03552466 -0.01148068 -7.50008e-4 0.01338136 -0.01093518 -7.5001e-4 0.03552466 -0.02562159 -7.50007e-4 0.006532251 -0.01193261 -7.50008e-4 0.01248931 -0.01150405 -7.50008e-4 0.01227223 -0.01105219 -7.50008e-4 0.01316428 -0.0171293 -7.50007e-4 0.002230465 -0.002442955 -7.5001e-4 0.03122287 -0.01150405 -7.50008e-4 0.01227223 -0.01105219 -0.001749992 0.01316428 -0.01105219 -7.50008e-4 0.01316428 -0.01150405 -0.001749992 0.01227223 -0.01193261 -0.001749992 0.01248931 -0.0171293 -0.001749992 0.002230465 -0.02562159 -0.001749992 0.006532251 -0.01148068 -0.001749992 0.01338136 -0.01150405 -0.001749992 0.01227223 -0.01105219 -0.001749992 0.01316428 -0.002442955 -0.001749992 0.03122287 -0.01093518 -0.001749992 0.03552466 -0.01679766 -0.003384411 0.002062439 -0.01181769 -0.002581655 0.01243108 -0.01160097 -0.003384411 0.01232129 -0.01193261 -0.001749992 0.01248931 -0.01701444 -0.002581655 0.002172231 -0.0171293 -0.001749992 0.002230465 -0.0108782 -0.004853665 0.01195514 -0.0103864 -0.005489289 0.01170605 -0.01558309 -0.005489289 0.0014472 -0.01607489 -0.004853665 0.001696288 -0.01648241 -0.00414735 0.001902759 -0.01128566 -0.00414735 0.01216161 -0.01370793 -0.006853759 4.97334e-4 -0.009190678 -0.006499469 0.01110035 -0.008511185 -0.006853759 0.01075613 -0.01438742 -0.006499469 8.41543e-4 -0.01501673 -0.006041705 0.001160323 -0.009820044 -0.006041705 0.01141917 -0.006302297 -0.007240712 0.009637236 -0.01149898 -0.007240712 -6.21613e-4 -0.007052659 -0.007228255 0.01001733 -0.007793843 -0.007098376 0.01039278 -0.01224935 -0.007228255 -2.41507e-4 -0.01299053 -0.007098376 1.33943e-4 -0.004833161 -0.006914138 0.008893013 -0.004144489 -0.006581962 0.008544147 -0.009341239 -0.006581962 -0.001714646 -0.01075428 -0.007135331 -9.98866e-4 -0.005557537 -0.007135331 0.009259939 -0.01002991 -0.006914138 -0.00136578 -0.003504097 -0.006145298 0.008219778 -0.002924084 -0.005612373 0.007925987 -0.008120834 -0.005612373 -0.002332806 -0.008700847 -0.006145298 -0.002039015 -0.002416014 -0.004993557 0.007668614 -0.007612705 -0.004993557 -0.002590179 -0.00718671 -0.004300892 -0.002806007 -0.00198996 -0.004300892 0.007452785 -0.001654505 -0.003548085 0.007282853 -0.006851196 -0.003548085 -0.00297594 -0.001416265 -0.002749979 0.007162153 -0.006612956 -0.002749979 -0.00309664 -9.54609e-4 -0.002749979 2.98157e-4 -9.90783e-4 -0.002749979 1.37012e-4 -0.006612956 -0.002749979 -0.00309664 0.001861691 -0.002749979 -0.007389605 -5.57862e-5 -0.002749979 -9.99231e-4 1.09262e-4 -0.002749979 -9.94723e-4 8.91782e-4 -0.002749979 -4.5263e-4 0.007058382 -0.002749979 0.002869188 -0.001416265 -0.002749979 0.007162153 -6.97326e-4 -0.002749979 7.16329e-4 -8.05847e-4 -0.002749979 5.91829e-4 6.96702e-4 -0.002749979 -7.17796e-4 8.05179e-4 -0.002749979 -5.93279e-4 4.26093e-4 -0.002749979 -9.05242e-4 5.69143e-4 -0.002749979 -8.22671e-4 2.71456e-4 -0.002749979 -9.63107e-4 -3.76958e-4 -0.002749979 -9.27113e-4 -2.19351e-4 -0.002749979 -9.76462e-4 -5.2433e-4 -0.002749979 -8.52458e-4 -7.72497e-4 -0.002749979 -6.36175e-4 -6.57359e-4 -0.002749979 -7.54584e-4 -9.36958e-4 -0.002749979 -3.50975e-4 -8.66552e-4 -0.002749979 -5.00418e-4 -9.99928e-4 -0.002749979 -2.78465e-5 -9.81842e-4 -0.002749979 -1.92039e-4 -8.92385e-4 -0.002749979 4.51155e-4 5.51818e-5 -0.002749979 9.97748e-4 -1.0991e-4 -0.002749979 9.9327e-4 -4.26742e-4 -0.002749979 9.03785e-4 -5.69776e-4 -0.002749979 8.21318e-4 -2.72051e-4 -0.002749979 9.61624e-4 3.76372e-4 -0.002749979 9.25623e-4 2.18762e-4 -0.002749979 9.74972e-4 5.23743e-4 -0.002749979 8.50968e-4 7.71892e-4 -0.002749979 6.34693e-4 6.56771e-4 -0.002749979 7.53094e-4 9.36364e-4 -0.002749979 3.49492e-4 8.65904e-4 -0.002749979 4.98965e-4 9.99296e-4 -0.002749979 2.64943e-5 9.81193e-4 -0.002749979 1.90586e-4 9.53941e-4 -0.002749979 -2.99606e-4 9.90159e-4 -0.002749979 -1.3848e-4 0.007058382 -0.001749992 0.002869188 0.001861691 -0.001749992 -0.007389605 0.001861691 -0.002749979 -0.007389605 0.007058382 -0.002749979 0.002869188 8.91782e-4 -0.001749992 -4.5263e-4 0.007058382 -0.001749992 0.002869188 9.53941e-4 -0.001749992 -2.99606e-4 7.71892e-4 -0.001749992 6.34693e-4 8.65904e-4 -0.001749992 4.98965e-4 0.001861691 -0.001749992 -0.007389605 -0.002160727 -0.001749992 0.007539272 -6.97326e-4 -0.001749992 7.16329e-4 -5.69776e-4 -0.001749992 8.21318e-4 9.99296e-4 -0.001749992 2.64943e-5 9.90159e-4 -0.001749992 -1.3848e-4 9.36364e-4 -0.001749992 3.49492e-4 9.81193e-4 -0.001749992 1.90586e-4 5.23743e-4 -0.001749992 8.50968e-4 6.56771e-4 -0.001749992 7.53094e-4 3.76372e-4 -0.001749992 9.25623e-4 5.51818e-5 -0.001749992 9.97748e-4 2.18762e-4 -0.001749992 9.74972e-4 -2.72051e-4 -0.001749992 9.61624e-4 -1.0991e-4 -0.001749992 9.9327e-4 -4.26742e-4 -0.001749992 9.03785e-4 -8.92385e-4 -0.001749992 4.51155e-4 -8.05847e-4 -0.001749992 5.91829e-4 -0.007357478 -0.001749992 -0.002719521 -7.72497e-4 -0.001749992 -6.36175e-4 -8.66552e-4 -0.001749992 -5.00418e-4 -9.90783e-4 -0.001749992 1.37012e-4 -9.54609e-4 -0.001749992 2.98157e-4 -9.81842e-4 -0.001749992 -1.92039e-4 -9.99928e-4 -0.001749992 -2.78465e-5 -9.36958e-4 -0.001749992 -3.50975e-4 -5.2433e-4 -0.001749992 -8.52458e-4 -6.57359e-4 -0.001749992 -7.54584e-4 -3.76958e-4 -0.001749992 -9.27113e-4 -5.57862e-5 -0.001749992 -9.99231e-4 -2.19351e-4 -0.001749992 -9.76462e-4 2.71456e-4 -0.001749992 -9.63107e-4 1.09262e-4 -0.001749992 -9.94723e-4 5.69143e-4 -0.001749992 -8.22671e-4 4.26093e-4 -0.001749992 -9.05242e-4 8.05179e-4 -0.001749992 -5.93279e-4 6.96702e-4 -0.001749992 -7.17796e-4 -0.01134103 -0.006223976 -7.01647e-4 -0.006822049 -0.006243705 0.00990051 -0.01201879 -0.006243705 -3.58317e-4 -0.01100587 -4.79778e-4 0.01201987 -0.01625585 -0.001249969 0.00178796 -0.01105916 -0.001249969 0.01204681 -0.01067376 -0.00608927 -0.001039624 -0.006144285 -0.006223976 0.009557187 -0.00547707 -0.00608927 0.009219169 -0.01003247 -0.005842804 -0.001364469 -0.009432017 -0.005490243 -0.001668632 -0.004835784 -0.005842804 0.008894324 -0.008886158 -0.00503987 -0.001945137 -0.004235267 -0.005490243 0.008590161 -0.003689467 -0.00503987 0.008313655 -0.008407592 -0.004501998 -0.00218755 -0.008007287 -0.003889262 -0.002390325 -0.003210842 -0.004502058 0.008071243 -0.007694423 -0.003215789 -0.002548813 -0.002810537 -0.003889262 0.007868468 -0.002497673 -0.003215789 0.00770998 -0.007476329 -0.002498209 -0.00265932 -0.007357478 -0.001749992 -0.002719521 -0.002279639 -0.002498209 0.007599472 -0.002160727 -0.001749992 0.007539272 -0.007493674 -0.006148219 0.01024073 -0.008144915 -0.005939841 0.01057058 -0.01269042 -0.006148219 -1.809e-5 -0.008760631 -0.005623281 0.01088249 -0.0133416 -0.005939841 3.11781e-4 -0.01395732 -0.005623281 6.23673e-4 -0.009326577 -0.00520575 0.01116919 -0.009829699 -0.004696905 0.01142406 -0.01452332 -0.00520575 9.10375e-4 -0.01025831 -0.004108369 0.0116412 -0.01502645 -0.004696905 0.001165211 -0.01545506 -0.004108369 0.00138235 -0.01060247 -0.003453731 0.01181554 -0.01085418 -0.002748072 0.01194304 -0.01579922 -0.003453731 0.001556634 -0.0110076 -0.002007782 0.0120207 -0.01605093 -0.002748072 0.001684188 -0.01620429 -0.002007782 0.001761853 -0.01023405 0.001646876 0.01162886 -0.01578527 9.85053e-4 0.001549601 -0.01058852 9.85052e-4 0.01180845 -0.01084786 2.70082e-4 0.01193982 -0.01604461 2.70083e-4 0.00168097 -0.01620262 -4.79777e-4 0.001761019 -0.01447206 0.002749562 8.84403e-4 -0.009275317 0.002749562 0.0111432 -0.008693873 0.003163993 0.0108487 -0.0154308 0.001646876 0.001370012 -0.009792804 0.002239823 0.0114054 -0.01498955 0.002239823 0.001146554 -0.007395863 0.0036695 0.0101912 -0.00671029 0.003748416 0.009843885 -0.01259255 0.0036695 -6.7655e-5 -0.008062362 0.003473103 0.0105288 -0.01325905 0.003473103 2.69968e-4 -0.01389056 0.003163993 5.8987e-4 -0.004705309 0.003276944 0.008828222 -0.01054614 0.003549695 -0.001104295 -0.005349397 0.003549695 0.009154498 -0.01121979 0.003708064 -7.6304e-4 -0.01190704 0.003748416 -4.14927e-4 -0.006023108 0.003708064 0.009495794 -0.008763134 0.00241661 -0.002007484 -0.003566384 0.00241661 0.008251309 -0.003098845 0.001849412 0.0080145 -0.009902 0.003276944 -0.001430571 -0.004106223 0.002896249 0.008524775 -0.009302914 0.002896249 -0.001734018 -0.002714753 0.001208186 0.00781989 -0.008295536 0.001849412 -0.002244293 -0.002423286 5.08262e-4 0.00767225 -0.007911443 0.001208186 -0.002438902 -0.007619976 5.08263e-4 -0.002586543 -0.002231478 -2.33728e-4 0.007575094 -0.002143979 -0.000999987 0.007530748 -0.007428228 -2.33727e-4 -0.002683699 -0.007340669 -0.000999987 -0.002728044 -0.02562159 -7.50007e-4 0.006532251 -0.02562159 -0.001749992 0.006532251 -0.0171293 -0.001749992 0.002230465 -0.01134103 -0.006223976 -7.01647e-4 -0.01075428 -0.007135331 -9.98866e-4 -0.01002991 -0.006914138 -0.00136578 -0.009341239 -0.006581962 -0.001714646 -0.01067376 -0.00608927 -0.001039624 -0.0170198 5.4723e-5 0.002174973 -0.01620262 -4.79777e-4 0.001761019 -0.01604461 2.70083e-4 0.00168097 -0.0171293 -7.50007e-4 0.002230465 -0.01003247 -0.005842804 -0.001364469 -0.008700847 -0.006145298 -0.002039015 -0.01149898 -0.007240712 -6.21613e-4 -0.008120834 -0.005612373 -0.002332806 -0.009432017 -0.005490243 -0.001668632 -0.007612705 -0.004993557 -0.002590179 -0.008886158 -0.00503987 -0.001945137 -0.008407592 -0.004501998 -0.00218755 -0.00718671 -0.004300892 -0.002806007 -0.008007287 -0.003889262 -0.002390325 -0.006851196 -0.003548085 -0.00297594 -0.007694423 -0.003215789 -0.002548813 -0.006612956 -0.002749979 -0.00309664 -0.007476329 -0.002498209 -0.00265932 -0.007357478 -0.001749992 -0.002719521 -0.01605093 -0.002748072 0.001684188 -0.01701444 -0.002581655 0.002172231 -0.01679766 -0.003384411 0.002062439 -0.01579922 -0.003453731 0.001556634 -0.01648241 -0.00414735 0.001902759 0.001861691 -0.002749979 -0.007389605 0.001861691 -0.001749992 -0.007389605 -0.008295536 0.001849412 -0.002244293 -0.007050037 0.001525044 -0.002875208 -0.007428407 0.002219021 -0.002683579 -0.01033616 0.004522562 -0.001210629 -0.01104629 0.004690825 -8.50942e-4 -0.01121979 0.003708064 -7.6304e-4 -0.01625585 -0.001249969 0.00178796 -0.01620429 -0.002007782 0.001761853 -0.01545506 -0.004108369 0.00138235 -0.01607489 -0.004853665 0.001696288 -0.01452332 -0.00520575 9.10375e-4 -0.01558309 -0.005489289 0.0014472 -0.01395732 -0.005623281 6.23673e-4 -0.01501673 -0.006041705 0.001160323 -0.0133416 -0.005939841 3.11781e-4 -0.01269042 -0.006148219 -1.809e-5 -0.01438742 -0.006499469 8.41543e-4 -0.01502645 -0.004696905 0.001165211 -0.01370793 -0.006853759 4.97334e-4 -0.01299053 -0.007098376 1.33943e-4 -0.01224935 -0.007228255 -2.41507e-4 -0.01201879 -0.006243705 -3.58317e-4 -0.01578527 9.85053e-4 0.001549601 -0.01651644 0.001577019 0.001919984 -0.01681423 8.35233e-4 0.002070844 -0.01447206 0.002749562 8.84403e-4 -0.01566892 0.002890706 0.001490712 -0.01498955 0.002239823 0.001146554 -0.01613223 0.002266347 0.001725375 -0.0154308 0.001646876 0.001370012 -0.01388967 0.004271507 5.89393e-4 -0.01325905 0.003473103 2.69968e-4 -0.01259255 0.0036695 -6.7655e-5 -0.01513373 0.003439962 0.00121957 -0.01389056 0.003163993 5.8987e-4 -0.01453679 0.00390321 9.17204e-4 -0.01249414 0.004698514 -1.17511e-4 -0.01190704 0.003748416 -4.14927e-4 -0.01177048 0.004749894 -4.84094e-4 -0.01320451 0.004538178 2.42326e-4 -0.008418262 0.003404796 -0.002182185 -0.009302914 0.002896249 -0.001734018 -0.007887303 0.002849519 -0.002451121 -0.01054614 0.003549695 -0.001104295 -0.009902 0.003276944 -0.001430571 -0.009010195 0.003873467 -0.001882314 -0.00965321 0.004248261 -0.001556575 -0.008763134 0.00241661 -0.002007484 -0.006560444 0 -0.003123223 -0.006759583 7.82823e-4 -0.003022372 -0.007619976 5.08263e-4 -0.002586543 -0.007911443 0.001208186 -0.002438902 0.001861691 -0.000999987 -0.007389605 0.001861691 0 -0.007389605 -0.007340669 -0.000999987 -0.002728044 -0.007428228 -2.33727e-4 -0.002683699 -0.00584954 0.004690825 0.009407877 -0.006573736 0.004749894 0.009774744 -0.01177048 0.004749894 -4.84094e-4 -0.01104629 0.004690825 -8.50942e-4 -0.00513941 0.004522562 0.009048163 -0.01033616 0.004522562 -0.001210629 -0.00445652 0.004248261 0.008702218 -0.003813445 0.003873467 0.008376479 -0.00965321 0.004248261 -0.001556575 -0.009010195 0.003873467 -0.001882314 -0.003221511 0.003404796 0.008076608 -0.008418262 0.003404796 -0.002182185 -0.002690613 0.002849519 0.007807672 -0.002231717 0.002219021 0.007575213 -0.007887303 0.002849519 -0.002451121 -0.007428407 0.002219021 -0.002683579 -0.001853346 0.001525044 0.007383584 -0.007050037 0.001525044 -0.002875208 -0.001562893 7.82822e-4 0.007236421 -0.001363754 0 0.00713557 -0.006759583 7.82823e-4 -0.003022372 -0.006560444 0 -0.003123223 -0.01249414 0.004698514 -1.17511e-4 -0.007297456 0.004698514 0.01014131 -0.008007764 0.004538178 0.01050114 -0.01320451 0.004538178 2.42326e-4 -0.01388967 0.004271507 5.89393e-4 -0.00869292 0.004271507 0.01084822 -0.009340047 0.00390321 0.01117604 -0.01453679 0.00390321 9.17204e-4 -0.009937047 0.003439962 0.01147842 -0.01513373 0.003439962 0.00121957 -0.01566892 0.002890706 0.001490712 -0.01047223 0.002890706 0.01174956 -0.01093548 0.002266347 0.01198422 -0.01613223 0.002266347 0.001725375 -0.01131969 0.001577019 0.01217883 -0.01651644 0.001577019 0.001919984 -0.01681423 8.35233e-4 0.002070844 -0.01161748 8.35232e-4 0.01232969 -0.01182311 5.47219e-5 0.01243382 -0.0170198 5.4723e-5 0.002174973 -0.0171293 -7.50007e-4 0.002230465 -0.01193261 -7.50008e-4 0.01248931 -0.01182311 5.47219e-5 0.01243382 -0.01084786 2.70082e-4 0.01193982 -0.01100587 -4.79778e-4 0.01201987 -0.01058852 9.85052e-4 0.01180845 -0.01131969 0.001577019 0.01217883 -0.01023405 0.001646876 0.01162886 -0.008007764 0.004538178 0.01050114 -0.007395863 0.0036695 0.0101912 -0.00869292 0.004271507 0.01084822 -0.008062362 0.003473103 0.0105288 -0.009340047 0.00390321 0.01117604 -0.008693873 0.003163993 0.0108487 -0.006573736 0.004749894 0.009774744 -0.00584954 0.004690825 0.009407877 -0.00671029 0.003748416 0.009843885 -0.009937047 0.003439962 0.01147842 -0.01047223 0.002890706 0.01174956 -0.009275317 0.002749562 0.0111432 -0.009792804 0.002239823 0.0114054 -0.01093548 0.002266347 0.01198422 -0.003813445 0.003873467 0.008376479 -0.004705309 0.003276944 0.008828222 -0.00445652 0.004248261 0.008702218 -0.01161748 8.35232e-4 0.01232969 -0.01150405 -7.50008e-4 0.01227223 -0.01105916 -0.001249969 0.01204681 -0.01193261 -7.50008e-4 0.01248931 -0.01193261 -0.001749992 0.01248931 -0.01150405 -0.001749992 0.01227223 -0.01181769 -0.002581655 0.01243108 -0.0110076 -0.002007782 0.0120207 -0.01060247 -0.003453731 0.01181554 -0.01128566 -0.00414735 0.01216161 -0.01160097 -0.003384411 0.01232129 -0.001654505 -0.003548085 0.007282853 -0.002810537 -0.003889262 0.007868468 -0.002497673 -0.003215789 0.00770998 -0.006822049 -0.006243705 0.00990051 -0.007052659 -0.007228255 0.01001733 -0.007793843 -0.007098376 0.01039278 -0.00198996 -0.004300892 0.007452785 -0.003210842 -0.004502058 0.008071243 -0.00547707 -0.00608927 0.009219169 -0.004144489 -0.006581962 0.008544147 -0.004833161 -0.006914138 0.008893013 -0.002924084 -0.005612373 0.007925987 -0.003504097 -0.006145298 0.008219778 -0.004235267 -0.005490243 0.008590161 -0.004835784 -0.005842804 0.008894324 -0.006144285 -0.006223976 0.009557187 -0.005557537 -0.007135331 0.009259939 -0.003689467 -0.00503987 0.008313655 -0.002416014 -0.004993557 0.007668614 -0.001416265 -0.002749979 0.007162153 -0.002279639 -0.002498209 0.007599472 -0.0103864 -0.005489289 0.01170605 -0.0108782 -0.004853665 0.01195514 -0.009829699 -0.004696905 0.01142406 -0.002160727 -0.001749992 0.007539272 0.007058382 -0.001749992 0.002869188 0.007058382 -0.002749979 0.002869188 -0.01025831 -0.004108369 0.0116412 -0.001853346 0.001525044 0.007383584 -0.002714753 0.001208186 0.00781989 -0.003098845 0.001849412 0.0080145 -0.009326577 -0.00520575 0.01116919 -0.009820044 -0.006041705 0.01141917 -0.01085418 -0.002748072 0.01194304 -0.008760631 -0.005623281 0.01088249 -0.009190678 -0.006499469 0.01110035 -0.008144915 -0.005939841 0.01057058 -0.008511185 -0.006853759 0.01075613 -0.007493674 -0.006148219 0.01024073 -0.006302297 -0.007240712 0.009637236 -0.001562893 7.82822e-4 0.007236421 -0.003566384 0.00241661 0.008251309 -0.002231717 0.002219021 0.007575213 -0.004106223 0.002896249 0.008524775 -0.002690613 0.002849519 0.007807672 -0.003221511 0.003404796 0.008076608 -0.005349397 0.003549695 0.009154498 -0.00513941 0.004522562 0.009048163 -0.006023108 0.003708064 0.009495794 -0.007297456 0.004698514 0.01014131 -0.001363754 0 0.00713557 -0.002423286 5.08262e-4 0.00767225 -0.002231478 -2.33728e-4 0.007575094 -0.002143979 -0.000999987 0.007530748 0.007058382 0 0.002869188 0.007058382 -0.000999987 0.002869188 0.007058382 0 0.002869188 0.001861691 0 -0.007389605 0.001861691 -0.000999987 -0.007389605 0.007058382 -0.000999987 0.002869188 -9.99954e-4 -0.000999987 -2.80589e-5 -0.007340669 -0.000999987 -0.002728044 -9.908e-4 -0.000999987 1.36912e-4 0.001861691 -0.000999987 -0.007389605 -5.54286e-5 -0.000999987 -9.9919e-4 1.09619e-4 -0.000999987 -9.94686e-4 8.91782e-4 -0.000999987 -4.5263e-4 0.007058382 -0.000999987 0.002869188 6.96791e-4 -0.000999987 -7.17618e-4 8.05179e-4 -0.000999987 -5.93279e-4 4.26361e-4 -0.000999987 -9.05152e-4 5.69323e-4 -0.000999987 -8.22537e-4 2.71722e-4 -0.000999987 -9.63017e-4 -3.76646e-4 -0.000999987 -9.27158e-4 -2.19038e-4 -0.000999987 -9.76507e-4 -5.24062e-4 -0.000999987 -8.52596e-4 -7.7231e-4 -0.000999987 -6.3638e-4 -6.57092e-4 -0.000999987 -7.54718e-4 -9.36897e-4 -0.000999987 -3.51232e-4 -8.6641e-4 -0.000999987 -5.00601e-4 -9.8178e-4 -0.000999987 -1.92184e-4 -8.92385e-4 -0.000999987 4.51155e-4 -9.546e-4 -0.000999987 2.98154e-4 -0.002143979 -0.000999987 0.007530748 5.51818e-5 -0.000999987 9.97748e-4 -1.0991e-4 -0.000999987 9.9327e-4 -6.97326e-4 -0.000999987 7.16329e-4 -8.05847e-4 -0.000999987 5.91829e-4 -4.26742e-4 -0.000999987 9.03785e-4 -5.69776e-4 -0.000999987 8.21318e-4 -2.72051e-4 -0.000999987 9.61624e-4 3.76372e-4 -0.000999987 9.25623e-4 2.18762e-4 -0.000999987 9.74972e-4 5.23743e-4 -0.000999987 8.50968e-4 7.71892e-4 -0.000999987 6.34693e-4 6.56771e-4 -0.000999987 7.53094e-4 9.36364e-4 -0.000999987 3.49492e-4 8.65904e-4 -0.000999987 4.98965e-4 9.99296e-4 -0.000999987 2.64943e-5 9.81193e-4 -0.000999987 1.90586e-4 9.53941e-4 -0.000999987 -2.99606e-4 9.90159e-4 -0.000999987 -1.3848e-4 8.91782e-4 0 -4.5263e-4 0.007058382 0 0.002869188 9.53941e-4 0 -2.99606e-4 7.71892e-4 0 6.34693e-4 8.65904e-4 0 4.98965e-4 0.001861691 0 -0.007389605 -6.97326e-4 0 7.16329e-4 -0.001363754 0 0.00713557 -8.05847e-4 0 5.91829e-4 9.99296e-4 0 2.64943e-5 9.90159e-4 0 -1.3848e-4 9.36364e-4 0 3.49492e-4 9.81193e-4 0 1.90586e-4 5.23743e-4 0 8.50968e-4 6.56771e-4 0 7.53094e-4 3.76372e-4 0 9.25623e-4 5.51818e-5 0 9.97748e-4 2.18762e-4 0 9.74972e-4 -2.72051e-4 0 9.61624e-4 -1.0991e-4 0 9.9327e-4 -5.69776e-4 0 8.21318e-4 -4.26742e-4 0 9.03785e-4 -8.92385e-4 0 4.51155e-4 -0.006560444 0 -0.003123223 -9.90729e-4 0 1.3721e-4 -9.546e-4 0 2.98154e-4 -8.66694e-4 0 -5.00124e-4 -7.72675e-4 0 -6.35862e-4 -9.81868e-4 0 -1.918e-4 -9.99908e-4 0 -2.76305e-5 -9.3704e-4 0 -3.5071e-4 -5.24553e-4 0 -8.52235e-4 -6.57582e-4 0 -7.5436e-4 -3.77316e-4 0 -9.2693e-4 -5.60991e-5 0 -9.99182e-4 -2.19618e-4 0 -9.76324e-4 2.71186e-4 0 -9.63196e-4 1.09038e-4 0 -9.94723e-4 5.69054e-4 0 -8.2285e-4 4.2596e-4 0 -9.05286e-4 8.05179e-4 0 -5.93279e-4 6.96657e-4 0 -7.17886e-4 -8.05847e-4 -0.000999987 5.91829e-4 -8.92385e-4 0 4.51155e-4 -8.92385e-4 -0.000999987 4.51155e-4 -4.26742e-4 -0.000999987 9.03785e-4 -5.69776e-4 0 8.21318e-4 -5.69776e-4 -0.000999987 8.21318e-4 -6.97326e-4 -0.000999987 7.16329e-4 -6.97326e-4 0 7.16329e-4 -8.05847e-4 0 5.91829e-4 -1.0991e-4 0 9.9327e-4 -1.0991e-4 -0.000999987 9.9327e-4 5.51818e-5 -0.000999987 9.97748e-4 -4.26742e-4 0 9.03785e-4 -2.72051e-4 -0.000999987 9.61624e-4 -2.72051e-4 0 9.61624e-4 3.76372e-4 -0.000999987 9.25623e-4 5.23743e-4 -0.000999987 8.50968e-4 3.76372e-4 0 9.25623e-4 2.18762e-4 -0.000999987 9.74972e-4 2.18762e-4 0 9.74972e-4 5.51818e-5 0 9.97748e-4 8.65904e-4 -0.000999987 4.98965e-4 7.71892e-4 0 6.34693e-4 7.71892e-4 -0.000999987 6.34693e-4 6.56771e-4 0 7.53094e-4 5.23743e-4 0 8.50968e-4 6.56771e-4 -0.000999987 7.53094e-4 9.81193e-4 0 1.90586e-4 9.81193e-4 -0.000999987 1.90586e-4 9.99296e-4 -0.000999987 2.64943e-5 8.65904e-4 0 4.98965e-4 9.36364e-4 -0.000999987 3.49492e-4 9.36364e-4 0 3.49492e-4 9.53941e-4 -0.000999987 -2.99606e-4 8.91782e-4 -0.000999987 -4.5263e-4 9.53941e-4 0 -2.99606e-4 9.90159e-4 -0.000999987 -1.3848e-4 9.90159e-4 0 -1.3848e-4 9.99296e-4 0 2.64943e-5 5.69323e-4 -0.000999987 -8.22537e-4 6.96657e-4 0 -7.17886e-4 6.96791e-4 -0.000999987 -7.17618e-4 8.05179e-4 0 -5.93279e-4 8.91782e-4 0 -4.5263e-4 8.05179e-4 -0.000999987 -5.93279e-4 2.71186e-4 0 -9.63196e-4 2.71722e-4 -0.000999987 -9.63017e-4 1.09619e-4 -0.000999987 -9.94686e-4 5.69054e-4 0 -8.2285e-4 4.26361e-4 -0.000999987 -9.05152e-4 4.2596e-4 0 -9.05286e-4 -2.19038e-4 -0.000999987 -9.76507e-4 -3.76646e-4 -0.000999987 -9.27158e-4 -2.19618e-4 0 -9.76324e-4 -5.54286e-5 -0.000999987 -9.9919e-4 -5.60991e-5 0 -9.99182e-4 1.09038e-4 0 -9.94723e-4 -5.24062e-4 -0.000999987 -8.52596e-4 -6.57092e-4 -0.000999987 -7.54718e-4 -5.24553e-4 0 -8.52235e-4 -3.77316e-4 0 -9.2693e-4 -6.57582e-4 0 -7.5436e-4 -7.7231e-4 -0.000999987 -6.3638e-4 -8.6641e-4 -0.000999987 -5.00601e-4 -7.72675e-4 0 -6.35862e-4 -9.36897e-4 -0.000999987 -3.51232e-4 -8.66694e-4 0 -5.00124e-4 -9.3704e-4 0 -3.5071e-4 -9.8178e-4 -0.000999987 -1.92184e-4 -9.99954e-4 -0.000999987 -2.80589e-5 -9.81868e-4 0 -1.918e-4 -9.908e-4 -0.000999987 1.36912e-4 -9.99908e-4 0 -2.76305e-5 -9.90729e-4 0 1.3721e-4 -9.546e-4 -0.000999987 2.98154e-4 -9.546e-4 0 2.98154e-4 -0.001178562 -0.004750013 0.001269102 -0.001688361 -0.004750013 -3.86211e-4 0.001688539 -0.004750013 3.86122e-4 0.001178741 -0.004750013 -0.001269161 5.09885e-4 -0.004750013 0.00165528 -5.09707e-4 -0.004750013 -0.00165534 0.001688539 -0.00575006 3.86122e-4 5.09885e-4 -0.004750013 0.00165528 0.001688539 -0.004750013 3.86122e-4 5.09885e-4 -0.00575006 0.00165528 0.001178741 -0.00575006 -0.001269161 0.001688539 -0.004750013 3.86122e-4 0.001178741 -0.004750013 -0.001269161 0.001688539 -0.00575006 3.86122e-4 -5.09708e-4 -0.00575006 -0.00165534 0.001178741 -0.004750013 -0.001269161 -5.09707e-4 -0.004750013 -0.00165534 0.001178741 -0.00575006 -0.001269161 -0.001688361 -0.00575006 -3.86211e-4 -5.09707e-4 -0.004750013 -0.00165534 -0.001688361 -0.004750013 -3.86211e-4 -5.09708e-4 -0.00575006 -0.00165534 -0.001178562 -0.00575006 0.001269102 -0.001688361 -0.004750013 -3.86211e-4 -0.001178562 -0.004750013 0.001269102 -0.001688361 -0.00575006 -3.86211e-4 5.09885e-4 -0.00575006 0.00165528 -0.001178562 -0.004750013 0.001269102 5.09885e-4 -0.004750013 0.00165528 -0.001178562 -0.00575006 0.001269102 -0.002385795 -0.00575006 7.4652e-4 -0.001178562 -0.00575006 0.001269102 -0.002230346 -0.00575006 0.00112909 0.001930475 -0.00575006 0.001588463 5.09885e-4 -0.00575006 0.00165528 0.001688539 -0.00575006 3.86122e-4 -0.002013981 -0.00575006 0.001480877 -0.001688361 -0.00575006 -3.86211e-4 -0.00174272 -0.00575006 0.001792252 -0.002476096 -0.00575006 3.43572e-4 -0.002498865 -0.00575006 -6.87346e-5 -0.002453505 -0.00575006 -4.79146e-4 -0.001423835 -0.00575006 0.00205475 -0.002341151 -0.00575006 -8.76469e-4 -0.001066148 -0.00575006 0.002261161 -6.79314e-4 -0.00575006 0.002405822 5.47774e-4 -0.00575006 0.0024392 1.38812e-4 -0.00575006 0.002496063 -2.73932e-4 -0.00575006 0.002484858 0.001642704 -0.00575006 0.00188452 -5.09708e-4 -0.00575006 -0.00165534 -0.001309335 -0.00575006 -0.002129554 -9.41098e-4 -0.00575006 -0.002315998 0.002341687 -0.00575006 8.75607e-4 0.002165615 -0.00575006 0.001249074 6.79379e-4 -0.00575006 -0.002405941 2.7411e-4 -0.00575006 -0.002484977 0.002476215 -0.00575006 -3.44425e-4 0.002499163 -0.00575006 6.78361e-5 0.001178741 -0.00575006 -0.001269161 0.001423776 -0.00575006 -0.002055048 0.001742601 -0.00575006 -0.001792669 0.002385795 -0.00575006 -7.47293e-4 0.002230226 -0.00575006 -0.001129746 0.002013862 -0.00575006 -0.001481413 0.002453863 -0.00575006 4.78244e-4 -1.38751e-4 -0.00575006 -0.002496123 0.00131011 -0.00575006 0.002129197 9.41796e-4 -0.00575006 0.002315759 -5.47202e-4 -0.00575006 -0.00243932 -0.001929759 -0.00575006 -0.001589119 -0.001641929 -0.00575006 -0.001885056 -0.002164959 -0.00575006 -0.001249849 0.001066088 -0.00575006 -0.00226134 -0.002453505 -0.003750026 -4.79146e-4 -0.002498865 -0.00575006 -6.87346e-5 -0.002498865 -0.003750026 -6.87346e-5 2.7411e-4 -0.00575006 -0.002484977 2.7411e-4 -0.003750026 -0.002484977 6.7938e-4 -0.003750026 -0.002405941 -0.002476096 -0.003750026 3.43572e-4 -0.002476096 -0.00575006 3.43572e-4 -0.002385795 -0.00575006 7.4652e-4 -0.002385795 -0.003750026 7.4652e-4 -0.002230346 -0.00575006 0.00112909 -0.002230346 -0.003750026 0.00112909 -0.002013981 -0.003750026 0.001480877 -0.002013981 -0.00575006 0.001480877 -0.00174272 -0.00575006 0.001792252 -0.00174272 -0.003750026 0.001792252 -0.001423835 -0.00575006 0.00205475 -0.001423835 -0.003750026 0.00205475 -0.001066148 -0.003750026 0.002261161 -0.001066148 -0.00575006 0.002261161 -6.79314e-4 -0.00575006 0.002405822 -6.79313e-4 -0.003750026 0.002405822 -2.73932e-4 -0.00575006 0.002484858 -2.73932e-4 -0.003750026 0.002484858 -0.002453505 -0.00575006 -4.79146e-4 -0.002341151 -0.003750026 -8.76469e-4 -0.002341151 -0.00575006 -8.76469e-4 -0.002164959 -0.003750026 -0.001249849 -0.002164959 -0.00575006 -0.001249849 -0.001929759 -0.00575006 -0.001589119 -0.001929759 -0.003750026 -0.001589119 -0.001641929 -0.003750026 -0.001885056 -0.001641929 -0.00575006 -0.001885056 -0.001309335 -0.003750026 -0.002129554 -0.001309335 -0.00575006 -0.002129554 -9.41098e-4 -0.00575006 -0.002315998 -9.41098e-4 -0.003750026 -0.002315998 -5.47202e-4 -0.003750026 -0.00243932 -5.47202e-4 -0.00575006 -0.00243932 -1.38751e-4 -0.003750026 -0.002496123 -1.38751e-4 -0.00575006 -0.002496123 0.001066088 -0.00575006 -0.00226134 6.79379e-4 -0.00575006 -0.002405941 0.001066088 -0.003750026 -0.00226134 0.002013862 -0.00575006 -0.001481413 0.001742601 -0.00575006 -0.001792669 0.002013862 -0.003750026 -0.001481413 0.001423776 -0.00575006 -0.002055048 0.001423776 -0.003750026 -0.002055048 0.001742601 -0.003750026 -0.001792669 0.002385795 -0.00575006 -7.47293e-4 0.002476215 -0.003750026 -3.44425e-4 0.002476215 -0.00575006 -3.44425e-4 0.002230226 -0.003750026 -0.001129746 0.002385795 -0.003750026 -7.47293e-4 0.002230226 -0.00575006 -0.001129746 0.002341687 -0.003750026 8.75607e-4 0.002341687 -0.00575006 8.75607e-4 0.002453863 -0.00575006 4.78244e-4 0.002453863 -0.003750026 4.78244e-4 0.002499163 -0.00575006 6.78361e-5 0.002499163 -0.003750026 6.7836e-5 0.001642704 -0.00575006 0.00188452 0.001930475 -0.00575006 0.001588463 0.001642704 -0.003750026 0.00188452 0.002165615 -0.00575006 0.001249074 0.002165615 -0.003750026 0.001249074 0.001930475 -0.003750026 0.001588463 9.41796e-4 -0.003750026 0.002315759 0.00131011 -0.00575006 0.002129197 0.00131011 -0.003750026 0.002129197 5.47774e-4 -0.003750026 0.0024392 9.41796e-4 -0.00575006 0.002315759 5.47774e-4 -0.00575006 0.0024392 1.38813e-4 -0.003750026 0.002496063 1.38812e-4 -0.00575006 0.002496063 0.001784205 -0.003750026 -9.03833e-4 0.002013862 -0.003750026 -0.001481413 0.001611113 -0.003750026 -0.001185119 0.001963138 -0.003750026 3.82587e-4 0.001873373 -0.003750026 7.00477e-4 0.002453863 -0.003750026 4.78244e-4 0.001732528 -0.003750026 9.99259e-4 0.002341687 -0.003750026 8.75607e-4 0.002499163 -0.003750026 6.7836e-5 0.001999318 -0.003750026 5.42595e-5 0.002165615 -0.003750026 0.001249074 0.001544415 -0.003750026 0.001270771 0.002476215 -0.003750026 -3.44425e-4 0.001981019 -0.003750026 -2.75549e-4 0.001930475 -0.003750026 0.001588463 0.001314163 -0.003750026 0.00150758 0.001908659 -0.003750026 -5.97842e-4 0.002385795 -0.003750026 -7.47293e-4 0.00131011 -0.003750026 0.002129197 0.001642704 -0.003750026 0.00188452 0.002230226 -0.003750026 -0.001129746 9.41796e-4 -0.003750026 0.002315759 0.001048088 -0.003750026 0.001703321 0.001066088 -0.003750026 -0.00226134 8.52914e-4 -0.003750026 -0.00180906 0.001423776 -0.003750026 -0.002055048 1.11068e-4 -0.003750026 0.001996815 -2.73932e-4 -0.003750026 0.002484858 1.38813e-4 -0.003750026 0.002496063 -0.002230346 -0.003750026 0.00112909 -0.001784205 -0.003750026 9.03278e-4 -0.0019086 -0.003750026 5.97208e-4 2.19306e-4 -0.003750026 -0.001987993 5.43522e-4 -0.003750026 -0.001924753 6.7938e-4 -0.003750026 -0.002405941 -0.00199908 -0.003750026 -5.4996e-5 -0.00196278 -0.003750026 -3.83327e-4 -0.002498865 -0.003750026 -6.87346e-5 -0.001047432 -0.003750026 -0.001703679 -9.41098e-4 -0.003750026 -0.002315998 -0.001309335 -0.003750026 -0.002129554 -0.001872897 -0.003750026 -7.01183e-4 -0.002453505 -0.003750026 -4.79146e-4 -0.002341151 -0.003750026 -8.76469e-4 -0.001731932 -0.003750026 -9.999e-4 -0.001313507 -0.003750026 -0.001508057 -0.001641929 -0.003750026 -0.001885056 -0.001929759 -0.003750026 -0.001589119 -0.00154376 -0.003750026 -0.001271307 -0.002164959 -0.003750026 -0.001249849 -0.001980841 -0.003750026 2.74848e-4 -0.002476096 -0.003750026 3.43572e-4 -5.47202e-4 -0.003750026 -0.00243932 -7.52858e-4 -0.003750026 -0.00185281 -4.37744e-4 -0.003750026 -0.001951456 -0.002385795 -0.003750026 7.4652e-4 2.7411e-4 -0.003750026 -0.002484977 -1.10982e-4 -0.003750026 -0.001996934 -1.38751e-4 -0.003750026 -0.002496123 -0.00174272 -0.003750026 0.001792252 -0.001423835 -0.003750026 0.00205475 -0.001139044 -0.003750026 0.001643776 -0.001066148 -0.003750026 0.002261161 -5.43434e-4 -0.003750026 0.001924633 -8.52901e-4 -0.003750026 0.001808881 0.001139044 -0.003750026 -0.001644015 0.001742601 -0.003750026 -0.001792669 -2.19128e-4 -0.003750026 0.001987874 -6.79313e-4 -0.003750026 0.002405822 4.38237e-4 -0.003750026 0.001951336 5.47774e-4 -0.003750026 0.0024392 0.001394093 -0.003750026 -0.001434147 7.53453e-4 -0.003750026 0.001852631 -0.002013981 -0.003750026 0.001480877 -0.001611173 -0.003750026 0.001184701 -0.001394152 -0.003750026 0.001433789 0.001963138 -0.002750039 3.82587e-4 0.001963138 -0.003750026 3.82587e-4 0.001999318 -0.003750026 5.42595e-5 -1.10982e-4 -0.003750026 -0.001996934 2.19306e-4 -0.002750039 -0.001987993 2.19306e-4 -0.003750026 -0.001987993 0.001873373 -0.002750039 7.00477e-4 0.001873373 -0.003750026 7.00477e-4 0.001732528 -0.003750026 9.99259e-4 0.001732528 -0.002750039 9.99259e-4 0.001544415 -0.002750039 0.001270771 0.001544415 -0.003750026 0.001270771 0.001314163 -0.002750039 0.00150758 0.001314163 -0.003750026 0.00150758 0.001048088 -0.003750026 0.001703321 0.001048088 -0.002750039 0.001703321 7.53454e-4 -0.002750039 0.001852631 7.53453e-4 -0.003750026 0.001852631 4.38237e-4 -0.002750039 0.001951336 4.38237e-4 -0.003750026 0.001951336 1.11068e-4 -0.003750026 0.001996815 1.11068e-4 -0.002750039 0.001996815 -2.19127e-4 -0.002750039 0.001987874 -2.19128e-4 -0.003750026 0.001987874 0.001999318 -0.002750039 5.42595e-5 0.001981019 -0.003750026 -2.75549e-4 0.001981019 -0.002750039 -2.75549e-4 0.001908659 -0.003750026 -5.97842e-4 0.001908659 -0.002750039 -5.97842e-4 0.001784205 -0.002750039 -9.03833e-4 0.001784205 -0.003750026 -9.03833e-4 0.001611113 -0.003750026 -0.001185119 0.001611113 -0.002750039 -0.001185119 0.001394093 -0.003750026 -0.001434147 0.001394093 -0.002750039 -0.001434147 0.001139044 -0.002750039 -0.001644015 0.001139044 -0.003750026 -0.001644015 8.52914e-4 -0.003750026 -0.00180906 8.52915e-4 -0.002750039 -0.00180906 5.43522e-4 -0.003750026 -0.001924753 5.43522e-4 -0.002750039 -0.001924753 -0.001047432 -0.003750026 -0.001703679 -7.53275e-4 -0.002750039 -0.001852691 -7.52858e-4 -0.003750026 -0.00185281 -4.37744e-4 -0.003750026 -0.001951456 -4.38058e-4 -0.002750039 -0.001951456 -1.10889e-4 -0.002750039 -0.001996934 -0.001544237 -0.002750039 -0.00127083 -0.00154376 -0.003750026 -0.001271307 -0.001731932 -0.003750026 -9.999e-4 -0.001047909 -0.002750039 -0.001703441 -0.001313507 -0.003750026 -0.001508057 -0.001313984 -0.002750039 -0.001507699 -0.00196278 -0.003750026 -3.83327e-4 -0.00199908 -0.003750026 -5.4996e-5 -0.001962959 -0.002750039 -3.82677e-4 -0.001872897 -0.003750026 -7.01183e-4 -0.001873195 -0.002750039 -7.00566e-4 -0.001732349 -0.002750039 -9.99348e-4 -0.001784205 -0.003750026 9.03278e-4 -0.001908481 -0.002750039 5.97752e-4 -0.0019086 -0.003750026 5.97208e-4 -0.001980841 -0.002750039 2.75459e-4 -0.001999139 -0.002750039 -5.43489e-5 -0.001980841 -0.003750026 2.74848e-4 -0.001393914 -0.002750039 0.001434028 -0.001610934 -0.002750039 0.001185059 -0.001394152 -0.003750026 0.001433789 -0.001784026 -0.002750039 9.03744e-4 -0.001611173 -0.003750026 0.001184701 -0.001139044 -0.003750026 0.001643776 -0.001138865 -0.002750039 0.001643955 -8.52901e-4 -0.003750026 0.001808881 -8.52736e-4 -0.002750039 0.001809 -5.43343e-4 -0.002750039 0.001924693 -5.43434e-4 -0.003750026 0.001924633 5.24105e-4 -0.002750039 8.51664e-4 0.001048088 -0.002750039 0.001703321 6.57145e-4 -0.002750039 7.53798e-4 0.001999318 -0.002750039 5.42595e-5 0.001981019 -0.002750039 -2.75549e-4 9.90556e-4 -0.002750039 -1.37796e-4 0.001963138 -0.002750039 3.82587e-4 9.9972e-4 -0.002750039 2.71075e-5 0.001908659 -0.002750039 -5.97842e-4 8.92163e-4 -0.002750039 -4.51937e-4 9.54374e-4 -0.002750039 -2.98943e-4 9.81618e-4 -0.002750039 1.91271e-4 9.36742e-4 -0.002750039 3.50215e-4 0.001873373 -0.002750039 7.00477e-4 0.001611113 -0.002750039 -0.001185119 8.05617e-4 -0.002750039 -5.92604e-4 8.66316e-4 -0.002750039 4.99606e-4 0.001732528 -0.002750039 9.99259e-4 0.001139044 -0.002750039 -0.001644015 6.97098e-4 -0.002750039 -7.17108e-4 0.001394093 -0.002750039 -0.001434147 7.72262e-4 -0.002750039 6.35368e-4 0.001544415 -0.002750039 0.001270771 5.69567e-4 -0.002750039 -8.22052e-4 8.52915e-4 -0.002750039 -0.00180906 4.26502e-4 -0.002750039 -9.04573e-4 0.001314163 -0.002750039 0.00150758 -5.5446e-5 -0.002750039 -9.985e-4 -1.10889e-4 -0.002750039 -0.001996934 -4.38058e-4 -0.002750039 -0.001951456 3.76771e-4 -0.002750039 9.26298e-4 7.53454e-4 -0.002750039 0.001852631 -2.19127e-4 -0.002750039 0.001987874 -2.71671e-4 -0.002750039 9.62319e-4 -5.43343e-4 -0.002750039 0.001924693 -0.001138865 -0.002750039 0.001643955 -6.97043e-4 -0.002750039 7.1689e-4 -0.001393914 -0.002750039 0.001434028 -2.18827e-4 -0.002750039 -9.75769e-4 -7.53275e-4 -0.002750039 -0.001852691 -3.76385e-4 -0.002750039 -9.26446e-4 -9.54267e-4 -0.002750039 2.98581e-4 -0.001908481 -0.002750039 5.97752e-4 -8.92087e-4 -0.002750039 4.51618e-4 -6.56724e-4 -0.002750039 -7.5406e-4 -0.001313984 -0.002750039 -0.001507699 -7.71857e-4 -0.002750039 -6.35687e-4 -9.99513e-4 -0.002750039 -2.75206e-5 -9.81353e-4 -0.002750039 -1.91686e-4 -0.001962959 -0.002750039 -3.82677e-4 -9.3642e-4 -0.002750039 -3.50614e-4 -0.001873195 -0.002750039 -7.00566e-4 -0.001980841 -0.002750039 2.75459e-4 -9.90403e-4 -0.002750039 1.37402e-4 -0.001999139 -0.002750039 -5.43489e-5 -8.65945e-4 -0.002750039 -4.99972e-4 -0.001732349 -0.002750039 -9.99348e-4 -0.001784026 -0.002750039 9.03744e-4 -0.001610934 -0.002750039 0.001185059 -0.001544237 -0.002750039 -0.00127083 -5.2369e-4 -0.002750039 -8.51867e-4 -0.001047909 -0.002750039 -0.001703441 -8.0556e-4 -0.002750039 5.92335e-4 -8.52736e-4 -0.002750039 0.001809 -5.69499e-4 -0.002750039 8.21882e-4 -4.26406e-4 -0.002750039 9.04443e-4 1.11068e-4 -0.002750039 0.001996815 -1.09519e-4 -0.002750039 9.9393e-4 2.19306e-4 -0.002750039 -0.001987993 1.09698e-4 -0.002750039 -9.94019e-4 5.55792e-5 -0.002750039 9.98414e-4 4.38237e-4 -0.002750039 0.001951336 2.71806e-4 -0.002750039 -9.62421e-4 5.43522e-4 -0.002750039 -0.001924753 2.19163e-4 -0.002750039 9.75663e-4 0.001784205 -0.002750039 -9.03833e-4 -6.57123e-4 0.00424987 -7.53739e-4 -7.72233e-4 0.00424987 -6.35257e-4 -8.66265e-4 0.00424987 -4.99446e-4 9.54375e-4 0.00424987 -2.98943e-4 8.92164e-4 0.00424987 -4.51937e-4 -2.7167e-4 0.00424987 9.62319e-4 -9.36653e-4 0.00424987 -3.50013e-4 -5.24074e-4 0.00424987 -8.51656e-4 -9.8148e-4 0.00424987 -1.91038e-4 -3.76717e-4 0.00424987 -9.26333e-4 -2.19072e-4 0.00424987 -9.75731e-4 -9.99527e-4 0.00424987 -2.68608e-5 -5.54447e-5 0.00424987 -9.98501e-4 -9.90304e-4 0.00424987 1.38039e-4 1.09699e-4 0.00424987 -9.9402e-4 -9.54067e-4 0.00424987 2.99165e-4 -8.91811e-4 0.00424987 4.5212e-4 2.71808e-4 0.00424987 -9.62422e-4 -5.69197e-4 0.00424987 8.22064e-4 6.971e-4 0.00424987 -7.17108e-4 -6.96712e-4 0.00424987 7.17181e-4 5.69568e-4 0.00424987 -8.22052e-4 4.26503e-4 0.00424987 -9.04573e-4 -8.05237e-4 0.00424987 5.92736e-4 -1.09518e-4 0.00424987 9.9393e-4 8.05618e-4 0.00424987 -5.92604e-4 -4.26172e-4 0.00424987 9.04534e-4 2.19164e-4 0.00424987 9.75663e-4 3.76772e-4 0.00424987 9.26298e-4 9.81619e-4 0.00424987 1.91271e-4 5.55805e-5 0.00424987 9.98414e-4 9.99722e-4 0.00424987 2.71072e-5 9.90557e-4 0.00424987 -1.37796e-4 8.66317e-4 0.00424987 4.99606e-4 6.57146e-4 0.00424987 7.53798e-4 7.72264e-4 0.00424987 6.35368e-4 5.24107e-4 0.00424987 8.51664e-4 9.36743e-4 0.00424987 3.50215e-4 9.9972e-4 -0.002750039 2.71075e-5 9.99722e-4 0.00424987 2.71072e-5 9.81619e-4 0.00424987 1.91271e-4 -2.7167e-4 0.00424987 9.62319e-4 -1.09519e-4 -0.002750039 9.9393e-4 -1.09518e-4 0.00424987 9.9393e-4 9.90556e-4 -0.002750039 -1.37796e-4 9.90557e-4 0.00424987 -1.37796e-4 9.54375e-4 0.00424987 -2.98943e-4 9.54374e-4 -0.002750039 -2.98943e-4 8.92163e-4 -0.002750039 -4.51937e-4 8.92164e-4 0.00424987 -4.51937e-4 8.05617e-4 -0.002750039 -5.92604e-4 8.05618e-4 0.00424987 -5.92604e-4 6.971e-4 0.00424987 -7.17108e-4 6.97098e-4 -0.002750039 -7.17108e-4 5.69567e-4 -0.002750039 -8.22052e-4 5.69568e-4 0.00424987 -8.22052e-4 4.26502e-4 -0.002750039 -9.04573e-4 4.26503e-4 0.00424987 -9.04573e-4 2.71808e-4 0.00424987 -9.62422e-4 2.71806e-4 -0.002750039 -9.62421e-4 1.09698e-4 -0.002750039 -9.94019e-4 1.09699e-4 0.00424987 -9.9402e-4 9.81618e-4 -0.002750039 1.91271e-4 9.36743e-4 0.00424987 3.50215e-4 9.36742e-4 -0.002750039 3.50215e-4 8.66317e-4 0.00424987 4.99606e-4 8.66316e-4 -0.002750039 4.99606e-4 7.72262e-4 -0.002750039 6.35368e-4 7.72264e-4 0.00424987 6.35368e-4 6.57146e-4 0.00424987 7.53798e-4 6.57145e-4 -0.002750039 7.53798e-4 5.24107e-4 0.00424987 8.51664e-4 5.24105e-4 -0.002750039 8.51664e-4 3.76771e-4 -0.002750039 9.26298e-4 3.76772e-4 0.00424987 9.26298e-4 2.19164e-4 0.00424987 9.75663e-4 2.19163e-4 -0.002750039 9.75663e-4 5.55805e-5 0.00424987 9.98414e-4 5.55792e-5 -0.002750039 9.98414e-4 -6.96712e-4 0.00424987 7.17181e-4 -5.69499e-4 -0.002750039 8.21882e-4 -5.69197e-4 0.00424987 8.22064e-4 -4.26172e-4 0.00424987 9.04534e-4 -4.26406e-4 -0.002750039 9.04443e-4 -2.71671e-4 -0.002750039 9.62319e-4 -8.92087e-4 -0.002750039 4.51618e-4 -8.91811e-4 0.00424987 4.5212e-4 -9.54067e-4 0.00424987 2.99165e-4 -6.97043e-4 -0.002750039 7.1689e-4 -8.05237e-4 0.00424987 5.92736e-4 -8.0556e-4 -0.002750039 5.92335e-4 -9.99527e-4 0.00424987 -2.68608e-5 -9.8148e-4 0.00424987 -1.91038e-4 -9.99513e-4 -0.002750039 -2.75206e-5 -9.90304e-4 0.00424987 1.38039e-4 -9.90403e-4 -0.002750039 1.37402e-4 -9.54267e-4 -0.002750039 2.98581e-4 -7.72233e-4 0.00424987 -6.35257e-4 -8.65945e-4 -0.002750039 -4.99972e-4 -8.66265e-4 0.00424987 -4.99446e-4 -9.3642e-4 -0.002750039 -3.50614e-4 -9.81353e-4 -0.002750039 -1.91686e-4 -9.36653e-4 0.00424987 -3.50013e-4 -5.2369e-4 -0.002750039 -8.51867e-4 -6.56724e-4 -0.002750039 -7.5406e-4 -5.24074e-4 0.00424987 -8.51656e-4 -7.71857e-4 -0.002750039 -6.35687e-4 -6.57123e-4 0.00424987 -7.53739e-4 -3.76717e-4 0.00424987 -9.26333e-4 -3.76385e-4 -0.002750039 -9.26446e-4 -2.19072e-4 0.00424987 -9.75731e-4 -2.18827e-4 -0.002750039 -9.75769e-4 -5.5446e-5 -0.002750039 -9.985e-4 -5.54447e-5 0.00424987 -9.98501e-4 0.01612603 -5.91658e-4 0.04591822 0.01706683 -0.001250028 0.04544168 0.01617473 -0.001250028 0.0458936 0.01598143 4.87617e-5 0.04599148 0.01686841 2.24392e-4 0.04554218 0.01701694 -5.04478e-4 0.04546695 0.00858736 9.18151e-4 0.04973703 0.00892049 0.001565277 0.04956829 0.009790539 0.001206755 0.04912757 0.01502317 0.001692831 0.0464769 0.01455813 0.002098619 0.04671251 0.01587527 0.002151727 0.0460453 0.01629114 0.001567482 0.0458346 0.01662468 9.20252e-4 0.04566562 0.0154224 0.001206755 0.04627472 0.0153864 0.002659916 0.0462929 0.01403981 0.002413034 0.04697501 0.01483547 0.003080666 0.04657196 0.01359826 0.003624677 0.04719871 0.01348239 0.002627551 0.04725742 0.01290112 0.00273627 0.04755187 0.01423496 0.003404617 0.04687619 0.01293945 0.003735959 0.04753243 0.01231181 0.00273627 0.04785037 0.01161348 0.003624439 0.04820412 0.01227301 0.003735959 0.04787003 0.01173055 0.002627551 0.04814481 0.01117306 0.002413034 0.04842722 0.01037544 0.003079473 0.04883128 0.01097619 0.003403961 0.04852694 0.009335935 0.002149701 0.04935783 0.01018971 0.001692831 0.04892534 0.009824573 0.002658188 0.04911029 0.01065474 0.002098619 0.04868978 0.008195936 -5.04479e-4 0.04993534 0.008343994 2.22711e-4 0.04986029 0.009231448 4.87613e-5 0.04941076 0.009468197 6.53751e-4 0.04929083 0.009086847 -5.91659e-4 0.04948401 0.008146047 -0.001250028 0.04996055 0.00903815 -0.001250028 0.04950869 0.01574468 6.53752e-4 0.04611146 -0.01727217 7.49958e-4 0.2365887 -0.01393938 0.003658115 0.2349004 -0.01352095 0.003497242 0.2346885 -0.01567089 0.003497242 0.2357775 -0.01670837 0.002592563 0.236303 -0.01640862 0.002957105 0.2361512 -0.01605981 0.003261446 0.2359745 -0.01525336 0.003658115 0.235566 -0.01695013 0.002177774 0.2364255 -0.01712763 0.001724004 0.2365154 -0.01481717 0.003739655 0.235345 -0.01437556 0.003739655 0.2351214 -0.01723557 0.00124371 0.2365701 -0.01695013 -6.78242e-4 0.2364255 -0.01712763 -2.24402e-4 0.2365154 -0.01278322 0.002957105 0.2343147 -0.01313203 0.003261446 0.2344914 -0.01723557 2.56038e-4 0.2365701 -0.01248437 0.002592563 0.2341634 -0.01224261 0.002177774 0.2340409 -0.01670747 -0.001093089 0.2363026 -0.01567089 -0.001997649 0.2357775 -0.01195627 0.00124371 0.2338958 -0.01191967 7.49958e-4 0.2338773 -0.01640862 -0.001457631 0.2361512 -0.01206511 0.001724004 0.233951 -0.01605981 -0.001761913 0.2359745 -0.01206511 -2.23682e-4 0.233951 -0.01224261 -6.77282e-4 0.2340409 -0.01437467 -0.002239584 0.2351209 -0.01195627 2.56038e-4 0.2338958 -0.01481628 -0.002239763 0.2353446 -0.01525247 -0.002158403 0.2355656 -0.01278322 -0.001456499 0.2343147 -0.01313203 -0.0017609 0.2344914 -0.01352006 -0.001996874 0.234688 -0.01393848 -0.002157866 0.2348999 -0.01248347 -0.001091957 0.2341629 -0.0886237 -0.004249989 -0.06804615 -0.1020048 -0.004249989 -0.06126785 -0.1020048 0.002749919 -0.06126785 -0.08924013 0.003700971 -0.06773394 -0.0895158 0.003749907 -0.06759428 -0.08937627 0.003737628 -0.06766498 -0.08911079 0.003640949 -0.06779944 -0.0889914 0.003558933 -0.06785988 -0.08879411 0.00333774 -0.06795984 -0.088885 0.003457009 -0.06791383 -0.08872091 0.003203928 -0.06799691 -0.08866733 0.003058969 -0.06802409 -0.08863466 0.002906382 -0.0680406 -0.0886237 0.002749919 -0.06804615 -0.1011127 0.003749907 -0.06171971 -0.1019611 0.003058969 -0.06129002 -0.1019076 0.003203928 -0.06131708 -0.1012519 0.003737628 -0.06164926 -0.1013884 0.003700971 -0.06158012 -0.1015177 0.003640949 -0.06151455 -0.1016373 0.003558933 -0.06145405 -0.1017435 0.003457009 -0.06140023 -0.1018344 0.00333774 -0.06135416 -0.1019941 0.002906382 -0.06127327 -0.101268 -0.005234837 -0.06164109 -0.1014178 -0.005189716 -0.06156522 -0.1011127 -0.005250036 -0.06171971 -0.1015588 -0.005116045 -0.06149381 -0.1016864 -0.005016088 -0.0614292 -0.1017961 -0.004892826 -0.06137359 -0.1018853 -0.004750013 -0.06132841 -0.1019513 -0.004592061 -0.06129497 -0.1019914 -0.004423677 -0.06127464 -0.0895158 -0.005250036 -0.06759428 -0.08924013 -0.005201101 -0.06773394 -0.08937627 -0.005237698 -0.06766498 -0.0889914 -0.005059063 -0.06785988 -0.08911079 -0.005141019 -0.06779944 -0.08879411 -0.00483781 -0.06795984 -0.088885 -0.004957139 -0.06791383 -0.08866733 -0.00455904 -0.06802409 -0.08872091 -0.004703998 -0.06799691 -0.08863466 -0.004406452 -0.0680406 -0.0350992 0.001749932 -0.09515947 -0.0342071 0.002749919 -0.09561133 -0.02171808 0.001749932 -0.1019378 -0.02233451 0.002700984 -0.1016255 -0.02261012 0.002749919 -0.1014859 -0.02247065 0.002737641 -0.1015565 -0.02220517 0.002640962 -0.101691 -0.02208578 0.002558946 -0.1017515 -0.02188843 0.002337694 -0.1018515 -0.02197939 0.002457022 -0.1018054 -0.02181529 0.002203941 -0.1018885 -0.02176171 0.002058923 -0.1019157 -0.02172905 0.001906335 -0.1019322 -0.03500193 0.002203941 -0.0952087 -0.03492879 0.002337694 -0.09524577 -0.03434664 0.002737641 -0.09554064 -0.03448277 0.002700984 -0.09547173 -0.03461211 0.002640962 -0.09540617 -0.0347315 0.002558946 -0.09534573 -0.0348379 0.002457022 -0.09529179 -0.03505557 0.002058923 -0.09518152 -0.03508824 0.001906335 -0.09516501 -0.02171808 -0.004249989 -0.1019378 -0.0350992 -0.004249989 -0.09515947 -0.0342071 -0.005250036 -0.09561133 -0.03451222 -0.005189716 -0.09545677 -0.03465318 -0.005116045 -0.09538537 -0.03436195 -0.005234837 -0.09553289 -0.03489047 -0.004892826 -0.0952652 -0.03478056 -0.005016028 -0.09532088 -0.03497964 -0.004750013 -0.09522002 -0.03504538 -0.004592061 -0.09518671 -0.03508561 -0.004423677 -0.09516632 -0.02261012 -0.005250036 -0.1014859 -0.02233451 -0.005201041 -0.1016255 -0.02247065 -0.005237698 -0.1015565 -0.02208578 -0.005059003 -0.1017515 -0.02220517 -0.005141019 -0.101691 -0.02188843 -0.00483781 -0.1018515 -0.02197939 -0.004957139 -0.1018054 -0.02176171 -0.00455904 -0.1019157 -0.02181529 -0.004703998 -0.1018885 -0.02172905 -0.004406452 -0.1019322 -0.1606355 -0.005166828 -0.03156799 -0.1607765 -0.005198657 -0.03149658 -0.1609202 -0.005204677 -0.0314238 -0.1606677 0.001426219 -0.03155171 -0.1611066 0.00142318 -0.03132939 -0.1609612 0.001451611 -0.031403 -0.1605009 -0.005110025 -0.03163617 -0.1603769 -0.005029678 -0.031699 -0.1602644 -0.004927873 -0.03175592 -0.160169 -0.004807353 -0.03180432 -0.1600923 -0.004671156 -0.03184318 -0.1600361 -0.00452286 -0.03187161 -0.1600013 -0.004366338 -0.03188925 -0.1599897 -0.004205584 -0.0318951 -0.1745831 -0.004538774 -0.02450269 -0.1599897 4.55608e-4 -0.0318951 -0.1747696 -0.002572119 -0.02440822 -0.1605268 0.001373171 -0.03162306 -0.1608131 0.001452624 -0.03147804 -0.1603965 0.001294851 -0.03168904 -0.1602796 0.001193523 -0.03174823 -0.1601788 0.00107187 -0.03179931 -0.1600977 9.33278e-4 -0.03184044 -0.1600022 6.20848e-4 -0.03188878 -0.1600388 7.81538e-4 -0.0318703 -0.1751568 -0.002812743 -0.02421212 -0.1750408 -0.002708554 -0.02427089 -0.1749097 -0.002627611 -0.02433729 -0.1753361 -0.003078401 -0.02412128 -0.1752567 -0.002937138 -0.02416151 -0.1754271 -0.003395259 -0.02407521 -0.1753932 -0.003232538 -0.02409237 -0.175436 -0.003561973 -0.02407068 -0.1753807 -0.003888905 -0.02409869 -0.1754208 -0.003728091 -0.02407836 -0.1752317 -0.004177153 -0.02417415 -0.1753165 -0.004040002 -0.02413123 -0.1750069 -0.004394769 -0.02428805 -0.1751273 -0.004296541 -0.02422702 -0.1747313 -0.004517614 -0.02442771 -0.1748731 -0.004469156 -0.02435582 0.05366253 7.49964e-4 0.2017771 0.04643231 7.49963e-4 0.1875038 0.06695008 7.49965e-4 0.1771104 0.05456632 7.49964e-4 0.2035612 0.0809586 7.49966e-4 0.2047647 0.06044089 7.49964e-4 0.2151582 0.05009424 7.49963e-4 0.2035846 0.05099803 7.49963e-4 0.2053688 0.0809586 7.49966e-4 0.2047647 0.06695008 7.49965e-4 0.1771104 0.06695008 -0.001250028 0.1771104 0.0809586 -0.001250028 0.2047647 0.01598143 4.87617e-5 0.04599148 0.1327132 -5.9165e-4 0.2760735 0.1325686 4.87696e-5 0.2761467 0.1327619 -0.001250028 0.2760488 0.01612603 -5.91658e-4 0.04591822 0.01617473 -0.001250028 0.0458936 0.1320095 0.001206815 0.2764299 0.1316103 0.001692831 0.2766321 0.01502317 0.001692831 0.0464769 0.0154224 0.001206755 0.04627472 0.01574468 6.53752e-4 0.04611146 0.1323319 6.5376e-4 0.2762666 0.01348239 0.002627551 0.04725742 0.130627 0.002413034 0.2771303 0.1300696 0.002627551 0.2774127 0.01403981 0.002413034 0.04697501 0.01455813 0.002098619 0.04671251 0.1311453 0.002098619 0.2768677 0.1283177 0.002627551 0.2783001 0.01173055 0.002627551 0.04814481 0.128899 0.00273627 0.2780056 0.1294883 0.00273627 0.2777071 0.01231181 0.00273627 0.04785037 0.01290112 0.00273627 0.04755187 0.1272419 0.002098619 0.278845 0.1267769 0.001692831 0.2790806 0.01018971 0.001692831 0.04892534 0.01117306 0.002413034 0.04842722 0.1277602 0.002413034 0.2785825 0.01065474 0.002098619 0.04868978 0.1263777 0.001206815 0.2792828 0.009468197 6.53751e-4 0.04929083 0.009790539 0.001206755 0.04912757 0.009231448 4.87613e-5 0.04941076 0.1260554 6.53759e-4 0.2794461 0.1258186 4.87692e-5 0.279566 0.009086847 -5.91659e-4 0.04948401 0.125674 -5.91651e-4 0.2796393 0.00903815 -0.001250028 0.04950869 0.1256253 -0.001250028 0.2796639 0.1202729 -0.001250028 0.2823752 0.1256253 -0.001250028 0.2796639 0.008146047 -0.001250028 0.04996055 -0.004900097 -0.001250028 0.03527057 -0.01114463 -0.001250028 0.03843379 -0.02252376 -0.001250028 4.79713e-4 0.00903815 -0.001250028 0.04950869 -0.06183803 -0.001250028 -0.07713073 -0.05737769 -0.001250028 -0.07939016 -0.0287683 -0.001250028 0.003642916 -0.04865533 2.24387e-4 -0.08380854 0.01701694 -5.04478e-4 0.04546695 0.01686841 2.24392e-4 0.04554218 0.01706683 -0.001250028 0.04544168 -0.04850679 -5.04483e-4 -0.08388382 -0.0484569 -0.001250028 -0.08390903 0.01629114 0.001567482 0.0458346 0.01587527 0.002151727 0.0460453 -0.04964846 0.002151727 -0.08330547 -0.0492326 0.001567482 -0.08351612 -0.04889905 9.20247e-4 -0.0836851 0.01662468 9.20252e-4 0.04566562 -0.05128878 0.003404617 -0.08247452 0.01483547 0.003080666 0.04657196 0.01423496 0.003404617 0.04687619 -0.05068826 0.003080666 -0.08277875 -0.05013734 0.002659916 -0.08305782 0.0153864 0.002659916 0.0462929 0.01227301 0.003735959 0.04787003 -0.05325073 0.003735899 -0.08148068 0.01293945 0.003735959 0.04753243 0.01359826 0.003624677 0.04719871 -0.05258429 0.003735899 -0.08181828 -0.05192548 0.003624677 -0.082152 0.01097619 0.003403961 0.04852694 0.01037544 0.003079473 0.04883128 -0.0551483 0.003079473 -0.08051949 -0.05391025 0.003624439 -0.08114659 0.01161348 0.003624439 0.04820412 -0.05454754 0.003403961 -0.08082377 -0.0561878 0.002149701 -0.07999289 0.009335935 0.002149701 0.04935783 -0.05660325 0.001565277 -0.07978248 -0.05569916 0.002658188 -0.08024042 0.009824573 0.002658188 0.04911029 0.00892049 0.001565277 0.04956829 -0.05693638 9.18147e-4 -0.07961374 -0.05717974 2.22707e-4 -0.07949048 0.00858736 9.18151e-4 0.04973703 0.008343994 2.22711e-4 0.04986029 -0.0573278 -5.04483e-4 -0.07941544 0.008195936 -5.04479e-4 0.04993534 -0.05737769 -0.001250028 -0.07939016 0.008146047 -0.001250028 0.04996055 -0.004682242 -0.001250028 -0.008558034 0.01706683 -0.001250028 0.04544168 -0.0484569 -0.001250028 -0.08390903 0.1327619 -0.001250028 0.2760488 0.01617473 -0.001250028 0.0458936 0.005711078 -0.001250028 0.01195961 0.1381143 -0.001250028 0.2733375 0.01284772 -0.001250028 0.008344531 0.00245428 -0.001250028 -0.01217311 -0.04399657 -0.001250028 -0.08616852 -0.1526941 -2.24152e-4 -0.03110682 -0.01723557 2.56038e-4 0.2365701 -0.01712763 -2.24402e-4 0.2365154 -0.01727217 7.49958e-4 0.2365887 -0.1528021 2.56168e-4 -0.03105217 -0.1528386 7.49948e-4 -0.03103363 -0.01670747 -0.001093089 0.2363026 -0.01640862 -0.001457631 0.2361512 -0.1519751 -0.001457214 -0.03147107 -0.1522748 -0.001092672 -0.03131926 -0.1525166 -6.77892e-4 -0.03119677 -0.01695013 -6.78242e-4 0.2364255 -0.1508198 -0.002158224 -0.03205627 -0.01567089 -0.001997649 0.2357775 -0.01525247 -0.002158403 0.2355656 -0.1512374 -0.001997351 -0.03184479 -0.1516263 -0.001761496 -0.03164774 -0.01605981 -0.001761913 0.2359745 -0.01393848 -0.002157866 0.2348999 -0.1495058 -0.002158224 -0.03272187 -0.01437467 -0.002239584 0.2351209 -0.01481628 -0.002239763 0.2353446 -0.1499421 -0.002239763 -0.03250092 -0.1503836 -0.002239763 -0.03227722 -0.01313203 -0.0017609 0.2344914 -0.01278322 -0.001456499 0.2343147 -0.1483497 -0.001457214 -0.03330755 -0.1490874 -0.001997351 -0.03293383 -0.01352006 -0.001996874 0.234688 -0.1486985 -0.001761496 -0.03313082 -0.1476316 -2.24151e-4 -0.03367131 -0.01224261 -6.77282e-4 0.2340409 -0.01206511 -2.23682e-4 0.233951 -0.1478091 -6.77891e-4 -0.03358137 -0.1480509 -0.001092672 -0.03345894 -0.01248347 -0.001091957 0.2341629 -0.01195627 0.00124371 0.2338958 -0.1475228 0.00124371 -0.03372645 -0.01191967 7.49958e-4 0.2338773 -0.01195627 2.56038e-4 0.2338958 -0.1474862 7.49949e-4 -0.03374499 -0.1475228 2.56169e-4 -0.03372645 -0.01224261 0.002177774 0.2340409 -0.01248437 0.002592563 0.2341634 -0.1480509 0.002592563 -0.03345894 -0.1476316 0.001724004 -0.03367131 -0.01206511 0.001724004 0.233951 -0.1478091 0.002177774 -0.03358137 -0.1490874 0.003497242 -0.03293383 -0.01313203 0.003261446 0.2344914 -0.01352095 0.003497242 0.2346885 -0.1486985 0.003261446 -0.03313082 -0.1483497 0.002957105 -0.03330755 -0.01278322 0.002957105 0.2343147 -0.01481717 0.003739655 0.235345 -0.1503836 0.003739655 -0.03227722 -0.01437556 0.003739655 0.2351214 -0.01393938 0.003658115 0.2349004 -0.1499421 0.003739655 -0.03250092 -0.1495058 0.003658115 -0.03272187 -0.1508198 0.003658115 -0.03205627 -0.01525336 0.003658115 0.235566 -0.1512374 0.003497242 -0.03184479 -0.01567089 0.003497242 0.2357775 -0.1516263 0.003261446 -0.03164774 -0.1519751 0.002957105 -0.03147107 -0.01605981 0.003261446 0.2359745 -0.01640862 0.002957105 0.2361512 -0.1522748 0.002592563 -0.03131926 -0.01670837 0.002592563 0.236303 -0.1525166 0.002177774 -0.03119677 -0.1526941 0.001724004 -0.03110682 -0.01695013 0.002177774 0.2364255 -0.01712763 0.001724004 0.2365154 -0.1528021 0.00124371 -0.03105217 -0.01723557 0.00124371 0.2365701 -0.08687698 -0.004620611 -0.06444704 -0.08864897 -0.004497885 -0.06803339 -0.0886237 -0.004249989 -0.06804615 -0.08681613 -0.004249989 -0.06447786 -0.08682709 -0.004406452 -0.06447231 -0.08884376 -0.004911839 -0.06793469 -0.08701997 -0.004890561 -0.06437462 -0.08872091 -0.004703998 -0.06799691 -0.08748728 -0.005221724 -0.06413787 -0.08931916 -0.005228281 -0.06769388 -0.08905905 -0.00511229 -0.06782567 -0.0872302 -0.005097627 -0.06426811 -0.0895158 -0.005250036 -0.06759428 -0.08770823 -0.005250036 -0.06402599 -0.0895158 -0.005250036 -0.06759428 -0.09930521 -0.005250036 -0.05815142 -0.1011127 -0.005250036 -0.06171971 -0.08770823 -0.005250036 -0.06402599 -0.09961026 -0.005189776 -0.05799686 -0.1014178 -0.005189716 -0.06156522 -0.101268 -0.005234837 -0.06164109 -0.1011127 -0.005250036 -0.06171971 -0.09930521 -0.005250036 -0.05815142 -0.09946042 -0.005234837 -0.0580728 -0.1016864 -0.005016088 -0.0614292 -0.09998852 -0.004893004 -0.05780529 -0.1017961 -0.004892826 -0.06137359 -0.09987878 -0.005016207 -0.05786085 -0.1015588 -0.005116045 -0.06149381 -0.09975123 -0.005116105 -0.05792552 -0.1001437 -0.004592239 -0.05772668 -0.1001839 -0.004423797 -0.05770635 -0.1019513 -0.004592061 -0.06129497 -0.1018853 -0.004750013 -0.06132841 -0.1000778 -0.004750192 -0.05776011 -0.1019914 -0.004423677 -0.06127464 -0.1001973 -0.004249989 -0.05769956 -0.1020048 -0.004249989 -0.06126785 -0.1020048 -0.004249989 -0.06126785 -0.1001973 0.002749919 -0.05769956 -0.1020048 0.002749919 -0.06126785 -0.1001973 -0.004249989 -0.05769956 -0.1001359 0.003121733 -0.05773061 -0.1019339 0.003147602 -0.06130379 -0.1019941 0.002906382 -0.06127327 -0.1020048 0.002749919 -0.06126785 -0.1001973 0.002749919 -0.05769956 -0.1001865 0.002906382 -0.05770498 -0.1018344 0.00333774 -0.06135416 -0.09999382 0.003389835 -0.05780261 -0.1016833 0.003522336 -0.06143075 -0.09965866 0.003671109 -0.05797237 -0.1014431 0.003681838 -0.0615524 -0.09982973 0.003558933 -0.0578857 -0.09944438 0.003737628 -0.05808097 -0.1012519 0.003737628 -0.06164926 -0.1011127 0.003749907 -0.06171971 -0.09930521 0.003749907 -0.05815142 -0.08770823 0.003749907 -0.06402599 -0.1011127 0.003749907 -0.06171971 -0.09930521 0.003749907 -0.05815142 -0.0895158 0.003749907 -0.06759428 -0.08751159 0.00372821 -0.06412559 -0.08929485 0.003721654 -0.06770622 -0.0895158 0.003749907 -0.06759428 -0.08770823 0.003749907 -0.06402599 -0.08892542 0.003503322 -0.06789332 -0.08713686 0.003521502 -0.06431543 -0.08911079 0.003640949 -0.06779944 -0.08730322 0.003640949 -0.06423115 -0.0868414 0.002997756 -0.0644651 -0.08864313 0.002970576 -0.06803637 -0.0887466 0.003261923 -0.06798392 -0.08695209 0.003285765 -0.06440901 -0.0886237 0.002749919 -0.06804615 -0.08681613 0.002749919 -0.06447786 -0.08681613 -0.004249989 -0.06447786 -0.0886237 0.002749919 -0.06804615 -0.08681613 0.002749919 -0.06447786 -0.0886237 -0.004249989 -0.06804615 -0.01992994 -0.004470705 -0.09835964 -0.02174329 -0.004497945 -0.101925 -0.02171808 -0.004249989 -0.1019378 -0.01991051 -0.004249989 -0.09836947 -0.02185404 -0.004785895 -0.1018689 -0.02021223 -0.005003392 -0.09821665 -0.02203875 -0.005021572 -0.1017753 -0.02003341 -0.004761993 -0.09830719 -0.02058166 -0.005221724 -0.09802949 -0.02241349 -0.005228281 -0.1015855 -0.02220517 -0.005141019 -0.101691 -0.0203976 -0.005141019 -0.09812277 -0.02261012 -0.005250036 -0.1014859 -0.02080261 -0.005250036 -0.09791761 -0.02261012 -0.005250036 -0.1014859 -0.03239959 -0.005250036 -0.09204304 -0.0342071 -0.005250036 -0.09561133 -0.02080261 -0.005250036 -0.09791761 -0.03270459 -0.005189776 -0.09188854 -0.03451222 -0.005189716 -0.09545677 -0.03436195 -0.005234837 -0.09553289 -0.0342071 -0.005250036 -0.09561133 -0.03239959 -0.005250036 -0.09204304 -0.03255444 -0.005234837 -0.0919646 -0.03478056 -0.005016028 -0.09532088 -0.03308278 -0.004893004 -0.09169691 -0.03489047 -0.004892826 -0.0952652 -0.03297281 -0.005016207 -0.09175264 -0.03465318 -0.005116045 -0.09538537 -0.03284543 -0.005116105 -0.0918172 -0.03323775 -0.004592239 -0.09161847 -0.0332781 -0.004423797 -0.09159803 -0.03504538 -0.004592061 -0.09518671 -0.03497964 -0.004750013 -0.09522002 -0.03317201 -0.004750192 -0.09165173 -0.03508561 -0.004423677 -0.09516632 -0.03329163 -0.004249989 -0.09159117 -0.0350992 -0.004249989 -0.09515947 -0.0350992 -0.004249989 -0.09515947 -0.03329163 0.001749932 -0.09159117 -0.0350992 0.001749932 -0.09515947 -0.03329163 -0.004249989 -0.09159117 -0.0332722 0.001970648 -0.09160101 -0.03507393 0.001997888 -0.09517222 -0.0350992 0.001749932 -0.09515947 -0.03329163 0.001749932 -0.09159117 -0.03496319 0.002285838 -0.09522837 -0.03298997 0.002503335 -0.091744 -0.03477847 0.002521514 -0.09532189 -0.03316873 0.002261936 -0.0916534 -0.03262048 0.002721667 -0.0919311 -0.03440374 0.002728164 -0.09551173 -0.03461211 0.002640962 -0.09540617 -0.03280454 0.002640962 -0.09183788 -0.0342071 0.002749919 -0.09561133 -0.03239959 0.002749919 -0.09204304 -0.02080261 0.002749919 -0.09791761 -0.0342071 0.002749919 -0.09561133 -0.03239959 0.002749919 -0.09204304 -0.02261012 0.002749919 -0.1014859 -0.02060592 0.002728164 -0.09801721 -0.02238917 0.002721667 -0.1015978 -0.02261012 0.002749919 -0.1014859 -0.02080261 0.002749919 -0.09791761 -0.02201974 0.002503335 -0.101785 -0.02023118 0.002521514 -0.09820705 -0.02220517 0.002640962 -0.101691 -0.0203976 0.002640962 -0.09812277 -0.01993578 0.001997888 -0.09835666 -0.02173751 0.001970589 -0.1019279 -0.02184098 0.002261936 -0.1018755 -0.02004653 0.002285838 -0.09830057 -0.02171808 0.001749932 -0.1019378 -0.01991051 0.001749932 -0.09836947 -0.01991051 -0.004249989 -0.09836947 -0.02171808 0.001749932 -0.1019378 -0.01991051 0.001749932 -0.09836947 -0.02171808 -0.004249989 -0.1019378 -0.1730656 -0.004469156 -0.02078753 -0.1748731 -0.004469156 -0.02435582 -0.1747313 -0.004517614 -0.02442771 -0.1745831 -0.004538774 -0.02450269 -0.1727756 -0.004538774 -0.0209344 -0.1729237 -0.004517614 -0.02085936 -0.1751273 -0.004296541 -0.02422702 -0.1734241 -0.004177153 -0.02060586 -0.1752317 -0.004177153 -0.02417415 -0.1733198 -0.004296541 -0.02065873 -0.1750069 -0.004394769 -0.02428805 -0.1731994 -0.004394769 -0.02071976 -0.1736133 -0.003728091 -0.02051007 -0.1754208 -0.003728091 -0.02407836 -0.1753807 -0.003888905 -0.02409869 -0.1735731 -0.003888905 -0.0205304 -0.1753165 -0.004040002 -0.02413123 -0.1735089 -0.004040002 -0.02056294 -0.1753932 -0.003232538 -0.02409237 -0.1754271 -0.003395259 -0.02407521 -0.1735856 -0.003232538 -0.02052408 -0.175436 -0.003561973 -0.02407068 -0.1736284 -0.003561973 -0.02050238 -0.1736195 -0.003395259 -0.02050691 -0.1752567 -0.002937138 -0.02416151 -0.1734491 -0.002937138 -0.02059322 -0.1733492 -0.002812743 -0.02064383 -0.1735285 -0.003078401 -0.02055299 -0.1753361 -0.003078401 -0.02412128 -0.1732332 -0.002708554 -0.0207026 -0.1751568 -0.002812743 -0.02421212 -0.1731021 -0.002627611 -0.020769 -0.1750408 -0.002708554 -0.02427089 -0.1749097 -0.002627611 -0.02433729 -0.1729621 -0.002572119 -0.02083992 -0.1747696 -0.002572119 -0.02440822 -0.1611066 0.00142318 -0.03132939 -0.1729621 -0.002572119 -0.02083992 -0.159299 0.00142318 -0.02776104 -0.1747696 -0.002572119 -0.02440822 -0.1590055 0.001452624 -0.02790975 -0.1608131 0.001452624 -0.03147804 -0.1609612 0.001451611 -0.031403 -0.1611066 0.00142318 -0.03132939 -0.159299 0.00142318 -0.02776104 -0.1591536 0.001451611 -0.02783471 -0.1605268 0.001373171 -0.03162306 -0.158589 0.001294851 -0.02812075 -0.1603965 0.001294851 -0.03168904 -0.1587192 0.001373171 -0.02805477 -0.1606677 0.001426219 -0.03155171 -0.1588602 0.001426219 -0.02798336 -0.1582901 9.33278e-4 -0.02827215 -0.1600977 9.33278e-4 -0.03184044 -0.1601788 0.00107187 -0.03179931 -0.1583713 0.00107187 -0.02823102 -0.1602796 0.001193523 -0.03174823 -0.1584721 0.001193523 -0.02817994 -0.1582312 7.81538e-4 -0.02830195 -0.1581947 6.20848e-4 -0.02832049 -0.1600388 7.81538e-4 -0.0318703 -0.1600022 6.20848e-4 -0.03188878 -0.1581822 4.55608e-4 -0.0283268 -0.1599897 4.55608e-4 -0.0318951 -0.1581822 -0.004205584 -0.0283268 -0.1599897 4.55608e-4 -0.0318951 -0.1581822 4.55608e-4 -0.0283268 -0.1599897 -0.004205584 -0.0318951 -0.1582285 -0.00452286 -0.02830332 -0.1600361 -0.00452286 -0.03187161 -0.1600013 -0.004366338 -0.03188925 -0.1599897 -0.004205584 -0.0318951 -0.1581822 -0.004205584 -0.0283268 -0.1581938 -0.004366338 -0.02832096 -0.160169 -0.004807353 -0.03180432 -0.1584569 -0.004927873 -0.02818763 -0.1602644 -0.004927873 -0.03175592 -0.1583614 -0.004807353 -0.02823603 -0.1600923 -0.004671156 -0.03184318 -0.1582847 -0.004671156 -0.02827483 -0.158828 -0.005166828 -0.02799963 -0.1606355 -0.005166828 -0.03156799 -0.1605009 -0.005110025 -0.03163617 -0.1586933 -0.005110025 -0.02806788 -0.1603769 -0.005029678 -0.031699 -0.1585693 -0.005029678 -0.02813071 -0.1589689 -0.005198657 -0.02792829 -0.1607765 -0.005198657 -0.03149658 -0.1609202 -0.005204677 -0.0314238 -0.1591126 -0.005204677 -0.02785551 -0.1745831 -0.004538774 -0.02450269 -0.1609202 -0.005204677 -0.0314238 -0.1591126 -0.005204677 -0.02785551 -0.1727756 -0.004538774 -0.0209344 -0.05622172 -0.01097494 -0.06604349 -0.06183803 -0.001250028 -0.07713073 -0.04779744 -0.0109356 -0.04941308 -0.06183803 -0.01100385 -0.07713073 -0.03937274 -0.0109021 -0.03278189 -0.02252376 -0.001250028 4.79713e-4 -0.03095543 -0.01087331 -0.01616531 -0.02252376 -0.01085025 4.79713e-4 -0.02252376 -0.001250028 4.79713e-4 -0.0287683 -0.001250028 0.003642916 -0.0287683 -0.01070207 0.003642916 -0.02252376 -0.01085025 4.79713e-4 -0.0287683 -0.001250028 0.003642916 -0.01114463 -0.001250028 0.03843379 -0.02289372 -0.01069289 0.01523983 -0.0287683 -0.01070207 0.003642916 -0.01701921 -0.01069009 0.02683681 -0.01114463 -0.01069372 0.03843379 -0.01114463 -0.001250028 0.03843379 -0.004900097 -0.001250028 0.03527057 -0.004900097 -0.01084208 0.03527057 -0.01114463 -0.01069372 0.03843379 0.008899688 -0.01093119 0.06251293 -0.004900097 -0.001250028 0.03527057 -0.004900097 -0.01084262 0.03527057 0.01720756 -0.01097977 0.0789135 0.02551996 -0.01102519 0.09532308 0.06695008 -0.001250028 0.1771104 0.04207676 -0.01110452 0.128008 0.0337882 -0.01106637 0.1116455 0.05036938 -0.01113873 0.1443784 0.0586639 -0.01116979 0.1607527 0.06695008 -0.01119685 0.1771104 0.04643231 7.49963e-4 0.1875038 0.05156129 -0.01084339 0.1849057 0.05669057 -0.01097643 0.1823074 0.0618202 -0.01109427 0.179709 0.06695008 7.49965e-4 0.1771104 0.04643231 -0.01069509 0.1875038 0.06695008 -0.01119685 0.1771104 0.0500456 -0.01064884 0.1946368 0.04643231 -0.01069509 0.1875038 0.04643231 7.49963e-4 0.1875038 0.05366253 7.49964e-4 0.2017771 0.05366253 -0.01058268 0.2017771 0.05009424 7.49963e-4 0.2035846 0.05366253 -0.01058268 0.2017771 0.05366253 7.49964e-4 0.2017771 0.05009424 -0.01047599 0.2035846 0.05099803 7.49963e-4 0.2053688 0.05009424 -0.01047599 0.2035846 0.05009424 7.49963e-4 0.2035846 0.05099803 -0.01045626 0.2053688 0.05456632 7.49964e-4 0.2035612 0.05099803 -0.01045626 0.2053688 0.05099803 7.49963e-4 0.2053688 0.05456632 -0.01056277 0.2035612 0.06044089 7.49964e-4 0.2151582 0.05456632 -0.01056277 0.2035612 0.05456632 7.49964e-4 0.2035612 0.06044089 -0.01039791 0.2151582 0.0809586 7.49966e-4 0.2047647 0.07582873 -0.0107792 0.2073633 0.07069909 -0.01066905 0.2099618 0.06556987 -0.01054197 0.21256 0.06044089 7.49964e-4 0.2151582 0.0809586 -0.01087236 0.2047647 0.06044089 -0.01039791 0.2151582 0.0809586 -0.001250028 0.2047647 0.09219026 -0.01031434 0.2269372 0.08657419 -0.0105704 0.2158505 0.09780633 -0.01010411 0.2380239 0.0809586 -0.01087236 0.2047647 0.1034228 -0.009939789 0.2491115 0.1202729 -0.001250028 0.2823752 0.1090394 -0.009821355 0.2601991 0.1146559 -0.009748756 0.2712867 0.1202729 -0.009721994 0.2823752 0.1336553 -0.009574055 0.2755962 0.1327619 -0.001250028 0.2760488 0.1381143 -0.001250028 0.2733375 0.1202729 -0.001250028 0.2823752 0.1256253 -0.001250028 0.2796639 0.1247346 -0.009729146 0.2801151 0.1267769 0.001692831 0.2790806 0.1311453 0.002098619 0.2768677 0.1316103 0.001692831 0.2766321 0.1300696 0.002627551 0.2774127 0.1283177 0.002627551 0.2783001 0.1294883 0.00273627 0.2777071 0.128899 0.00273627 0.2780056 0.130627 0.002413034 0.2771303 0.1277602 0.002413034 0.2785825 0.1272419 0.002098619 0.278845 0.1263777 0.001206815 0.2792828 0.1320095 0.001206815 0.2764299 0.1260554 6.53759e-4 0.2794461 0.1323319 6.5376e-4 0.2762666 0.1325686 4.87696e-5 0.2761467 0.1258186 4.87692e-5 0.279566 0.1327132 -5.9165e-4 0.2760735 0.125674 -5.91651e-4 0.2796393 0.1381143 -0.009411811 0.2733375 0.1291955 -0.009679794 0.2778554 0.1202729 -0.009721994 0.2823752 0.04433131 -0.01156747 0.08819985 0.005711078 -0.001250028 0.01195961 0.03881418 -0.0115478 0.07730853 0.04984837 -0.01157087 0.09909123 0.03329706 -0.01151192 0.06641721 0.0553655 -0.01155799 0.1099826 0.02777999 -0.0114597 0.05552583 0.06088215 -0.01152884 0.120873 0.02226287 -0.01139122 0.04463452 0.06639927 -0.01148337 0.1317643 0.01674574 -0.01130646 0.0337432 0.07191592 -0.01142168 0.1426548 0.0112282 -0.01120543 0.02285099 0.07743257 -0.01134371 0.1535452 0.005711078 -0.01108813 0.01195961 0.08294922 -0.01124942 0.1644357 0.09398293 -0.01101213 0.1862174 0.08846628 -0.01113891 0.175327 0.09949916 -0.01086902 0.197107 0.1381143 -0.001250028 0.2733375 0.1105325 -0.01053404 0.2188879 0.1050158 -0.0107097 0.2079975 0.1160491 -0.01034212 0.2297784 0.1215653 -0.01013398 0.2406679 0.1270815 -0.00990951 0.2515575 0.1325982 -0.009668767 0.2624479 0.1381143 -0.009411811 0.2733375 0.005711078 -0.001250028 0.01195961 0.01284772 -0.001250028 0.008344531 0.01284772 -0.01107525 0.008344531 0.005711078 -0.01108813 0.01195961 0.01284772 -0.001250028 0.008344531 0.00245428 -0.001250028 -0.01217311 0.007750868 -0.011078 -0.00171715 0.01284772 -0.01107525 0.008344531 0.00245428 -0.01108449 -0.01217311 0.00245428 -0.001250028 -0.01217311 -0.004682242 -0.001250028 -0.008558034 -0.004682242 -0.01109838 -0.008558034 0.00245428 -0.01108449 -0.01217311 -0.01312065 -0.01111859 -0.02521622 -0.004682242 -0.001250028 -0.008558034 -0.004682242 -0.01109838 -0.008558034 -0.02436149 -0.01115286 -0.04740679 -0.04399657 -0.001250028 -0.08616852 -0.03558117 -0.01119506 -0.06955564 -0.04399657 -0.01123219 -0.08616852 -0.08682709 -0.004406452 -0.06447231 -0.08681613 -0.004249989 -0.06447786 -0.06183803 -0.001250028 -0.07713073 -0.08250397 0.01473015 -0.06666225 -0.05974972 0.01442104 -0.07818859 -0.05855405 0.01433515 -0.0787943 -0.0869134 -0.004703998 -0.06442862 -0.08685976 -0.00455904 -0.0644558 -0.08707743 -0.004957139 -0.06434553 -0.08698654 -0.00483781 -0.06439155 -0.06183803 -0.01100385 -0.07713073 -0.06751042 -0.01083731 -0.07425737 -0.0875687 -0.005237698 -0.06409668 -0.08718389 -0.005059063 -0.06429159 -0.09303665 -0.01005256 -0.0613268 -0.08770823 -0.005250036 -0.06402599 -0.07602679 -0.01058226 -0.0699433 -0.08452689 -0.01032042 -0.06563752 -0.1001973 -0.004249989 -0.05769956 -0.1490874 -0.001997351 -0.03293383 -0.1486985 -0.001761496 -0.03313082 -0.09930521 -0.005250036 -0.05815142 -0.1043863 -0.009684622 -0.05557751 -0.1476316 -2.24151e-4 -0.03367131 -0.1001973 0.002749919 -0.05769956 -0.1478091 -6.77891e-4 -0.03358137 -0.1475228 2.56169e-4 -0.03372645 -0.08743256 0.003700971 -0.06416559 -0.0875687 0.003737628 -0.06409668 -0.05391025 0.003624439 -0.08114659 -0.1001839 -0.004423797 -0.05770635 -0.1001437 -0.004592239 -0.05772668 -0.1499421 -0.002239763 -0.03250092 -0.1616947 0.004705071 -0.02654749 -0.1503836 0.003739655 -0.03227722 -0.05325073 0.003735899 -0.08148068 -0.08770823 0.003749907 -0.06402599 -0.1486985 0.003261446 -0.03313082 -0.1000269 0.00333774 -0.05778586 -0.1001001 0.003203928 -0.05774879 -0.08681613 0.002749919 -0.06447786 -0.05693638 9.18147e-4 -0.07961374 -0.05717974 2.22707e-4 -0.07949048 -0.1561586 0.005608439 -0.02935189 -0.1499421 0.003739655 -0.03250092 -0.1405476 0.008098304 -0.03725975 -0.1376832 0.008542835 -0.03871077 -0.09944438 0.003737628 -0.05808097 -0.09971022 0.003640949 -0.05794626 -0.1495058 0.003658115 -0.03272187 -0.09958088 0.003700971 -0.05801182 -0.0573278 -5.04483e-4 -0.07941544 -0.09930521 0.003749907 -0.05815142 -0.1348187 0.008982241 -0.04016178 -0.1075953 0.01273334 -0.05395203 -0.038329 0.01171195 -0.08903944 -0.03714787 0.01148623 -0.08963775 -0.03239959 -0.005250036 -0.09204304 -0.03576362 -0.01119118 -0.09033894 -0.03748703 -0.01121062 -0.08946597 -0.03951138 0.01192903 -0.08844047 -0.1064034 0.01287001 -0.05455577 -0.1052116 0.01300334 -0.0551595 -0.1028262 0.01325923 -0.05636781 -0.04306536 0.01253074 -0.08664017 -0.04187965 0.01233834 -0.08724081 -0.05737769 -0.001250028 -0.07939016 -0.04781794 0.01322233 -0.08423274 -0.04662841 0.0130611 -0.08483529 -0.09685736 0.01383084 -0.05939143 -0.1016326 0.01338154 -0.05697244 -0.1004399 0.01350015 -0.05757665 -0.04425209 0.01271545 -0.086039 -0.09088122 0.01429295 -0.06241863 -0.05139088 0.0136609 -0.08242285 -0.09207671 0.01421004 -0.06181311 -0.04900813 0.01337605 -0.08362984 -0.09446746 0.01402962 -0.060602 -0.05019915 0.0135222 -0.08302652 -0.06214225 0.01457053 -0.07697665 -0.08010876 0.01480573 -0.06787556 -0.07891082 0.01483494 -0.06848239 -0.08609551 0.01457452 -0.06484293 -0.05735886 0.01424163 -0.0793997 -0.0561642 0.0141406 -0.08000487 -0.066931 0.01478201 -0.07455086 -0.07292068 0.01488953 -0.07151675 -0.0717225 0.01488143 -0.0721237 -0.06333905 0.01463425 -0.07637041 -0.07771295 0.01485812 -0.06908917 -0.06453615 0.01469063 -0.075764 -0.01852768 0.006452322 -0.09906995 -0.05258429 0.003735899 -0.08181828 -0.01966822 0.006863832 -0.0984922 -0.02892428 0.009645044 -0.09380346 -0.03009366 0.009938001 -0.09321111 -0.03292393 0.002558946 -0.09177744 -0.03303033 0.002457022 -0.0917235 -0.05013734 0.002659916 -0.08305782 -0.02080261 -0.005250036 -0.09791761 -0.003664076 -0.00734359 -0.1065992 -0.005300104 -0.008030056 -0.1057705 -0.004484713 -0.007706701 -0.1061835 -0.002081573 -0.005280911 -0.1074008 -0.0203976 -0.005141019 -0.09812277 -0.02027821 -0.005059003 -0.09818321 -0.00461775 -0.001214206 -0.1061161 -0.01991051 -0.004249989 -0.09836947 -0.01991051 0.001749932 -0.09836947 -0.002183854 -0.004487693 -0.107349 -0.01992148 -0.004406452 -0.09836393 -0.01033425 -0.009410977 -0.1032204 -0.009481728 -0.009246945 -0.1036522 -0.04850679 -5.04483e-4 -0.08388382 -0.04865533 2.24387e-4 -0.08380854 -0.04399657 -0.001250028 -0.08616852 -0.002158761 -0.005674898 -0.1073618 -0.002303361 -0.006044328 -0.1072885 -0.02066308 -0.005237698 -0.09798824 -0.0484569 -0.001250028 -0.08390903 -0.03403329 -0.01116472 -0.09121549 -0.02884161 -0.01103484 -0.09384536 -0.0323053 -0.01113039 -0.09209084 -0.03057247 -0.01108735 -0.09296858 -0.02410781 -0.01083368 -0.09624332 -0.0249719 -0.01087725 -0.09580558 -0.02711784 -0.01097208 -0.09471851 -0.02324396 -0.01078671 -0.09668087 -0.003021121 -0.006937146 -0.1069249 -0.003326117 -0.007152199 -0.1067705 -0.01806491 -0.01041638 -0.09930437 -0.01892733 -0.01049089 -0.09886747 -0.02065318 -0.01062315 -0.09799325 -0.0215165 -0.01068186 -0.09755593 -0.008632719 -0.009061753 -0.1040823 -0.006951391 -0.008607089 -0.104934 -0.01204538 -0.009695649 -0.1023536 -0.01290279 -0.009823024 -0.1019193 -0.01118904 -0.009558916 -0.1027874 -0.01376128 -0.009941577 -0.1014844 -0.007788658 -0.008850157 -0.1045099 -0.0146206 -0.01005172 -0.1010491 -0.01634156 -0.0102483 -0.1001774 -0.01548075 -0.01015383 -0.1006134 -0.006121993 -0.008332014 -0.1053541 -0.02238011 -0.01073622 -0.09711849 -0.002742409 -0.006681501 -0.1070661 -0.02583611 -0.0109176 -0.09536778 -0.002500295 -0.006382644 -0.1071888 -0.03922986 -0.01122397 -0.08858311 -0.02052694 -0.005201041 -0.09805721 -0.04268723 -0.01123386 -0.08683174 -0.04095894 -0.01123154 -0.08770722 -0.02017182 -0.004957139 -0.09823709 -0.002090752 -0.004877507 -0.1073963 -0.02000772 -0.004703998 -0.09832024 -0.01995414 -0.00455904 -0.09834736 -0.002527713 -0.003778755 -0.1071749 -0.002338051 -0.004122376 -0.107271 -0.002960741 -0.00313282 -0.1069555 -0.002738833 -0.003451287 -0.107068 -0.003757357 -0.002135515 -0.106552 -0.00554192 -3.68949e-4 -0.105648 -0.007555127 0.001112401 -0.1046282 -0.006529808 4.00291e-4 -0.1051476 -0.008593916 0.001784682 -0.104102 -0.03329163 0.001749932 -0.09159117 -0.03329163 -0.004249989 -0.09159117 -0.01181501 0.003570258 -0.1024703 -0.01072782 0.00300908 -0.103021 -0.02066308 0.002737641 -0.09798824 -0.02080261 0.002749919 -0.09791761 -0.01291227 0.004108786 -0.1019145 -0.01402181 0.0046193 -0.1013524 -0.03328067 0.001906335 -0.09159672 -0.0492326 0.001567482 -0.08351612 -0.04964846 0.002151727 -0.08330547 -0.01513838 0.005108416 -0.1007869 -0.03239959 0.002749919 -0.09204304 -0.033248 0.002058923 -0.09161323 -0.03312122 0.002337694 -0.09167748 -0.03319442 0.002203941 -0.09164041 -0.01739245 0.00602293 -0.09964501 -0.03253906 0.002737641 -0.09197235 -0.05128878 0.003404617 -0.08247452 -0.02081292 0.007260024 -0.09791237 -0.02196222 0.007640004 -0.09733015 -0.02311474 0.008006751 -0.09674632 -0.02427119 0.008358836 -0.09616053 -0.02543032 0.008698642 -0.09557336 -0.02659249 0.009025633 -0.09498465 -0.02775728 0.009340941 -0.09439462 -0.03126496 0.01022064 -0.0926178 -0.03243827 0.01049274 -0.09202343 -0.03478997 0.0110079 -0.09083217 -0.03361326 0.01075536 -0.09142827 -0.03596824 0.01125174 -0.09023529 -0.09805184 0.0137248 -0.05878633 -0.08968514 0.01437103 -0.06302458 -0.05258327 0.01379215 -0.08181881 -0.09327298 0.01412212 -0.06120711 -0.08489853 0.01463192 -0.06544923 -0.05496996 0.014032 -0.08060979 -0.08848887 0.01444405 -0.06363052 -0.08729237 0.01451194 -0.06423664 -0.0609458 0.01449942 -0.07758271 -0.08130633 0.0147708 -0.0672689 -0.07651489 0.01487535 -0.06969606 -0.07531684 0.01488631 -0.07030296 -0.06932657 0.01484531 -0.07333737 -0.07411873 0.01489114 -0.07090985 -0.06573349 0.01473993 -0.07515746 -0.07052445 0.01486682 -0.0727306 -0.0681287 0.01481723 -0.07394415 -0.08370131 0.01468384 -0.06605571 -0.05377626 0.01391583 -0.08121448 -0.09566283 0.01393252 -0.05999648 -0.04543989 0.012892 -0.08543735 -0.09924542 0.01361453 -0.0581817 -0.1040189 0.01313304 -0.05576366 -0.04069495 0.01213771 -0.08784091 -0.1087871 0.0125935 -0.0533483 -0.112969 0.01207894 -0.05122995 -0.1147399 0.01185041 -0.05033284 -0.1105884 0.01237636 -0.05243581 -0.1262191 0.01026302 -0.04451799 -0.1233511 0.01067483 -0.04597079 -0.1204822 0.01107734 -0.04742407 -0.1434112 0.007649421 -0.03580921 -0.1462739 0.007196545 -0.03435909 -0.1290862 0.009843111 -0.0430656 -0.1319525 0.009415924 -0.04161369 -0.1490874 0.003497242 -0.03293383 -0.09982973 0.003558933 -0.0578857 -0.1519992 0.006280839 -0.03145885 -0.1491365 0.006740212 -0.03290897 -0.09993588 0.003457009 -0.05783194 -0.1519751 0.002957105 -0.03147107 -0.1670845 0.003817439 -0.0238173 -0.1512374 0.003497242 -0.03184479 -0.1516263 0.003261446 -0.03164774 -0.1001536 0.003058969 -0.05772167 -0.1001865 0.002906382 -0.05770498 -0.1483497 0.002957105 -0.03330755 -0.1751663 0.002478778 -0.01972335 -0.1591536 0.001451611 -0.02783471 -0.1522748 0.002592563 -0.03131926 -0.1525166 0.002177774 -0.03119677 -0.1587192 0.001373171 -0.02805477 -0.1588602 0.001426219 -0.02798336 -0.1526941 0.001724004 -0.03110682 -0.1590055 0.001452624 -0.02790975 -0.159299 0.00142318 -0.02776104 -0.1836023 0.001074671 -0.01545006 -0.1000778 -0.004750192 -0.05776011 -0.1582847 -0.004671156 -0.02827483 -0.1584721 0.001193523 -0.02817994 -0.1528021 0.00124371 -0.03105217 -0.1583713 0.00107187 -0.02823102 -0.09987878 -0.005016207 -0.05786085 -0.1327198 -0.008715689 -0.04122501 -0.09998852 -0.004893004 -0.05780529 -0.1977662 -0.001297771 -0.00827521 -0.1731021 -0.002627611 -0.020769 -0.1732332 -0.002708554 -0.0207026 -0.09961026 -0.005189776 -0.05799686 -0.09946042 -0.005234837 -0.0580728 -0.1583614 -0.004807353 -0.02823603 -0.1581822 -0.004205584 -0.0283268 -0.1581822 4.55608e-4 -0.0283268 -0.1519751 -0.001457214 -0.03147107 -0.1503836 -0.002239763 -0.03227722 -0.1734241 -0.004177153 -0.02060586 -0.1733198 -0.004296541 -0.02065873 -0.2007802 -0.006093502 -0.006748437 -0.1497554 -0.008098423 -0.03259545 -0.1582553 -0.007780313 -0.02828979 -0.1589689 -0.005198657 -0.02792829 -0.1516263 -0.001761496 -0.03164774 -0.1512374 -0.001997351 -0.03184479 -0.1508198 -0.002158224 -0.03205627 -0.1922782 -0.00644344 -0.01105523 -0.1727756 -0.004538774 -0.0209344 -0.1591126 -0.005204677 -0.02785551 -0.1752672 -0.0071249 -0.01967227 -0.1731994 -0.004394769 -0.02071976 -0.1730656 -0.004469156 -0.02078753 -0.1729237 -0.004517614 -0.02085936 -0.1837533 -0.006788551 -0.01537352 -0.2091981 -0.003285706 -0.002484261 -0.2063497 -0.002772629 -0.003927171 -0.2120651 -0.005618453 -0.001031994 -0.2120251 -0.003808617 -0.0010522 -0.2149351 -0.004338145 4.21807e-4 -0.2206274 -0.005250036 0.003305256 -0.2177317 -0.004835009 0.001838445 -0.1495058 -0.002158224 -0.03272187 -0.05569916 0.002658188 -0.08024042 -0.0561878 0.002149701 -0.07999289 -0.1474862 7.49949e-4 -0.03374499 -0.1475228 0.00124371 -0.03372645 -0.1476316 0.001724004 -0.03367131 -0.08698654 0.00333774 -0.06439155 -0.08707743 0.003457009 -0.06434553 -0.0551483 0.003079473 -0.08051949 -0.1508198 0.003658115 -0.03205627 -0.1480509 0.002592563 -0.03345894 -0.05660325 0.001565277 -0.07978248 -0.1736195 -0.003395259 -0.02050691 -0.2034835 -0.002271234 -0.00537908 -0.1735856 -0.003232538 -0.02052408 -0.1582285 -0.00452286 -0.02830332 -0.09975123 -0.005116105 -0.05792552 -0.1156692 -0.009307444 -0.04986208 -0.1735089 -0.004040002 -0.02056294 -0.1242289 -0.009013295 -0.04552614 -0.158828 -0.005166828 -0.02799963 -0.1585693 -0.005029678 -0.02813071 -0.1412425 -0.008409798 -0.03690773 -0.1586933 -0.005110025 -0.02806788 -0.166794 -0.007454931 -0.0239644 -0.1735731 -0.003888905 -0.0205304 -0.1733492 -0.002812743 -0.02064383 -0.1729621 -0.002572119 -0.02083992 -0.158589 0.001294851 -0.02812075 -0.1478091 0.002177774 -0.03358137 -0.1581938 -0.004366338 -0.02832096 -0.08730322 -0.005141019 -0.06423115 -0.08743256 -0.005201101 -0.06416559 -0.1483497 -0.001457214 -0.03330755 -0.1480509 -0.001092672 -0.03345894 -0.05454754 0.003403961 -0.08082377 -0.1176115 0.01146972 -0.04887825 -0.08718389 0.003558933 -0.06429159 -0.08730322 0.003640949 -0.06423115 -0.0869134 0.003203928 -0.06442862 -0.08685976 0.003058969 -0.0644558 -0.08682709 0.002906382 -0.06447231 -0.04889905 9.20247e-4 -0.0836851 -0.01995414 0.002058923 -0.09834736 -0.00965619 0.002411663 -0.1035639 -0.01992148 0.001906335 -0.09836393 -0.02008092 -0.00483781 -0.09828317 -0.03284543 -0.005116105 -0.0918172 -0.04399657 -0.01123219 -0.08616852 -0.03297281 -0.005016207 -0.09175264 -0.01979011 -0.01055961 -0.09843045 -0.01720297 -0.01033568 -0.09974098 -0.03270459 -0.005189776 -0.09188854 -0.03255444 -0.005234837 -0.0919646 -0.03308278 -0.004893004 -0.09169691 -0.03323775 -0.004592239 -0.09161847 -0.03317201 -0.004750192 -0.09165173 -0.0332781 -0.004423797 -0.09159803 -0.01626229 0.005575537 -0.1002175 -0.0326752 0.002700984 -0.09190338 -0.03280454 0.002640962 -0.09183788 -0.05068826 0.003080666 -0.08277875 -0.05192548 0.003624677 -0.082152 -0.02052694 0.002700984 -0.09805721 -0.02027821 0.002558946 -0.09818321 -0.0203976 0.002640962 -0.09812277 -0.02017182 0.002457022 -0.09823709 -0.02000772 0.002203941 -0.09832024 -0.02008092 0.002337694 -0.09828317 -0.1736133 -0.003728091 -0.02051007 -0.1736284 -0.003561973 -0.02050238 -0.2006226 -0.001780867 -0.006828248 -0.1522748 -0.001092672 -0.03131926 -0.1734491 -0.002937138 -0.02059322 -0.1735285 -0.003078401 -0.02055299 -0.1525166 -6.77892e-4 -0.03119677 -0.1936944 -6.13624e-4 -0.01033782 -0.1581947 6.20848e-4 -0.02832049 -0.1528386 7.49948e-4 -0.03103363 -0.1582901 9.33278e-4 -0.02827215 -0.1582312 7.81538e-4 -0.02830195 -0.1528021 2.56168e-4 -0.03105217 -0.1526941 -2.24152e-4 -0.03110682 -0.1584569 -0.004927873 -0.02818763 0.01306682 7.02956e-4 0.3669478 0.02195554 -0.007108807 0.3624451 -0.006400763 -0.002568125 0.3768093 -0.002684414 -0.006247401 0.3749268 -0.008978009 -0.003008246 0.3781148 0.01673871 -0.006935 0.3650878 0.008073627 -1.30672e-4 0.3694772 0.01164942 -0.006759405 0.3676658 0.01823318 0.001561343 0.3643308 0.02195554 0.002177536 0.3624451 0.002930879 -9.93127e-4 0.3720822 -0.002368867 -0.00188589 0.3747669 0.006688594 -0.006582021 0.3701788 0.002019464 -0.00642836 0.3725439 -0.007423996 -0.006039023 0.3773276 -0.01219928 -0.005803406 0.3797466 -0.01297152 -0.003696858 0.3801378 -0.01700937 -0.00554037 0.3821831 -0.01805812 -0.004582464 0.3827144 -0.02185511 -0.005250036 0.3846378 -0.07099419 0.00300467 0.1789526 -0.07505202 0.002994596 0.170942 -0.07176023 -0.007348477 0.1774403 -0.0556789 -0.00736916 0.2091866 -0.05481559 0.00300759 0.2108908 -0.06694352 0.003011405 0.186949 -0.07978612 -0.007328271 0.1615964 -0.08009076 0.002976119 0.1609951 -0.06371921 -0.00736165 0.1933141 -0.08514189 0.002951979 0.1510235 -0.06088739 0.003013849 0.1989045 -0.08514189 -0.007311403 0.1510235 -0.04977315 0.00299561 0.2208451 -0.04473942 0.002978086 0.2307822 -0.04765278 -0.007369577 0.2250309 -0.03962683 -0.007364332 0.240875 -0.03867071 0.002948701 0.2427624 -0.03360003 0.002917289 0.2527726 -0.02956181 0.002888083 0.2607443 -0.02891796 -0.007346928 0.2620155 -0.02552014 0.002855002 0.2687231 -0.02148276 0.002818107 0.2766934 -0.01641774 0.002766549 0.2866922 -0.01822018 -0.007318198 0.2831339 -0.0113604 0.002708673 0.2966759 -0.01016914 -0.007288753 0.2990276 -0.007328212 0.002658367 0.3046358 -0.003290653 0.002604126 0.3126063 -0.002134263 -0.007253646 0.3148892 7.49335e-4 0.002546012 0.3205818 0.004782617 0.002484083 0.328544 0.009825944 0.00240153 0.3385 0.005893647 -0.007211565 0.3307372 0.01487869 0.002312362 0.3484747 0.0139324 -0.007163643 0.3466066 0.01890414 0.0022372 0.3564214 0.02195554 0.002177536 0.3624451 0.02195554 -0.007108807 0.3624451 0.07065296 0.008842825 0.488168 0.06133764 0.006311833 0.4866922 0.0592184 0.005562841 0.4858523 0.05993968 0.004915654 0.4840453 0.05713939 0.004817843 0.4849347 0.05510604 0.004085063 0.4839458 0.05118626 0.002649605 0.48174 0.05311888 0.003364503 0.4828864 0.04929178 0.001951992 0.4805362 0.06349366 0.007053256 0.487443 0.06568855 0.007796406 0.4881135 0.04743683 0.001271784 0.4792754 0.0502783 0.001158058 0.4778741 0.04562669 6.05791e-4 0.4779481 0.0438565 -4.41591e-5 0.4765603 0.04211735 -6.7187e-4 0.4751275 0.040412 -0.001277327 0.4736508 0.04161131 -0.002140104 0.4701187 0.03874522 -0.001865983 0.4721153 0.03710734 -0.002429425 0.4705438 0.03549295 -0.002965748 0.4689414 0.03390657 -0.003476262 0.4673035 0.03235 -0.003962755 0.4656247 0.03081208 -0.004418015 0.4639275 0.03368198 -0.00478357 0.4612945 0.0292924 -0.004842102 0.462211 0.02779358 -0.005233585 0.4604715 0.02484673 -0.00592488 0.4569423 0.02339595 -0.006225883 0.455156 0.02631258 -0.005594134 0.4587141 0.02624154 -0.006597042 0.4518885 0.02196395 -0.006492137 0.4533537 0.02054435 -0.006732344 0.4515382 0.0191673 -0.007610082 0.4421212 0.01637244 -0.007290899 0.4460132 0.01500803 -0.007427275 0.4441474 0.01913857 -0.006946504 0.4497102 0.01774835 -0.007132232 0.4478687 0.01099228 -0.007696628 0.4384793 0.01231926 -0.007628977 0.4403797 0.02748054 -0.008104264 0.43791 0.03408199 -0.00706309 0.4479169 0.02333503 -0.007881939 0.44001 0.01365697 -0.007541358 0.4422703 0.009676814 -0.007745742 0.4365685 0.005893111 -0.007835149 0.4217411 0.003259479 -0.007714748 0.4268742 0.00200504 -0.007660984 0.4249089 0.01240229 -0.007972419 0.4320526 0.008372545 -0.007775068 0.4346487 0.007080256 -0.007782936 0.4327173 0.005796432 -0.007776141 0.4307781 0.00452286 -0.007754504 0.4288305 7.58633e-4 -0.007596194 0.4229375 -0.001708805 -0.007428765 0.4189737 -4.79788e-4 -0.007520437 0.4209596 -0.006561875 -0.006983876 0.4109755 -4.15683e-4 -0.007349491 0.4112452 -0.005358636 -0.007107913 0.4129835 -0.002932131 -0.007329821 0.4169815 -0.004149138 -0.007223665 0.4149861 -0.00895369 -0.00672537 0.4069488 -0.007760226 -0.006856381 0.4089639 0.01949155 -0.00831747 0.4011725 0.02525097 -0.008776187 0.4119415 -0.01014131 -0.00658673 0.4049295 -0.006575763 -0.0066666 0.4006247 -0.01538026 -0.005960524 0.3959135 -0.01132494 -0.006446897 0.4029071 -0.01250547 -0.006307363 0.400882 -0.01264369 -0.005937755 0.3899361 -0.01368242 -0.006166815 0.3988551 -0.007801532 -0.0062536 0.3874832 -0.01700937 -0.00554037 0.3821831 -0.01219928 -0.005803406 0.3797466 -0.01719504 -0.005749642 0.392764 -0.019661 -0.005476176 0.3884711 -0.02185511 -0.005250036 0.3846378 -0.1444739 -0.005169093 0.1533493 -0.1403908 -0.005395054 0.1471939 0.07016777 0.009259819 0.4892041 0.06792455 0.008541464 0.4887037 0.08182531 0.01234126 0.4899508 0.07242661 0.009958505 0.4896158 0.07700103 0.01130652 0.4901773 0.07470643 0.01064282 0.4899407 0.08383524 0.01305806 0.4903159 0.08155465 0.01250493 0.4903614 0.07927721 0.01192116 0.4903156 -0.02876824 -0.0107007 0.003642857 -0.04159718 -0.01062589 -0.01223671 -0.08514189 -0.007311403 0.1510235 -0.0672127 -0.01002669 -0.01292502 -0.05627119 -0.01097393 -0.06614112 -0.06166309 -0.01085686 -0.0638768 -0.07305479 -0.01054531 -0.05805003 -0.08021736 -0.01032477 -0.05437129 -0.05287086 -0.01066106 -0.03385353 -0.06711727 -0.01071357 -0.06087434 -0.09227514 -0.009926795 -0.04836899 -0.1036863 -0.009707748 -0.0559321 -0.067142 -0.01023358 -0.02662414 -0.05293619 -0.01047939 -0.02015691 -0.09433466 -0.009081006 8.13793e-4 -0.1040524 -0.00951296 -0.04208415 -0.1471532 -0.007215023 0.02756941 -0.1330907 -0.007386028 0.04094219 -0.1212713 -0.008504271 -0.009452164 -0.112179 -0.008441746 0.009852945 -0.1615858 -0.006501615 0.0485444 -0.1530138 -0.006802201 0.0442022 -0.1419239 -0.006775736 0.06591498 -0.1672964 -0.006290197 0.05143719 -0.1243128 -0.008011102 0.01599943 -0.1355037 -0.008054494 -0.005658328 -0.1769928 -0.006060481 0.04652613 -0.1474776 -0.005153477 0.1473633 -0.1414454 -0.005186557 0.1593907 -0.1322527 -0.005452573 0.163548 -0.1280436 -0.005564033 0.1727557 -0.1333996 -0.005240738 0.1754689 -0.1374174 -0.005212426 0.1674355 -0.1514951 -0.005134701 0.139366 -0.1555435 -0.005118966 0.1313163 -0.1508471 -0.005349695 0.1263839 -0.1586188 -0.005108714 0.1252088 -0.1616028 -0.005100548 0.1192882 -0.1596157 -0.005333244 0.1090459 -0.1660789 -0.005091011 0.1104179 -0.1667783 -0.00533241 0.09487354 -0.1778015 -0.005082607 0.08724611 -0.1725381 -0.005083382 0.09763807 -0.1818414 -0.005085229 0.07927966 -0.1794563 -0.005351722 0.0699594 -0.1849351 -0.005088508 0.07318645 -0.1894661 -0.00509721 0.06427186 -0.1940609 -0.005109608 0.05524575 -0.1955497 -0.005410373 0.03842157 -0.1989646 -0.005126297 0.04562431 -0.2056874 -0.005156099 0.03246134 -0.2083962 -0.005475044 0.01312977 -0.2149574 -0.005494475 4.33102e-4 -0.2037457 -0.005847036 0.008353233 -0.08169257 -0.01041054 -0.06707328 -0.2092329 -0.005738914 -0.002466619 -0.1980405 -0.00615251 0.005490839 -0.2103925 -0.005181908 0.0232644 -0.2135291 -0.00520116 0.0171411 -0.2168077 -0.00522381 0.01074659 -0.2206274 -0.005250036 0.003305256 -0.04133033 -0.01123327 -0.0875191 -0.03276884 -0.01119613 -0.07794231 -0.1827136 -0.005754292 0.04939568 -0.06183803 -0.01100385 -0.07713073 -0.06751042 -0.01083731 -0.07425737 -0.1160033 -0.00929588 -0.04969286 -0.1357331 -0.00761044 0.02178448 -0.1275374 -0.007372856 0.05179435 -0.01731657 -0.01019692 0.07113903 -0.03959995 -0.00979048 0.05508553 -0.02271801 -0.01018059 0.06020367 2.29478e-6 -0.01076447 0.05552965 -0.003029763 -0.01062601 0.0639019 -0.01114463 -0.01069444 0.03843379 -0.1164761 -0.0073601 0.07352387 -0.1219987 -0.007364034 0.06265479 -0.06664258 -0.008930444 0.06194955 -0.06760245 -0.008707225 0.07610505 -0.1109709 -0.00736159 0.08440446 -0.1308838 -0.006767988 0.08765685 -0.1054866 -0.007369279 0.0952956 -0.04603743 -0.008806705 0.119875 -0.04074436 -0.008852005 0.1308708 -0.1000245 -0.007383704 0.1061991 0.04056107 -0.01093518 0.1580782 0.03001832 -0.01075959 0.1497439 0.03565084 -0.01092022 0.1468907 0.0215702 -0.01049727 0.1540233 0.02653342 -0.01051384 0.165184 0.03494983 -0.01077514 0.1609206 -0.04399657 -0.01123023 -0.08616852 -0.01088774 -0.01111733 -0.03638368 -0.01861625 -0.01113343 -0.03606516 -0.01506263 -0.01010948 -0.1008252 -0.01008683 -0.01016807 -0.08967339 0.05578464 -0.01102393 0.1777017 0.04541856 -0.01092404 0.169288 0.05100572 -0.01106882 0.1664578 -0.002402186 -0.01001125 0.131969 -0.01374626 -0.009616732 0.1377154 -0.004437923 -0.009356439 -0.09254473 -0.009819447 -0.009316623 -0.1034812 0.001062333 -0.007757961 -0.09533095 0.006192743 -0.003085494 -0.08979147 0.0111196 -0.007714569 -0.07643753 -0.07174015 -0.008206486 0.105544 -0.0771622 -0.008185386 0.09461802 0.001503705 -0.01088619 0.04791259 -0.005411684 -0.01075172 0.04460179 -0.004900097 -0.01084208 0.03527057 -0.01331734 -0.00988245 -0.1017093 -0.01155453 -0.009619891 -0.1026023 0.06695008 -0.01119685 0.1771104 0.05879306 -0.01102852 0.1812424 0.06134414 -0.01114958 0.1748855 -0.0759285 -0.007475674 0.1625453 -0.07978612 -0.007328271 0.1615964 -0.08118736 -0.007419347 0.1517928 0.005259394 -0.01008635 0.1486075 -0.07443034 -0.007342219 0.1721692 0.01274234 -0.003053247 -0.07748192 0.01617991 -0.003037333 -0.07100188 -0.06371921 -0.00736165 0.1933141 -0.0600869 -0.007635116 0.195427 -0.05840021 -0.007369518 0.2038147 -0.04399842 -0.007860004 0.2145091 -0.03158771 -0.007351934 0.2567451 -0.02817779 -0.007653176 0.2475143 -0.02283984 -0.00749135 0.2584498 -0.01750409 -0.007278919 0.2693941 -0.02623283 -0.007340431 0.2673161 -0.02087843 -0.007326006 0.2778863 -0.01552355 -0.007308781 0.2884574 -0.01212185 -0.007041931 0.2803038 -0.006768226 -0.006811976 0.2912198 -0.01016914 -0.007288753 0.2990276 -0.001354217 -0.006612896 0.3021506 0.05099797 -0.01045763 0.2053688 0.05456632 -0.01056277 0.2035612 0.06044089 -0.01039826 0.2151582 -0.06907457 -0.007353365 0.1827421 -0.07065826 -0.007534861 0.1734264 0.03632861 -0.01046246 0.1875573 0.0411663 -0.01038074 0.1987648 0.05073422 -0.00886482 0.2616565 -0.06539207 -0.007590174 0.1843668 0.05009424 -0.01047599 0.2035846 0.0500456 -0.01064884 0.1946368 0.04945099 -0.009222507 0.2491106 0.06525498 -0.009356915 0.2540521 0.06820058 -0.009827971 0.2396129 0.07277435 -0.009569406 0.2509194 0.0206595 -0.00820446 0.2636952 0.03167301 -0.00817579 0.2717396 0.06898421 -0.01024335 0.2255915 0.07355809 -0.009980738 0.236899 0.06357765 -0.01008921 0.2283303 0.004006087 -0.006479561 0.3130393 5.39258e-4 -0.007240116 0.3201671 -0.004814684 -0.007265865 0.3095978 0.08122915 -0.009804069 0.2467135 0.1381165 -0.01016885 0.2998173 0.1415554 -0.01071298 0.3118253 0.1332158 -0.01023524 0.3022998 0.1494672 -0.008985221 0.2803478 0.1445048 -0.009412348 0.2828616 0.1409825 -0.009228348 0.2709531 0.1460179 -0.008794903 0.2684023 0.137349 -0.009190499 0.2591243 0.1576625 -0.008652269 0.2899161 0.1544087 -0.008275806 0.2778447 0.1623941 -0.00727719 0.2875193 0.1325982 -0.009668767 0.2624479 0.1336085 -0.009270071 0.2473689 0.1297644 -0.009438395 0.2356795 0.1387788 -0.008825063 0.2447499 -0.007788658 -0.008850157 -0.1045099 -0.008632719 -0.009061753 -0.1040823 0.002515733 -0.003104269 -0.0966919 -0.006951391 -0.008607089 -0.104934 -0.005776286 -0.008211553 -0.1055293 -0.003647565 -0.007334947 -0.1066076 6.91038e-4 -0.003113687 -0.1001135 -0.02632254 -0.01094049 -0.09512144 -0.01574754 -0.01065695 -0.08675682 -0.02142268 -0.01095104 -0.08383625 0.0232408 -0.003006994 -0.05764281 0.02702701 -0.002992868 -0.05044198 0.02390211 -0.007667124 -0.05224812 0.06140786 -0.002965867 0.01691138 0.06311661 -0.00297147 0.02039182 0.05725359 -0.007633864 0.01285815 0.05015403 -0.00294882 -0.005631744 0.05276888 -0.002950072 -4.46074e-4 0.04631429 -0.007624745 -0.008938848 0.005711078 -0.01108813 0.01195961 0.0177403 -0.01108026 0.01920467 0.0112282 -0.01120543 0.02285099 0.01284772 -0.01107478 0.008344531 -0.03203946 -0.01112461 -0.09222549 -0.0296685 -0.01106238 -0.09342646 -0.03606033 -0.01119786 -0.09018862 0.0297302 -0.00298351 -0.04528456 0.03241765 -0.002975285 -0.04013758 0.02955859 -0.007650434 -0.04144912 -0.02704811 -0.01111888 -0.08081543 -0.02361381 -0.01080948 -0.09649354 -0.02077466 -0.01063275 -0.09793174 -0.01840758 -0.01045048 -0.0991308 0.01250958 -0.009288668 -0.06063777 0.01181983 -0.01008605 -0.04831367 -0.004484713 -0.007706701 -0.1061835 -0.003326117 -0.007152199 -0.1067705 -0.003021121 -0.006937146 -0.1069249 -0.002742409 -0.006681501 -0.1070661 -0.002500295 -0.006382644 -0.1071888 -0.002303361 -0.006044328 -0.1072885 -0.002158761 -0.005674898 -0.1073618 -0.001134455 -0.003123223 -0.1035347 -0.002081573 -0.005280911 -0.1074008 -0.002090752 -0.004877507 -0.1073963 -0.002183854 -0.004487693 -0.107349 -0.002338051 -0.004122376 -0.107271 -0.002582788 -0.003685235 -0.107147 -0.002960741 -0.00313282 -0.1069555 0.01821887 -0.007686793 -0.06303304 0.0200991 -0.003020167 -0.06359726 0.005200266 -0.01057928 -0.04718333 -0.005756974 -0.01104146 -0.0405156 -1.6087e-4 -0.01087313 -0.04362922 0.0269221 -0.01053535 -0.00530827 0.00245428 -0.01108449 -0.01217311 0.01630288 -0.01100045 0.002195775 0.02153664 -0.01083052 -0.001759231 0.04965204 -0.009235084 0.01145976 0.05503946 -0.01007556 0.0367648 0.04304343 -0.01055175 0.02689164 0.03732895 -0.01084697 0.02978634 0.03456181 -0.01102077 0.03861856 0.05831229 -0.01061117 0.0583896 0.04801768 -0.01088392 0.05172508 0.02859205 -0.01109963 0.04104733 0.01674574 -0.01130646 0.0337432 0.0231918 -0.011087 0.0301125 0.03393673 -0.01111865 0.0520125 0.02226287 -0.01139122 0.04463452 0.05789738 -0.01094758 0.07266771 0.05083554 -0.01110154 0.07246333 0.03922134 -0.01114463 0.06301039 0.07585513 -0.01077389 0.09689784 0.04444062 -0.01117813 0.07404249 0.03329706 -0.01151192 0.06641721 0.04153865 -0.01156002 0.08268713 0.073798 -0.01110237 0.1078904 0.08555847 -0.01033014 0.1033295 0.05425703 -0.01126331 0.09528833 0.06900465 -0.01127797 0.1128477 0.04984837 -0.01157087 0.09909123 0.05966854 -0.01131886 0.1073668 0.1156879 -0.003456354 0.139123 0.1178082 -0.003452003 0.1445603 0.1122195 -0.008023202 0.1354494 0.0553655 -0.01155799 0.1099826 0.06459701 -0.0113638 0.1185495 0.1166921 -0.007993578 0.1468486 0.1199156 -0.003438591 0.1500234 0.1219707 -0.003416836 0.1554226 0.06088215 -0.01152884 0.120873 0.08545958 -0.01116782 0.1353345 0.09106749 -0.01087808 0.1324937 0.09570497 -0.01086717 0.143815 0.06945288 -0.01139634 0.129768 0.1260459 -0.003346741 0.1663191 0.1210708 -0.007925927 0.1582885 0.1241263 -0.003386139 0.1611482 0.06722795 -0.01147902 0.1334003 0.1002602 -0.0108233 0.1551723 0.09012156 -0.01115566 0.1466434 0.07423591 -0.01140952 0.1410199 0.08453512 -0.01132065 0.1494732 0.07743257 -0.01134371 0.1535452 0.09470462 -0.01111036 0.1579865 0.07984876 -0.01133352 0.1381767 0.08914619 -0.01127451 0.1608022 0.08501803 -0.01121395 0.1685197 0.09368222 -0.01118814 0.1721624 0.1047328 -0.0107395 0.1665647 0.1145977 -0.01013749 0.1752166 0.1091219 -0.01060885 0.1779904 0.09920901 -0.01102489 0.1693628 0.1036339 -0.01089233 0.1807704 0.1426426 -0.002657055 0.2139117 0.1376168 -0.007198989 0.2044495 0.1414313 -0.00271207 0.2102285 0.1079794 -0.01070576 0.1922082 0.09814292 -0.01105451 0.1835519 0.09398293 -0.01101213 0.1862174 0.1025286 -0.01086676 0.1949693 0.1047908 -0.01072049 0.2075532 0.1462082 -0.002506852 0.2249845 0.1414987 -0.00696659 0.2161064 0.1450309 -0.002554476 0.2212896 0.1259286 -0.009660661 0.2243362 0.1122447 -0.01046752 0.2036775 0.117648 -0.01018834 0.2009404 0.1164259 -0.01020288 0.2151839 0.1309287 -0.009224534 0.2208479 0.140206 -0.008240163 0.2303901 0.1349961 -0.008988082 0.2330293 0.1105325 -0.01053404 0.2188879 0.1160491 -0.01034212 0.2297784 0.1205191 -0.009940564 0.2267338 0.124521 -0.009709298 0.2383355 0.1215653 -0.01013398 0.2406679 0.1562435 -0.002475082 0.258409 0.1572943 -0.002527773 0.2621409 0.1559088 -0.006657838 0.263392 0.1593552 -0.002682745 0.2696152 0.1603661 -0.002781271 0.2733584 0.1270815 -0.00990951 0.2515575 0.1424537 -0.008751094 0.2565385 0.163312 -0.003181636 0.284605 0.1592145 -0.00687915 0.2754102 0.1623449 -0.003029167 0.2808531 0.1527974 -0.009350717 0.2923806 0.1479119 -0.009771227 0.2948554 0.1395316 -0.009669244 0.2853808 0.1686963 -0.004404366 0.307205 0.1695107 -0.004653513 0.3109894 0.168193 -0.008562088 0.3120941 0.1709256 -0.005085647 0.3185994 0.1715651 -0.005297303 0.3224174 0.1731047 -0.005830049 0.3339302 0.1704758 -0.009202897 0.3246787 0.172679 -0.005688309 0.3300823 0.1721597 -0.005506038 0.3262448 0.1660102 -0.01050066 0.3269408 0.1614184 -0.01115983 0.3292669 0.1589301 -0.01056343 0.3167863 0.1430155 -0.01002418 0.2973357 0.1463733 -0.01057064 0.3093847 0.1542146 -0.01096934 0.319175 0.1568074 -0.01155674 0.3316025 0.1511888 -0.01032191 0.3069454 0.1283149 -0.01024574 0.3047824 0.1319156 -0.01078855 0.3167084 0.123414 -0.01021391 0.3072649 0.1367356 -0.01077824 0.3142668 0.1400297 -0.01141721 0.3263604 0.1494885 -0.01121348 0.321569 0.1521862 -0.01179546 0.3339434 0.14476 -0.01135313 0.3239643 0.1352993 -0.0114274 0.3287567 0.1270957 -0.01075726 0.31915 0.1475626 -0.01193201 0.3362856 0.1429374 -0.01199465 0.3386285 0.1497973 -0.01229155 0.3488453 0.1222761 -0.0106936 0.3215914 0.1185134 -0.01014918 0.3097474 0.1452994 -0.0123524 0.3511237 0.1383119 -0.01200461 0.3409717 0.1305689 -0.01139658 0.3311529 0.1336864 -0.01197451 0.3433147 0.1290613 -0.01191347 0.3456576 0.1258388 -0.01133418 0.333549 0.1469544 -0.01233237 0.3638941 0.1408012 -0.01236212 0.3534023 0.121109 -0.01124691 0.3359449 0.1163795 -0.01113998 0.3383406 0.1106637 -0.01044887 0.3274954 0.1179073 -0.01167732 0.3512994 0.1244364 -0.01182812 0.3480004 0.1097426 -0.01096475 0.3416763 0.1010344 -0.01017606 0.3323642 0.1086733 -0.01141607 0.3559798 0.09982866 -0.01066237 0.3467246 0.1523433 -7.7447e-4 0.4261723 0.1442096 0.004001736 0.4413577 0.142007 0.003361761 0.4424734 0.09952121 -0.01112365 0.3606176 0.1435901 -0.01053476 0.3924447 0.1475028 -0.01052635 0.3904626 0.1460741 -0.008425533 0.4043613 0.1030867 -0.01150572 0.3725047 0.1252982 -0.01149231 0.3883574 0.1234591 -0.01203483 0.3757928 0.1311486 -0.01162707 0.3853961 0.08697259 -0.01069384 0.366978 0.0908693 -0.01108723 0.378696 0.1062323 -0.01151597 0.3845205 0.09441381 -0.01111102 0.3905092 0.05917423 -0.009699344 0.3810654 0.1088242 -0.0109961 0.3967036 0.0677064 -0.01025843 0.3904314 0.06495833 -0.009449541 0.3643885 0.09756183 -0.01061022 0.4024099 0.07258403 -0.009716391 0.415064 0.03916728 -0.008532762 0.3774274 0.04073429 -0.009051203 0.3903952 0.04932725 -0.009608328 0.3997355 0.06834775 -0.01017826 0.4037153 0.08609431 0.01355963 0.4901704 -0.1534385 -0.005706608 0.1069647 -0.1619374 -0.006022036 0.07605296 -0.1676538 -0.005715429 0.07894867 -0.1399831 -0.005741834 0.1336855 -0.127027 -0.005824387 0.1593875 -0.1226858 -0.005858838 0.1700417 -0.002986073 -0.006511867 0.385044 -0.007423996 -0.006039023 0.3773276 -0.001823723 -0.006976604 0.3982175 0.004231989 -0.00765258 0.4088909 0.01041239 -0.008129894 0.4194518 0.01676362 -0.008256912 0.4298433 0.03017288 -0.006853401 0.4498971 0.06223142 0.004766225 0.4828844 0.0373252 -0.005021214 0.4594489 0.04490303 -0.0023548 0.4684512 0.08832418 0.01400363 0.489923 0.09053701 0.01440036 0.4895778 0.05312848 9.72181e-4 0.4764303 0.09273278 0.01474994 0.4891348 0.08302468 0.01226562 0.4893442 -0.1923567 -0.006392359 0.002618849 -0.1979482 -0.006210565 -0.008183002 -0.1562188 -0.006263256 0.07315617 -0.1477211 -0.006013274 0.1040682 -0.1342845 -0.006048083 0.1307676 -0.1341977 -0.0062716 0.1166746 -0.1229668 -0.006123125 0.1529015 -0.1171887 -0.006131172 0.1672571 -0.002684414 -0.006247401 0.3749268 0.001831948 -0.006715118 0.3826034 0.002902448 -0.007230043 0.3958234 0.008852958 -0.007900416 0.4065501 0.01490664 -0.008370935 0.4171752 0.02110177 -0.008489549 0.4276458 0.05596262 8.20181e-4 0.4749947 0.0645107 0.004643976 0.4817298 0.0409488 -0.005215525 0.4576134 0.07305401 0.008690774 0.4869518 0.04817694 -0.002530336 0.4667928 -0.1866691 -0.006603002 -2.60966e-4 -0.1922782 -0.00644344 -0.01105523 -0.1784045 -0.006331026 0.02973651 -0.1451824 -0.006255388 0.09489995 -0.1284835 -0.006483137 0.11378 -0.1178421 -0.006352245 0.1494103 -0.1259979 -0.006301581 0.1330288 0.002428412 -0.00643903 0.3723368 0.008540332 -0.006962299 0.3792206 0.007631361 -0.00742954 0.3934279 0.01347655 -0.008095443 0.404208 0.01940274 -0.008560597 0.4148977 0.03162688 -0.008279144 0.4358097 0.02544087 -0.008672595 0.4254478 0.06773352 0.004510343 0.4800983 0.06022059 6.43738e-4 0.4728378 0.03799283 -0.007228076 0.4459358 0.0445733 -0.005368411 0.4557774 0.05145174 -0.002668499 0.4651339 0.08460927 0.012196 0.4885407 -0.1809586 -0.006804227 -0.003161311 -0.1866073 -0.006673514 -0.01392787 -0.172701 -0.006542205 0.02684736 -0.1505032 -0.006474852 0.07026094 -0.1394651 -0.006467044 0.09200382 -0.1199066 -0.006783962 0.1094354 -0.1175698 -0.006528258 0.1355969 -0.1031358 -0.006683588 0.1601385 0.0137937 -0.007658362 0.3903541 0.03172105 -0.008903563 0.4222673 0.05619376 -0.002842843 0.4627321 0.03762692 -0.008499801 0.432771 0.04309904 -0.007416009 0.4433513 0.07611113 0.008559048 0.4854038 0.04980951 -0.005560994 0.4531254 -0.1752679 -0.007002234 -0.006050705 -0.1809372 -0.006900608 -0.01680004 -0.1619853 -0.006943643 0.01971131 -0.1090057 -0.006828606 0.1312586 -0.09874814 -0.006956338 0.146576 0.01406252 -0.006843686 0.3664435 -0.1695671 -0.007199287 -0.008999109 -0.1752672 -0.0071249 -0.01967227 -0.09320396 -0.007041811 0.1551074 0.03003197 -0.007701754 0.3682584 -0.1638433 -0.007395267 -0.01179659 -0.1695963 -0.007346272 -0.02254492 -0.09458619 -0.007405459 0.1171169 -0.08917373 -0.007435142 0.12805 0.02195554 -0.007108807 0.3624451 0.06256908 -0.008089244 0.4334854 0.08393388 0.003947854 0.4718902 0.0907154 0.01198405 0.4854472 -0.1581492 -0.00759238 -0.01468098 -0.1639253 -0.007564723 -0.02541756 0.02544122 -0.007134735 0.3569 0.01660162 -0.007145881 0.3518759 0.02010971 -0.006734311 0.3458803 0.05153727 -0.009587585 0.4122285 0.05657595 -0.009153962 0.4231716 0.0747345 -0.006423473 0.4405004 0.08665418 0.008192777 0.4800618 0.07871139 -0.003621935 0.4513267 0.08189892 -1.07611e-4 0.4618568 -0.1496075 -0.00789082 -0.0190078 -0.1559944 -0.007865965 -0.02943509 -0.1469069 -0.007654428 1.18032e-4 -0.0723927 -0.007870554 0.1332254 -0.04922842 -0.007857561 0.2035436 -0.04241174 -0.007367372 0.2353773 -0.03881138 -0.007827818 0.2255098 -0.03346121 -0.007764518 0.2365413 -0.0369426 -0.007360637 0.2461739 0.009386539 -0.006435453 0.3239607 0.005893647 -0.007211565 0.3307372 0.01475596 -0.006510794 0.3349035 0.01124763 -0.007180154 0.3413066 -0.09931588 -0.007959485 0.06483125 -0.08809161 -0.008163869 0.07281476 -0.1382189 -0.008292615 -0.02477687 -0.1432411 -0.008337855 -0.03589534 -0.1131649 -0.007978439 0.03768116 -0.0883314 -0.007968485 0.08660548 -0.09912127 -0.008166253 0.05106598 -0.06635069 -0.008235394 0.1164888 -0.05344873 -0.008200585 0.157827 -0.06136792 -0.00811696 0.1413179 -0.02957022 -0.008548974 0.1936038 -0.04558795 -0.008282721 0.1743646 -0.03474539 -0.008525013 0.1825505 -0.02440714 -0.0085482 0.2046588 -0.006859838 -0.008400022 0.2368238 -0.01200067 -0.00851643 0.2257945 -0.00376898 -0.008161604 0.2488152 0.01178622 -0.007465064 0.2818133 0.001411259 -0.007944226 0.2598212 0.02367985 -0.007171273 0.3030492 0.02725917 -0.007063269 0.3148906 0.03236824 -0.007129311 0.3259722 0.03942495 -0.00741291 0.3360832 0.04451698 -0.007804751 0.3472237 0.04903519 -0.008371412 0.3586884 0.0783137 -0.008644104 0.4255119 -0.1155075 -0.008879363 -0.02261888 -0.1003031 -0.008435249 0.03116589 -0.07858008 -0.008698463 0.05432736 -0.04139703 -0.008628308 0.1517221 -0.02510797 -0.009012639 0.1639904 -0.00466156 -0.009036839 0.2083213 0.03073835 -0.007752239 0.2858419 0.1001575 -0.009425818 0.4144459 -0.1270716 -0.008914589 -0.04408609 0.11202 -0.007742345 0.421611 0.1107881 -0.009790122 0.4090599 -0.07767373 -0.008932709 0.0402016 -0.04660046 -0.009190678 0.08597302 -0.04121959 -0.009214818 0.09692102 -0.04495424 -0.009000122 0.1056503 -0.007292032 -0.00950551 0.1686438 -0.02579963 -0.00918734 0.1438211 0.002823472 -0.009520769 0.1908649 -0.002220213 -0.009525775 0.1797494 0.02631199 -0.009236693 0.233611 0.02776372 -0.008885383 0.2464721 0.05853009 -0.008183002 0.2990322 0.0602377 -0.008127391 0.3118447 0.09933155 0.007741868 0.4736422 0.1039061 0.003235578 0.4617752 -0.07886672 -0.009202182 0.02030718 0.05101346 -0.008150696 0.2892045 0.0744313 -0.009281456 0.3458248 0.10526 -9.42286e-4 0.4500235 0.1001071 0.01165145 0.4806914 -0.02680587 -0.009493291 0.1101331 0.06933236 -0.008483111 0.3209404 0.1170149 -0.01125788 0.3925542 0.07390612 -0.008856475 0.3323431 0.1185317 -0.0100376 0.405137 0.1123861 -0.004813253 0.4342664 0.1034659 -0.004507362 0.4387859 -0.09559315 -0.009478032 -0.02587532 -0.08147591 -0.009563982 -0.007407844 -0.04558628 -0.00940299 0.07178777 -0.05652397 -0.009388387 0.04998928 -0.05775022 -0.009539544 0.03694248 -0.02154302 -0.009537518 0.1211442 -0.006040453 -0.009693384 0.1543315 0.02674913 -0.009900212 0.2060663 0.02185773 -0.00998032 0.1948804 0.02400481 -0.009505569 0.2211072 0.04844248 -0.008384287 0.2768737 0.1147943 -0.01178956 0.380183 0.1192055 -0.007972061 0.4179709 0.0874983 -0.01025134 0.3529693 0.1021659 -0.007404565 0.4266033 -0.02874302 -0.009817242 0.07692718 0.01030677 -0.01012301 0.1597289 0.06288838 -0.008884966 0.2695699 0.1318534 -0.01038551 0.3983899 0.1263386 -0.01025861 0.4011816 0.1233451 0.007307648 0.4614764 0.1329106 0.002655923 0.4470813 0.1351907 0.002723276 0.4459263 0.1264477 -0.008177101 0.4143018 -0.06168389 -0.00985527 0.008186757 -0.05337333 -0.009790301 0.02789217 -0.02070498 -0.009854495 0.09336662 -0.008519172 -0.01005488 0.1077083 -0.01016372 -0.009933233 0.1153799 0.02027976 -0.01013332 0.1820223 0.01531225 -0.01014095 0.1708682 0.03910976 -0.01002979 0.213441 0.03983312 -0.009708225 0.2267282 0.04465633 -0.009478151 0.237915 0.06750786 -0.00872296 0.2808607 0.07349437 -0.008589327 0.3051445 0.1119707 -0.01178967 0.3680037 0.08976656 -0.009814143 0.3380675 0.1200318 -0.001420199 0.442539 0.1254178 -0.005205988 0.4276645 0.1256651 -0.001564741 0.4396854 -0.01196038 -0.01022022 0.08209955 0.0739299 -0.008711099 0.2912573 0.08284956 -0.008946299 0.3140986 0.08720374 -0.009312212 0.3256119 0.1121773 0.01201206 0.4745758 0.1053119 0.01354336 0.4801027 0.1022293 0.01388514 0.4824308 0.1319656 -0.005352079 0.4243471 0.1055455 0.007526159 0.4704932 -0.0502839 -0.01018327 0.00582832 -0.0391606 -0.01016747 0.02752578 -0.02809715 -0.01021474 0.04584139 -0.006653666 -0.01025098 0.09308677 -0.001400172 -0.01028978 0.1041021 0.006105661 -0.01029717 0.1276592 0.0165593 -0.01046186 0.1428834 0.03145211 -0.01050454 0.1763628 0.05073428 -0.01007044 0.2212062 0.07516038 -0.009278774 0.2633616 0.05546808 -0.009837388 0.2324382 0.08342242 -0.008918762 0.3001183 0.114391 -0.001249015 0.4453967 0.1142481 0.002892732 0.4565351 -0.008744239 -0.01046311 0.06679666 0.01177799 -0.01047921 0.1247859 0.07964879 -0.009112656 0.2747182 0.08406758 -0.00903505 0.2861257 0.09271055 -0.009261429 0.3091058 0.09691321 -0.009622573 0.3206957 0.1209592 -0.01204407 0.3634487 0.1336911 -0.008338689 0.410632 0.1195068 0.007233262 0.4634202 0.1283485 0.00262016 0.4493923 0.1306295 0.002625048 0.4482368 0.118867 -0.005020439 0.4309833 -0.04170835 -0.01044952 0.001484274 -0.03058004 -0.01043391 0.02317923 -0.01958149 -0.01043695 0.04494506 0.001902222 -0.01051664 0.08875274 0.009750247 -0.01057636 0.1052923 0.01745057 -0.01065236 0.1219124 0.0250349 -0.01072502 0.13859 0.03983169 -0.01076471 0.1721181 0.04643225 -0.01069843 0.1875039 0.09350723 -0.009224772 0.2950144 0.1273078 -0.01219046 0.3602375 0.1357651 -0.01045769 0.3964084 0.131352 -0.001667618 0.436804 0.1098954 0.007392108 0.4682894 -0.07318264 -0.01066792 -0.07138401 -0.03041028 -0.01060277 0.009426832 -0.01934164 -0.01059597 0.03115427 0.004973709 -0.01066219 0.0803588 0.01283878 -0.01071751 0.09688925 0.02626264 -0.01093554 0.1106083 0.02312332 -0.01081413 0.1190388 0.03068566 -0.01088613 0.1357276 0.0513575 -0.01084041 0.185009 0.05366253 -0.01058268 0.2017771 0.06828814 -0.01061356 0.211183 0.07891589 -0.01011955 0.234185 0.08564239 -0.009575009 0.2580673 0.09000355 -0.009405493 0.2694826 0.09429532 -0.009324371 0.2809522 0.1026472 -0.009542703 0.3040767 0.1318053 -0.01227349 0.3579593 0.1067054 -0.009899795 0.31574 0.1533254 -0.008269369 0.4006881 0.1569486 -0.008082151 0.3988527 0.1529762 -0.005120217 0.4137058 0.1295893 -0.01217609 0.3726906 0.1397429 0.003036737 0.4436203 0.149527 -0.001178681 0.4275988 0.1388211 -0.008409738 0.4080354 0.1365994 -0.005416154 0.4220016 -0.0415138 -0.01079022 -0.02594304 -0.02028703 -0.01068979 0.0203858 0.008024275 -0.0107969 0.07197612 0.01593661 -0.01084399 0.08848148 0.02113127 -0.01088607 0.09952718 0.03133046 -0.01098668 0.1217216 0.03633671 -0.01103252 0.132865 0.04128366 -0.01106613 0.1440373 0.04617267 -0.01108056 0.1552356 0.05659323 -0.01119512 0.1636274 0.07439112 -0.01038342 0.2228526 0.1005817 -0.00941056 0.2914184 0.1477423 -0.01177644 0.3769904 0.1518908 -0.01172024 0.374889 0.1514153 -0.01047337 0.3884807 0.1339302 -0.0122562 0.3704916 0.1352967 -0.01170361 0.3832948 0.1296601 0.00820285 0.4582775 0.1229349 0.01091045 0.4651345 0.120094 0.01143246 0.4677495 0.1424473 -0.008433282 0.4061985 0.1398751 -0.005437433 0.4203423 0.1353564 -0.001696765 0.4347771 0.1251251 0.002643644 0.4510241 0.1205599 0.002726197 0.453337 0.1131041 0.007309615 0.4666637 -0.03517603 -0.01088649 -0.02449721 -0.02252376 -0.01085025 4.79713e-4 0.02176582 -0.01100617 0.08791208 0.02826166 -0.01103907 0.1007354 0.0337882 -0.01106637 0.1116455 0.04033696 -0.01109558 0.1245734 0.05178469 -0.0112074 0.1523928 0.07582873 -0.0107792 0.2073633 0.07967633 -0.0105111 0.2198287 0.08868759 -0.009977996 0.2428583 0.09303516 -0.009746313 0.2542849 0.09731131 -0.009574413 0.2657555 0.1015116 -0.009490966 0.2772781 0.1056319 -0.009524703 0.2888602 0.1096675 -0.009704411 0.3005087 0.1174569 -0.01060467 0.3240326 0.1136132 -0.01005876 0.3122296 0.1363032 -0.01233285 0.3556808 0.1382714 -0.01231348 0.3682925 0.139445 -0.01175838 0.3811935 0.1396778 -0.01050931 0.3944265 0.1143153 0.01235711 0.4728325 0.1172269 0.01190811 0.470315 0.09910625 0.01420021 0.4847124 0.09594047 0.01448845 0.4869472 0.1381932 -0.001690685 0.4333401 0.1045762 0.01153331 0.4784278 0.05036938 -0.01113873 0.1443784 0.0558964 -0.01115971 0.1552894 0.061423 -0.01117908 0.1661995 0.08963257 -0.01033955 0.2287564 0.08657419 -0.0105704 0.2158505 0.09399271 -0.01007586 0.240171 0.1024971 -0.009670078 0.2631286 0.09828269 -0.00984317 0.2516267 0.1066317 -0.00958544 0.2746845 0.1106824 -0.009617865 0.2863018 0.1146447 -0.009796261 0.2979875 0.1426128 -0.01234173 0.3660933 0.1435936 -0.01178532 0.379092 0.1281186 0.007754743 0.4590583 0.1265325 0.007527112 0.4598618 0.1113842 0.01178151 0.4749774 0.1163005 0.007251977 0.4650444 0.0809586 -0.01087236 0.2047647 0.09219026 -0.01031434 0.2269372 0.09780633 -0.01010411 0.2380239 0.1034228 -0.009939789 0.2491115 0.1090394 -0.009821355 0.2601991 0.1117522 -0.009653031 0.2720907 0.1157333 -0.009684562 0.2837432 0.1196222 -0.009861946 0.295466 0.1512957 -0.0122736 0.361695 0.1466991 -0.001422107 0.4290313 0.1497032 -0.005289316 0.4153638 0.1431517 -0.0054304 0.4186825 0.10975 0.01159393 0.4758054 0.1249411 0.007390141 0.4606679 0.1146559 -0.009748756 0.2712867 0.1202729 -0.009721994 0.2823752 0.1246 -0.009894311 0.2929445 0.129578 -0.009883642 0.2904229 0.1247346 -0.009729146 0.2801151 0.159973 -0.01192134 0.3572994 0.1542937 -0.01215875 0.3465676 0.1587877 -0.01192653 0.3442911 0.1556354 -0.01214545 0.3594967 0.1560378 -0.01159775 0.3727883 0.1553264 -0.01035785 0.3864995 0.1550819 2.14302e-5 0.424785 0.1594947 -0.004372179 0.4104038 0.1497004 -0.008376419 0.4025244 0.1464283 -0.005386054 0.4170227 0.1410291 -0.00165224 0.4319036 0.1217483 0.00726056 0.4622852 -0.004682242 -0.01109838 -0.008558034 0.02777999 -0.0114597 0.05552583 0.1291955 -0.009679794 0.2778554 0.1601827 -0.01138365 0.3706887 0.1592354 -0.01015591 0.3845194 0.143865 -0.001568496 0.430467 0.1105689 0.01166445 0.4753905 0.1069069 0.01151388 0.4772463 0.08787721 -0.003165841 0.07302302 0.08946138 -0.003186702 0.07656216 0.0834791 -0.007784068 0.0679444 0.09260272 -0.003229618 0.08365285 0.09415972 -0.003251135 0.08720457 0.08849012 -0.0078395 0.07908648 0.09341424 -0.007897794 0.0902726 0.08794206 -0.009488105 0.09304457 0.08151412 -0.00941658 0.07850766 0.07544326 -0.01021808 0.08032596 0.0815469 -0.01082867 0.1099634 0.08634799 -0.01086288 0.1212096 0.08071893 -0.01115375 0.1240611 0.07508689 -0.01132005 0.126914 0.1058034 -0.01034617 0.1523643 0.115733 -0.009477198 0.1609925 0.1102444 -0.01026511 0.1637727 0.1336553 -0.009574055 0.2755962 0.1345556 -0.009816229 0.2879014 0.1643009 -0.01154881 0.3551071 0.1632717 -0.01154059 0.3420197 0.1686108 -0.01093012 0.3529239 0.1643183 -0.01102763 0.3685937 0.1631358 -0.009820163 0.3825436 0.1605638 -0.007770955 0.3970214 0.1562423 -0.004839062 0.4120513 0.1337435 0.008660256 0.4542158 0.1311195 0.009250462 0.4570114 0.1374691 0.002840995 0.4447722 0.1085608 0.01153779 0.476409 0.03616547 -0.00296539 -0.03293055 0.03518307 -0.007637441 -0.03063303 0.04135698 -0.0029549 -0.02287602 0.0451579 -0.002950429 -0.01546347 0.0475189 -0.002949118 -0.01082813 0.04077011 -0.007628679 -0.01979708 0.05181092 -0.007626295 0.001945972 0.05624133 -0.002954185 0.006488084 0.05796915 -0.002957403 0.009960055 0.06988817 -0.003002047 0.03434693 0.0679574 -0.007669687 0.03477907 0.06820559 -0.002993106 0.03085321 0.07489067 -0.00303477 0.04484993 0.07320815 -0.007699131 0.04579412 0.07323056 -0.003022968 0.04134589 0.07818758 -0.003061413 0.05186969 0.07982361 -0.003076314 0.05538588 0.08307129 -0.003109216 0.06242835 0.08468258 -0.003127098 0.06595593 0.07838386 -0.00773704 0.05684834 0.1058705 -0.003403842 0.1147526 0.1029974 -0.007995665 0.1127757 0.1033083 -0.003374397 0.1085961 0.1084756 -0.003427028 0.121098 0.1076542 -0.008021652 0.1240916 0.1112859 -0.003446698 0.1280397 0.1135581 -0.003454446 0.1337311 0.131993 -0.00316447 0.1827263 0.1295409 -0.007649362 0.181286 0.1300322 -0.003235399 0.1772482 0.1350185 -0.003032207 0.1913233 0.1336296 -0.007436156 0.1928448 0.1377279 -0.002900779 0.199202 0.1389729 -0.002839446 0.2028736 0.1188632 -0.009956419 0.1866949 0.1134273 -0.01042431 0.1894485 0.1496655 -0.00241363 0.2360919 0.1452729 -0.00676763 0.2278235 0.1485251 -0.002436935 0.2323852 0.1381143 -0.009411811 0.2733375 0.1739658 -0.006124973 0.3455334 0.1740657 -0.00613898 0.3494039 0.1720797 -0.009637475 0.3375579 0.1728022 -0.00971198 0.3508007 0.1740038 -0.006057381 0.3571544 0.1738425 -0.005961656 0.3610351 0.1684367 -0.01043641 0.3665075 0.1707974 -0.008164823 0.3786626 0.16702 -0.009262621 0.3805761 0.167665 -0.006236672 0.3934243 0.1641638 -0.007254183 0.3951978 0.1626579 -0.003452897 0.4088015 0.05450803 -0.002951741 0.003018975 0.05969101 -0.002961277 0.01343387 0.06481951 -0.002977848 0.02387636 0.06263738 -0.007648169 0.02380132 0.08628416 -0.003145992 0.06948733 0.09103697 -0.003208518 0.0801056 0.09570741 -0.00327301 0.09075993 0.09877538 -0.00331664 0.09788221 0.1002959 -0.003336489 0.1014502 0.09825026 -0.007952094 0.1015022 0.1280555 -0.003296375 0.1717904 0.1253541 -0.007813453 0.1697679 0.1438427 -0.002604544 0.2175993 0.1473731 -0.002466678 0.2286832 0.1507935 -0.002396762 0.2398015 0.1489346 -0.006630718 0.2396053 0.1541016 -0.002410054 0.2509543 0.152481 -0.006584584 0.2514591 0.1530119 -0.002393066 0.247233 0.1734611 -0.005950093 0.3377885 0.1735841 -0.005817949 0.3649045 0.172442 -0.009272456 0.3644786 0.1727663 -0.00537467 0.372595 0.1722145 -0.005084395 0.3764269 0.1699923 -0.003936469 0.3877883 0.1690621 -0.00346136 0.3915238 0.1657006 -0.001813948 0.402542 0.164389 -0.001205921 0.4061366 0.1598773 7.68281e-4 0.4166826 0.1581778 0.001439034 0.4200982 0.1504243 0.00418508 0.4332671 0.1482539 0.004850864 0.4364157 0.1363122 0.008053064 0.4513756 0.1388167 0.007435739 0.4484838 0.03867459 -0.002959847 -0.02808201 0.03355485 -0.01004356 -0.006383776 0.07156288 -0.003012061 0.03784465 0.07654368 -0.003047525 0.04835748 0.08145135 -0.003092229 0.05890512 0.09196466 -0.01037943 0.1183645 0.09666293 -0.01039642 0.1296593 0.1012762 -0.01038765 0.1409929 0.136472 -0.002960503 0.1955336 0.1402077 -0.002776563 0.2065494 0.1230393 -0.009724318 0.1982094 0.1551788 -0.002437412 0.2546796 0.1583314 -0.002598226 0.2658764 0.1613633 -0.002893924 0.277104 0.1642651 -0.003351271 0.2883606 0.166117 -0.00373739 0.2958815 0.1669996 -0.003946304 0.2996515 0.1654318 -0.007869064 0.2997305 0.1702406 -0.00487107 0.3147897 0.1559937 -0.009908318 0.3045114 0.1740782 -0.006116449 0.3532773 0.1715682 -0.004748284 0.3802518 0.1680374 -0.002940118 0.3952376 0.1629818 -5.63989e-4 0.4096956 0.1563819 0.002124309 0.4234696 0.1459879 0.005512952 0.4395085 0.02762383 -0.00924617 -0.03177225 0.03872168 -0.009230792 -0.01021456 0.06651568 -0.00298506 0.02736324 0.06038278 -0.009263515 0.03329306 0.07085561 -0.009320795 0.0552752 0.1018065 -0.003355741 0.1050209 0.0927931 -0.009538054 0.1042665 0.0975579 -0.009576499 0.1155312 0.1022351 -0.009596526 0.1268367 0.1068241 -0.009591221 0.1381825 0.1113236 -0.00955373 0.149568 0.1200509 -0.00935465 0.1724543 0.1242764 -0.009179294 0.1839528 0.1284083 -0.008953571 0.1954898 0.1333287 -0.008644461 0.2096447 0.1519098 -0.002386331 0.2435159 0.1439274 -0.008085906 0.2421418 0.1475372 -0.008021354 0.2539634 0.1510322 -0.008075058 0.2658623 0.1678595 -0.004168629 0.3034263 0.1607785 -0.009221434 0.3020877 0.1636261 -0.009889304 0.3144075 0.1737483 -0.006048381 0.3416563 0.1677371 -0.01089954 0.3397578 0.1732228 -0.005619168 0.3687542 0.1544883 0.002824068 0.4267952 0.1436295 0.006171226 0.4425472 0.1284479 0.009819447 0.4597659 0.1113578 0.01277935 0.4753037 0.09724587 -0.003295242 0.0943188 0.1652033 -0.003538072 0.2921182 0.1708274 -0.004365503 0.3840304 0.166917 -0.00238794 0.3989136 0.1614795 1.11971e-4 0.413221 0.1525018 0.003515541 0.4300636 0.1412552 0.006808519 0.4455412 0.1257197 0.01037275 0.4624729 0.1083553 0.01317471 0.4777259 0.1297478 -8.66802e-4 0.1833342 0.1301671 -0.003230214 0.1776227 -0.03792762 0.0144695 0.0433641 -0.04301035 0.0142312 0.04099571 -0.04913389 0.01366394 0.04424142 -0.05013084 0.01396012 0.03461414 -0.05018311 0.013341 0.04981261 -0.0275467 0.01509028 0.03312242 -0.02038621 0.01514863 0.03960382 -0.07373172 0.01009237 0.06444978 -0.03909933 0.0136457 0.06419944 -0.08850806 0.004947245 0.1156584 -0.09562444 0.003945648 0.1167632 -0.04321837 0.01296633 0.07144242 -0.04729366 0.01260113 0.07101398 -0.07640832 0.007441341 0.1014043 -0.009068846 0.01507902 0.03891563 -0.008190929 0.01513242 0.04845237 -0.07880717 0.007953524 0.08887112 -0.01333314 0.01516079 0.04591846 0.0396263 0.01034551 0.04411298 0.04265147 0.009586274 0.04258835 -9.30767e-4 0.01480156 0.03966039 0.002199292 0.01459258 0.03817057 0.04754811 0.008738458 0.04498571 0.0204153 0.01323026 0.04378676 0.02547448 0.01275819 0.04628759 0.03157573 0.01167601 0.04314982 0.03853636 0.01102179 0.04966157 0.07505893 -6.39084e-4 0.05096161 0.07132154 -6.09671e-4 0.04303687 0.07061183 0.001317918 0.04828679 0.07322335 -0.003022551 0.04132491 0.06677949 0.00134772 0.04022294 0.0640524 0.00298506 0.04160141 0.07159376 -0.003011941 0.03790414 0.07484543 -0.003034174 0.04474949 0.06735038 -5.82205e-4 0.03473269 0.05050164 0.00782001 0.04340261 0.05736869 0.006775438 0.05005621 0.05350124 0.006806194 0.04198819 0.05999743 -0.002961814 0.01404875 0.05562961 -5.36064e-4 0.01077258 0.05968314 -5.47668e-4 0.01896995 0.06995666 -0.003002285 0.03448712 0.06831252 -0.002993524 0.03107261 0.0635432 -5.6218e-4 0.02686345 0.06666296 -0.002985477 0.02766185 0.06500625 -0.002978324 0.02425372 0.05901044 0.001390635 0.02416825 0.0633428 -0.002972006 0.02084892 0.04752987 0.00447458 0.01497071 0.05148571 0.004462301 0.02296602 0.05233871 0.003044128 0.0175389 0.06167268 -0.002966582 0.01744759 0.055072 0.001404404 0.01616299 0.05168199 -5.29567e-4 0.002866625 0.05662953 -0.002954483 0.007260024 0.05493652 -0.002951979 0.003870189 0.05111032 0.001413464 0.008190989 0.05831646 -0.002957761 0.01065284 0.03284239 0.007888019 0.007628619 0.03582543 0.006872534 0.006163775 0.04271793 0.005739808 0.0125699 0.04354935 0.004481852 0.00700128 0.03472423 0.005745649 -0.003294646 0.0592845 0.00442171 0.0389766 0.06019067 0.003010153 0.03357928 0.04711163 0.001418113 2.19511e-4 0.03904408 0.001415371 -0.01566153 0.043576 -5.2851e-4 -0.01315367 0.04438108 0.003058373 0.001603484 0.03842365 0.003058314 -0.01015537 0.04982739 -0.002948462 -0.006283879 0.04778265 -5.27993e-4 -0.004876673 0.0515353 -0.002948999 -0.002901613 0.04308855 0.00141865 -0.007731556 0.05323803 -0.002950251 4.83222e-4 0.04811418 -0.002948582 -0.009663403 0.04554325 -0.002949833 -0.0147131 0.02774703 0.006869554 -0.009741902 0.02663624 0.005734622 -0.01910221 0.04294651 -0.002952575 -0.01978868 0.03956645 -5.33652e-4 -0.02098584 0.02952647 0.004474401 -0.02056568 0.03030091 0.003044426 -0.02597093 0.03303682 0.001404702 -0.0273422 -0.02768296 0.01484394 0.04829192 -0.02351862 0.01497983 0.04884868 0.04121553 -0.002954959 -0.02315938 0.03948009 -0.00295794 -0.02652776 0.0353958 -5.41263e-4 -0.02907234 0.03659635 -0.00296396 -0.03210473 0.0294128 -5.58214e-4 -0.04059344 0.002417981 0.009585142 -0.03682494 0.03337711 -0.002972126 -0.03830409 0.02484261 0.00137943 -0.043096 0.03008538 -0.002982199 -0.04461038 -0.01179146 0.01098924 -0.04930382 -0.008736431 0.01029974 -0.05079394 -0.04291605 0.01444637 -0.04943621 -0.04584407 0.01465606 -0.047571 0.02117276 -5.88765e-4 -0.05630588 0.02723354 -0.002991795 -0.05005532 0.02459406 -0.003001451 -0.05508005 0.01660615 0.001344621 -0.0587747 0.01311433 0.004414737 -0.05206298 0.01387459 0.002981841 -0.05740523 -0.03665554 0.01388013 -0.05236434 -0.03967112 0.01418936 -0.050682 0.01983582 -0.003020823 -0.06410175 -0.03357976 0.01352167 -0.0539177 -0.0502246 0.01377612 -0.07807648 0.01391941 -6.22995e-4 -0.07003408 -0.02446442 0.01214057 -0.05871337 -0.02139455 0.01157331 -0.06021809 0.008396267 0.001303136 -0.0742889 -0.02080696 0.01092988 -0.06639266 -0.0176559 0.01024222 -0.06768906 0.002485275 0.004357814 -0.07218766 0.01585358 -0.003038525 -0.07162433 0.01074308 -0.003062725 -0.08124822 0.006165087 -6.62498e-4 -0.08463519 -3.94278e-4 0.005614638 -0.07072293 -0.006495058 0.006718814 -0.07523077 -0.02889978 0.01016128 -0.08890724 -0.01472777 0.009483933 -0.0693832 -0.005674421 0.001221239 -0.1007408 -0.01011383 0.007726311 -0.07498997 0.007362902 -0.003079473 -0.08759915 -0.008394479 0.002852678 -0.09937405 -0.01117587 0.004272758 -0.09787964 -0.01291227 0.004108786 -0.1019145 -0.00965619 0.002411663 -0.1035639 -0.01404082 0.005527019 -0.09640222 -0.01458489 0.004871189 -0.1010672 -0.003757357 -0.002135515 -0.106552 -0.00116837 -0.003123223 -0.1036003 -0.002960741 -0.00313282 -0.1069555 -0.007555127 0.001112401 -0.1046282 -0.008593916 0.001784682 -0.104102 -0.003046989 -7.13149e-4 -0.1019199 -0.00554192 -3.68949e-4 -0.105648 -0.006529808 4.00291e-4 -0.1051476 -0.00461775 -0.001214206 -0.1061161 -0.01072782 0.00300908 -0.103021 -0.01181501 0.003570258 -0.1024703 -0.06688803 0.01261365 0.0322265 -0.0775938 0.01098001 0.04158723 -0.08036196 0.01139616 0.02859854 -0.06351447 0.01223796 0.04642415 -0.08227342 0.01053345 0.0400201 -0.01950973 0.01507747 0.04910403 -0.05577534 0.01138657 0.07720416 -0.1075353 0.008179843 0.02845585 -0.1108573 0.007696449 0.02951407 -0.121828 0.006936311 0.01945674 -0.1136693 0.007211089 0.03156304 -0.07004773 0.008897542 0.09103494 -0.06806433 0.009609401 0.08342927 -0.1158962 0.006292223 0.0415228 -0.1307641 0.005453228 0.02460795 -0.1279551 0.006190121 0.01881307 -0.07966536 0.005924582 0.118054 -0.08609187 0.006268501 0.1006067 -0.1417397 0.005152821 0.007059574 -0.1386731 0.004684925 0.02049505 -0.143647 0.003926336 0.02207785 -0.1555036 0.002882659 0.01403182 -0.1552534 0.001898825 0.02951854 -0.09521532 0.004984855 0.1021818 -0.1695182 8.36868e-4 0.01675939 -0.1738519 -1.76611e-4 0.02332627 -0.1116065 0.001934289 0.1154845 -0.101501 0.002929925 0.1203649 -0.08835327 0.004420578 0.1237048 -0.2023514 -0.002074658 -0.005952537 -0.05245089 0.01222163 0.06840258 -0.05269944 0.01180428 0.07564604 -0.18502 -0.002496063 0.03533422 -0.02479785 0.01464956 0.06184405 -0.03560423 0.01467907 0.04025912 -0.02992779 0.01445114 0.05931222 -0.2148321 -0.004320442 3.69628e-4 -0.2116491 -0.003738939 -0.001242697 -0.2176644 -0.004821896 0.001804351 -0.1993672 -0.004191219 0.02987068 0.08255743 -7.18794e-4 0.06718546 0.08598405 -0.003144562 0.06882101 -0.2206274 -0.005250036 0.003305256 -0.2165992 -0.005221486 0.01115268 0.08617758 -7.67229e-4 0.07519346 0.08909201 -0.003184258 0.07573246 0.08977699 -8.20079e-4 0.08327889 0.09063297 -0.003204584 0.07919371 -0.1056361 0.001900315 0.1274594 -0.1016956 0.001736283 0.1373395 -0.1197397 3.62435e-4 0.122729 0.09216564 -0.003226518 0.08265912 0.09368938 -0.003248453 0.08612793 -0.1108469 3.38423e-4 0.1400998 0.09520465 -0.003269851 0.08960103 0.09254598 -8.62603e-4 0.08958917 -0.1194838 -0.00120449 0.1458676 0.09521979 -9.03555e-4 0.09575057 0.09820878 -0.003311097 0.09655839 0.09867 -9.5522e-4 0.1038182 0.09969776 -0.003332257 0.1000425 0.1011782 -0.003351867 0.1035311 -0.1181814 -0.001919686 0.1584485 -0.1184005 -0.002632915 0.1678709 0.1041118 -0.003386795 0.1105185 0.1026495 -0.003370046 0.1070231 0.1022115 -0.001004457 0.1122357 0.1056046 -0.00104475 0.1204388 0.10701 -0.003417909 0.1175206 0.1055652 -0.003403007 0.1140174 0.1084456 -0.003430426 0.1210273 -0.1237587 -0.003120422 0.1642779 0.1098721 -0.003440618 0.1245375 -0.1298374 -0.004230558 0.1672503 0.1089555 -0.001076221 0.1286752 0.1112894 -0.003448426 0.1280513 -0.1303294 -0.004702746 0.1739136 -0.1329131 -0.00477308 0.1687813 -0.1354085 -0.005226314 0.1714522 0.1131104 -0.001098453 0.1390843 0.1126982 -0.00345534 0.1315693 -0.1333996 -0.005240976 0.1754689 0.1154877 -0.003459811 0.1386152 0.1140974 -0.003459215 0.1350901 0.1168688 -0.003457129 0.142144 0.1182407 -0.003451764 0.1456762 0.1196035 -0.003443896 0.149212 0.1171783 -0.001094937 0.1495192 0.1209565 -0.003431916 0.1527505 0.1204253 -0.001071989 0.1580137 0.1236354 -0.003395318 0.1598401 0.1223006 -0.003415703 0.1562935 0.1250286 -0.001001715 0.1703215 0.1249606 -0.003371179 0.1633893 0.1262769 -0.003342747 0.166943 0.1275832 -0.003309905 0.1704995 0.1288802 -0.003272593 0.1740597 0.1314458 -0.003179192 0.1811898 0.1327142 -0.003126561 0.18476 0.1327276 -7.47706e-4 0.191766 0.1339725 -0.00307244 0.1883341 0.1352203 -0.00301671 0.1919113 0.1364588 -0.002955436 0.195492 0.1357567 -6.18439e-4 0.2004956 0.137687 -0.00289148 0.1990758 0.1401113 -0.002770721 0.2062552 0.1389047 -0.002829909 0.2026638 0.1377909 -5.25539e-4 0.2064957 0.1413069 -0.002713918 0.2098498 0.1424928 -0.002653121 0.2134483 0.1399391 -4.32283e-4 0.2129163 0.1436673 -0.00259763 0.2170503 0.1427194 -3.24144e-4 0.2214118 0.1448308 -0.002548277 0.2206568 0.1447845 -2.60779e-4 0.2278669 0.1459822 -0.002505123 0.224266 0.1482523 -0.002429425 0.2314965 0.1471229 -0.002465784 0.2278795 0.1461394 -2.29009e-4 0.2321667 0.1498525 -0.002393186 0.2366894 0.1474787 -2.07569e-4 0.2364743 0.1488031 -1.97829e-4 0.2407919 0.1515685 -0.002379477 0.2423695 0.1501121 -2.01209e-4 0.2451193 0.153174 -0.002379298 0.2477714 0.1514052 -2.19089e-4 0.2494561 0.1551571 -0.002419114 0.2545908 0.1526829 -2.52858e-4 0.253804 0.1539446 -3.03928e-4 0.2581622 0.1568533 -0.002493977 0.2605628 0.1551898 -3.73678e-4 0.2625309 0.1578723 -0.002550244 0.2642123 0.1564194 -4.63509e-4 0.2669122 0.1588789 -0.002623975 0.2678645 0.1598733 -0.002715289 0.2715197 0.1576322 -5.74818e-4 0.2713041 0.1608554 -0.002824127 0.2751777 0.1588284 -7.08998e-4 0.2757079 0.1618348 -0.002955615 0.2788359 0.1600075 -8.67448e-4 0.2801236 0.1628054 -0.003106474 0.2824963 0.1611704 -0.001051545 0.2845531 0.1623154 -0.001262664 0.288994 0.1637536 -0.003269612 0.2861614 0.1646794 -0.003445029 0.2898311 0.1634435 -0.001502096 0.2934491 0.1655831 -0.003632724 0.2935064 0.1664994 -0.003858566 0.2971786 0.1645485 -0.001766681 0.2979192 0.1673789 -0.004085719 0.3008595 0.1666516 -0.002343356 0.3069191 0.1682137 -0.004309237 0.3045484 0.1656211 -0.002049446 0.3024079 0.1676295 -0.002641201 0.3114547 0.1690049 -0.004529058 0.308247 0.1697649 -0.00475502 0.3119547 0.1705017 -0.004993796 0.3156697 0.168546 -0.002936005 0.3160203 0.171173 -0.005211889 0.3193955 0.1693906 -0.003220558 0.3206179 0.1717779 -0.00540924 0.3231302 0.1701537 -0.003487765 0.3252521 0.1708253 -0.003730535 0.329925 0.1723163 -0.005585908 0.3268739 0.1728107 -0.005760073 0.3306355 0.173236 -0.00591135 0.3344051 0.1713958 -0.003941774 0.3346412 0.1735786 -0.006027817 0.3381785 0.1718552 -0.004114329 0.3394036 0.173838 -0.006109416 0.3419549 0.1702691 -0.003988087 0.3871055 0.1681763 -0.002150416 0.3903314 0.1693993 -0.003520309 0.3907667 0.1721933 -0.004241168 0.344215 0.1710438 -0.004425227 0.3834107 0.1717263 -0.004825651 0.3796874 0.170351 -0.003250479 0.3795815 0.09671092 -0.003290593 0.09307754 0.08754223 -0.003164291 0.07227462 0.08441698 -0.00312519 0.06537079 0.08284199 -0.003107249 0.06192457 0.0787791 -6.75497e-4 0.05895173 0.08125859 -0.003090679 0.05848151 0.009233534 0.01431822 0.04454356 0.01427775 0.01399898 0.04694783 -0.004022002 0.0149616 0.04124355 0.07966744 -0.003075122 0.05504345 0.01933735 0.01362806 0.04941833 0.05640894 0.005680441 0.04046177 0.06315726 0.004392504 0.04706436 0.07645958 -0.003046751 0.04817706 0.07806777 -0.00306046 0.05160868 0.1724011 -0.004315137 0.3490803 0.1740151 -0.006157338 0.345736 0.1741365 -0.006169497 0.3533342 0.174121 -0.006185472 0.3495396 0.1724681 -0.004329085 0.3540021 0.1723846 -0.004275977 0.3589835 0.1740621 -0.006109535 0.3571215 0.1736411 -0.005859851 0.3646851 0.1738981 -0.006005525 0.3609016 0.1721411 -0.004148662 0.3640291 0.1732928 -0.005671262 0.3684655 0.1717276 -0.003940045 0.3691417 0.1728575 -0.005436062 0.372226 0.1723353 -0.005154192 0.3759667 0.1711344 -0.003643035 0.3743252 0.1693684 -0.002755284 0.3849163 0.1684343 -0.003021895 0.3943943 0.1667569 -0.001434028 0.3958291 0.1673759 -0.002482712 0.3979952 0.165078 -6.15449e-4 0.4014102 0.164978 -0.001290798 0.4051119 0.1662265 -0.001892209 0.4015772 0.162184 -5.50286e-5 0.4120402 0.1636304 -6.78409e-4 0.4085991 0.1631031 2.94811e-4 0.4070727 0.1607969 0.001286029 0.4128156 0.1581242 0.002347588 0.4186378 0.1606179 5.93211e-4 0.4154375 0.1550498 0.003468871 0.4245401 0.1572083 0.001909673 0.422088 0.158954 0.001251459 0.4187869 0.1534702 0.003226399 0.4285429 0.1515378 0.004639148 0.4305194 0.1553809 0.002567768 0.4253398 0.1475539 0.00584793 0.4365764 0.1493639 0.004566788 0.4348075 0.15145 0.003901422 0.4317005 0.1430619 0.00708425 0.4427103 0.1449941 0.005868256 0.4408683 0.1472113 0.00522232 0.4378631 0.1403271 0.00715214 0.446712 0.1380621 0.008329153 0.4488951 0.1426969 0.006512641 0.4438177 0.1354328 0.00837326 0.4523703 0.1379055 0.007772326 0.4495641 0.1303252 0.009525537 0.4578531 0.1329093 0.008954942 0.4551339 0.1325995 0.009553015 0.4550801 0.1276929 0.01007395 0.4605283 0.1267194 0.01072543 0.461211 0.1250158 0.01059764 0.463159 0.120471 0.01181596 0.4672324 0.1195217 0.01157075 0.4682883 0.1222928 0.01109671 0.4657457 0.1138322 0.01244401 0.473242 0.1166954 0.01201933 0.4707883 0.1139011 0.01279401 0.4730904 0.1109312 0.01284486 0.4756498 0.1079923 0.01322191 0.4780117 0.06106948 5.92878e-4 0.4153707 0.05933433 6.18949e-4 0.411311 0.04536616 -3.79903e-4 0.4034811 0.04860019 -3.30016e-4 0.4068222 0.03066807 -0.001720786 0.4009234 0.0328539 -0.00192368 0.4048185 0.04689139 3.99734e-4 0.3977066 0.009907066 -0.003975093 0.4014177 0.0120812 -0.004233002 0.4053348 0.02612119 -0.001881718 0.398213 0.005479037 -0.002819299 0.3888785 0.007749736 -0.003699719 0.3974983 -3.36016e-4 -0.003274023 0.3877127 -0.002873659 -0.003719389 0.3890351 -0.005412995 -0.004176259 0.3903475 -0.01724261 -0.005744159 0.392681 -0.01313138 -0.005550026 0.3940525 -0.0158469 -0.005233287 0.3892999 -0.01015174 -0.005046486 0.392728 -0.02185511 -0.005250036 0.3846378 -0.01964908 -0.005478739 0.3884918 -0.01806539 -0.0049901 0.3853939 0.04825574 -8.21119e-4 0.4119692 0.05757313 7.04997e-4 0.4072468 0.07034641 0.002074837 0.4106715 0.0741465 0.002441763 0.4136692 0.07533168 0.002475976 0.4179728 0.07972395 0.003150761 0.4157477 0.07708531 0.002687036 0.4219674 0.09182941 0.005047082 0.4241983 0.08868944 0.004459917 0.420952 0.08321148 0.003618657 0.4188632 0.09278327 0.005429327 0.4285228 0.08453261 0.003852069 0.4230564 0.0877186 0.004458725 0.4262782 0.09565234 0.006181061 0.4318506 0.09677761 0.005971252 0.4265012 0.09950768 0.006686151 0.4298998 0.1024355 0.00804919 0.4378089 0.1020055 0.007454097 0.4333674 0.09830307 0.006989359 0.4352418 0.1044964 0.008902311 0.4413435 0.0988751 0.007601618 0.4396106 0.1062251 0.00976032 0.4449358 0.107884 0.009256243 0.4396253 0.1113053 0.009554147 0.4378952 0.1095755 0.008793473 0.4341947 0.1127308 0.01032465 0.4416481 0.1137768 0.01108783 0.4454721 0.1129755 0.0117588 0.4500882 0.1151099 0.01185184 0.4489723 0.1165506 0.01189875 0.4482425 0.1151839 0.01260787 0.4533191 0.1176415 0.01210933 0.448839 0.1160563 0.01118952 0.4442926 0.1142808 0.01373958 0.4605541 0.1156036 0.01379102 0.460313 0.113071 0.01377254 0.4614221 0.1130355 0.01431077 0.4650036 0.11098 0.01472282 0.4691891 0.1149117 0.01424217 0.4640504 0.1109402 0.01480692 0.4720618 0.114941 0.01442205 0.4671803 0.109023 0.01498347 0.4730331 0.1125713 0.01464027 0.4683817 0.1122258 0.01463586 0.4714102 0.1076627 0.01492762 0.4762509 0.1086285 0.01476573 0.4757618 0.130938 0.01124173 0.4409544 0.129856 0.01176804 0.4455415 0.1323698 0.01105123 0.4402291 0.1281642 0.01228892 0.4502568 0.1258336 0.01279574 0.4550896 0.1293615 0.01208835 0.4496504 0.1135023 0.01442176 0.4707636 0.1095855 0.01456832 0.4752771 0.1035175 0.01495236 0.4805217 0.1041589 0.01482009 0.4801968 0.1114897 0.0140357 0.4743121 0.1105511 0.01432561 0.4747872 0.1054268 0.01446598 0.479555 0.1283577 0.01180094 0.4572288 0.1331977 0.01090764 0.4513593 0.1321647 0.01126152 0.4518826 0.1047898 0.01466166 0.4798776 0.1362111 0.009578824 0.4498328 0.1371629 0.009007215 0.4493506 0.1409878 0.008484244 0.4437609 0.1398853 0.009040713 0.4443194 0.1352263 0.01007556 0.4503316 0.1318145 0.01014423 0.4554778 0.1205447 0.0136764 0.4611907 0.1186593 0.01392745 0.4621479 0.1165309 0.01421034 0.4663741 0.122867 0.01327401 0.4600102 0.1196963 0.01361799 0.4647694 0.123793 0.01308321 0.4595412 0.1219384 0.01344692 0.4604806 0.1181163 0.01394432 0.4655703 0.09868139 0.01485478 0.4847564 0.1247163 0.01287323 0.4590734 0.09932243 0.01465821 0.4844319 0.1066557 0.01391899 0.4789324 0.1060504 0.01422595 0.4792391 0.09977656 0.01444095 0.4842016 0.1070556 0.01362931 0.4787294 0.09998446 0.01429146 0.484096 0.09802681 0.0149886 0.4850881 0.09273278 0.01474994 0.4891348 0.09586066 0.01449191 0.4870022 0.1256351 0.01264244 0.458608 0.1208335 0.01333642 0.4641925 0.121606 0.01312202 0.4638012 0.1160404 0.01384061 0.4694778 0.1223741 0.01288604 0.4634121 0.123135 0.01262521 0.4630267 0.1274576 0.01210945 0.4576848 0.1265495 0.01238876 0.4581448 0.1246302 0.01201212 0.4622693 0.1292489 0.01145845 0.4567774 0.1238879 0.01233583 0.4626452 0.1309849 0.01064252 0.455898 0.1253554 0.01164627 0.4619019 0.1260566 0.01122516 0.4615467 0.1301267 0.01107555 0.4563328 -0.02026319 0.007074058 -0.09819084 -0.01694095 0.006649494 -0.09488701 -0.02217561 0.007712006 -0.09722208 0.005666315 0.002938568 -0.07292342 0.02210932 0.003018081 -0.04172378 0.02479714 0.007885098 -0.008211493 0.04837596 0.003053605 0.009566724 0.05627906 0.003029823 0.02554565 0.06291776 0.0013718 0.03219646 0.07440495 0.001282155 0.05637305 0.07815128 0.001240134 0.06447094 0.08089435 0.001204431 0.07047891 0.08364677 0.001165449 0.07656919 0.08728206 0.001109242 0.08472645 0.09088742 0.00105071 0.09294372 0.1047766 8.46526e-4 0.1258937 0.1013792 8.8819e-4 0.1176321 0.0944401 9.9269e-4 0.1011705 0.1097518 8.02929e-4 0.1382316 0.09793478 9.3772e-4 0.1093938 0.1162555 7.96233e-4 0.154877 0.1225473 8.65303e-4 0.1715659 0.1294296 0.001057028 0.1905538 0.1333163 0.001212 0.2016951 0.1361939 0.001327097 0.2101309 0.1390091 0.001430153 0.2185716 0.1417753 0.001511096 0.2270646 0.1437809 0.001548469 0.2333614 0.1451305 0.001562237 0.2376638 0.1464652 0.001564085 0.2419761 0.147785 0.001552641 0.2462981 0.1490889 0.001526534 0.2506294 0.1503778 0.001484334 0.2549716 0.1516509 0.001424729 0.2593241 0.1529078 0.00134623 0.263687 0.1541492 0.001247465 0.2680621 0.1553741 0.001127004 0.272448 0.1565825 9.83601e-4 0.2768455 0.1577743 8.15722e-4 0.2812549 0.1589499 6.22021e-4 0.285678 0.1601079 4.01092e-4 0.2901123 0.1612489 1.51772e-4 0.2945607 0.1623675 -1.22948e-4 0.299024 0.163454 -4.16208e-4 0.3035057 0.1644991 -7.21028e-4 0.3080095 0.1654922 -0.001030385 0.3125374 0.1664249 -0.001337349 0.3170948 0.1672866 -0.001634836 0.3216837 0.1680683 -0.001915931 0.3263086 0.1687595 -0.002173662 0.3309714 0.1693513 -0.002400934 0.3356768 0.1698337 -0.002590835 0.3404275 0.1701967 -0.00273633 0.3452265 0.1704311 -0.002830445 0.3500781 0.1705272 -0.002866208 0.3549854 0.1704748 -0.002836585 0.3599509 0.1702648 -0.002734601 0.3649795 0.1698876 -0.002553284 0.3700737 0.1693333 -0.002285599 0.3752375 0.1685917 -0.001924574 0.3804727 0.167654 -0.001463174 0.3857847 0.1665099 -8.94579e-4 0.3911755 0.1651422 -2.17038e-4 0.396647 0.1635187 5.59721e-4 0.4022 0.1616041 0.00142461 0.4078321 0.1593633 0.002366542 0.4135419 0.1567617 0.003374457 0.419328 0.1537652 0.004437267 0.4251908 0.1503379 0.005543828 0.4311272 0.1020016 0.01390451 0.4825989 0.1050161 0.01357513 0.4803287 0.146445 0.006683111 0.4371381 0.1420539 0.007843911 0.4432209 0.09894937 0.01421016 0.4848232 0.1387568 0.009532868 0.4448911 0.1342191 0.01051473 0.4508419 -0.01678168 0.005786418 -0.09995442 -0.02364861 0.008171796 -0.09647589 -0.02748596 0.01265317 -0.05709892 0.02133119 0.004449903 -0.03637546 0.009565711 0.008769392 -0.03040963 0.01061129 0.009618997 -0.02108192 0.03761571 0.004485011 -0.00475794 0.04376423 0.006856858 0.02205538 0.06788271 0.002954006 0.04965537 0.07168084 0.002916693 0.05774557 0.07542783 0.002872943 0.06583684 0.07910025 0.002822697 0.0738815 0.08276998 0.002766013 0.08204251 0.08638423 0.002705752 0.09020358 0.1003977 0.002477228 0.1231087 0.08994895 0.002644419 0.0983783 0.1053485 0.002418458 0.1352443 0.09347194 0.002584218 0.1065843 0.09696233 0.002527594 0.1148455 0.1118938 0.002383649 0.1517845 0.1181322 0.00241518 0.1680958 0.1268687 0.002607107 0.1919081 0.130768 0.002754151 0.2030473 0.1336503 0.002857983 0.2114365 0.136482 0.002949714 0.2198612 0.1392688 0.003018677 0.2283464 0.1412867 0.003046691 0.2346249 0.142647 0.003053963 0.2389218 0.1439929 0.003049194 0.2432285 0.1453239 0.003030955 0.2475448 0.1466395 0.002997875 0.2518702 0.1479401 0.002948641 0.2562065 0.1492252 0.002881705 0.2605528 0.1504944 0.002795815 0.2649095 0.1517484 0.00268954 0.2692783 0.152986 0.00256145 0.2736577 0.1542075 0.002410173 0.2780486 0.1554124 0.002234399 0.2824513 0.1566015 0.002032577 0.2868676 0.1577731 0.001803457 0.2912949 0.1589282 0.001545727 0.2957363 0.160061 0.001262485 0.3001924 0.1611622 9.60391e-4 0.3046666 0.1622226 6.46362e-4 0.3091626 0.1632319 3.27292e-4 0.3136823 0.1641816 1.00723e-5 0.3182311 0.1650615 -2.98388e-4 0.3228107 0.1658627 -5.91198e-4 0.3274258 0.1671893 -0.001102268 0.336772 0.166575 -8.61468e-4 0.332078 0.1676959 -0.001306772 0.3415104 0.1680851 -0.001468002 0.3462961 0.1684472 -0.001621186 0.3537257 0.1683955 -0.001595616 0.3637104 0.1676895 -0.001265525 0.3739818 0.1662613 -5.7988e-4 0.3844622 0.1647477 1.63951e-4 0.3920682 0.1634345 8.08761e-4 0.3975121 0.1618697 0.001550197 0.4030354 0.1600186 0.002376854 0.4086351 0.1578471 0.003277242 0.4143099 0.1553207 0.004239916 0.4200579 0.1524057 0.005253434 0.4258794 0.1199349 0.01222026 0.467504 0.1490685 0.00630635 0.4317703 0.1452729 0.007387161 0.4377319 0.1134953 0.01309996 0.4732961 0.1311227 0.01158183 0.4524103 0.1028606 0.01506221 0.4808549 -0.01852768 0.006452322 -0.09906995 -0.02798861 0.009403407 -0.09427744 0.01022762 0.005673289 -0.05060189 0.01845562 0.005709648 -0.03488695 0.02583307 0.008808255 0.001200079 0.05539542 0.004444837 0.03094887 0.04958206 0.006830632 0.0339055 0.05249255 0.005704164 0.0323807 0.06696188 0.004357218 0.05510902 0.07169926 0.004303991 0.06527101 0.07628816 0.004239797 0.07529926 0.07995486 0.004181146 0.08344227 0.0835759 0.004118621 0.09160602 0.0991944 0.003853976 0.1283159 0.08712434 0.004054844 0.09972697 0.09233301 0.003962159 0.1118643 0.1057903 0.003783404 0.1446458 0.115145 0.003775596 0.1687077 0.1258295 0.004015028 0.1978844 0.1295619 0.004141569 0.2085593 0.1324378 0.004231095 0.2169547 0.1352751 0.004302918 0.2254219 0.1380677 0.004346013 0.2339539 0.1400769 0.004350244 0.2402238 0.1414342 0.004339694 0.2445246 0.1427769 0.004315555 0.248835 0.1441044 0.004276454 0.2531543 0.1454172 0.004221022 0.2574844 0.1467148 0.004147887 0.2618245 0.1479967 0.004055559 0.2661747 0.1492637 0.003942728 0.2705369 0.1505146 0.003807961 0.2749096 0.1517494 0.00364995 0.2792938 0.1529681 0.003467202 0.2836894 0.1541711 0.003258347 0.2880987 0.155357 0.003022074 0.2925189 0.1565265 0.002757132 0.296953 0.1576739 0.00246638 0.3014016 0.1587904 0.002156615 0.305868 0.1598667 0.001834571 0.3103561 0.1608927 0.001507103 0.3148673 0.1618601 0.001180946 0.3194071 0.1627588 8.63011e-4 0.3239772 0.1635802 5.60022e-4 0.328582 0.1646459 1.49508e-4 0.3354763 0.1657092 -2.84478e-4 0.3448863 0.1663034 -5.40514e-4 0.3546687 0.1663284 -5.53191e-4 0.3646588 0.1654758 -1.57507e-4 0.3775007 0.163712 6.96524e-4 0.3892077 0.1616671 0.001700103 0.3984074 0.1601631 0.002410888 0.4038999 0.158378 0.003204345 0.4094662 0.1562781 0.004068672 0.4151048 0.1538295 0.004992067 0.4208133 0.1509998 0.005962729 0.4265916 0.1193675 0.01256102 0.4677914 0.1477545 0.006968915 0.4324359 0.1440606 0.007998943 0.438346 0.1130662 0.01335775 0.4735134 0.1300736 0.01187282 0.4529418 0.1167891 0.01411497 0.4630967 -0.02948409 0.009787499 -0.09351992 -0.03539299 0.01113468 -0.0905267 -0.0349617 0.01147407 -0.08585 0.003155946 0.00677675 -0.05698865 0.01140344 0.006818592 -0.0412966 0.01957094 0.006850481 -0.02561724 0.01773983 0.008796393 -0.01462346 0.006631195 0.01107668 -0.01398253 0.007641971 0.01037901 -0.01944279 0.04859763 0.005722224 0.02443188 0.06029772 0.005650281 0.04857933 0.06410568 0.005613923 0.05662518 0.06786882 0.005570828 0.06467956 0.07157498 0.005520701 0.072721 0.07522463 0.005463898 0.08075451 0.0788989 0.005400776 0.08896392 0.08251327 0.005334615 0.09715944 0.09115642 0.005175113 0.1172634 0.09790426 0.005068302 0.1335184 0.08606356 0.005268335 0.105333 0.1042699 0.005001723 0.1493324 0.1150465 0.005016624 0.1772336 0.1223393 0.005184412 0.1971607 0.1254245 0.005279004 0.2058506 0.1283199 0.005364596 0.2141536 0.1311829 0.005437552 0.222533 0.1340224 0.005487442 0.2310327 0.1368098 0.005501866 0.2395719 0.1388169 0.005480945 0.2458504 0.1401716 0.005451619 0.2501548 0.1415113 0.005407214 0.2544679 0.1428368 0.005346357 0.2587916 0.144147 0.00526762 0.2631252 0.145442 0.00516963 0.2674688 0.1467223 0.005050957 0.2718243 0.1479867 0.004910349 0.2761902 0.1492353 0.004746317 0.2805673 0.1504679 0.00455743 0.284956 0.1516853 0.004342377 0.2893579 0.1528856 0.004099786 0.2937708 0.1540698 0.003828406 0.2981974 0.1552323 0.003531098 0.3026384 0.1563643 0.003214538 0.307097 0.1574569 0.00288546 0.3115767 0.1585 0.002550482 0.3160793 0.1594855 0.002216458 0.32061 0.1604035 0.001890063 0.3251703 0.161598 0.001445055 0.3317754 0.1629284 9.17216e-4 0.3410795 0.163854 5.27872e-4 0.3509468 0.1642398 3.57426e-4 0.3610476 0.1640263 4.55041e-4 0.3707802 0.1631647 8.6367e-4 0.3809329 0.1620453 0.001409113 0.3886259 0.1610583 0.001897275 0.3939371 0.1586137 0.00308448 0.404228 0.1566998 0.003936171 0.4103164 0.154673 0.00476855 0.4159178 0.1523045 0.005657136 0.4215858 0.1495618 0.006590068 0.4273201 0.1187806 0.01285713 0.4680887 0.1464101 0.007554948 0.4331169 0.1428197 0.008540034 0.4389746 0.1124172 0.01367735 0.4738425 -0.0259689 0.008853435 -0.09530055 2.02491e-4 0.007790088 -0.05548161 0.008465409 0.007833182 -0.03975182 0.01660656 0.007865488 -0.02411895 0.02682912 0.00964266 0.01064002 0.0338447 0.008801996 0.01709741 0.04079335 0.007871925 0.02354085 0.04173588 0.008774757 0.03303134 0.06118875 0.006737947 0.05812072 0.06495392 0.006693601 0.06617122 0.06865429 0.00664258 0.07419228 0.0723021 0.006584048 0.08220869 0.07596963 0.006519377 0.09038972 0.09164834 0.006226003 0.1267848 0.07959425 0.006451249 0.09859538 0.08477449 0.006351351 0.1105219 0.09809863 0.006132066 0.1425063 0.1084246 0.006074965 0.1686652 0.1142677 0.006132364 0.1841298 0.1217759 0.006311178 0.2047036 0.1255845 0.006416857 0.2155438 0.1284724 0.006482124 0.2239278 0.1313329 0.006523489 0.2324139 0.1341326 0.006529033 0.2409086 0.136162 0.006501734 0.2471953 0.1375288 0.006467759 0.2514935 0.138881 0.006418526 0.2558003 0.140219 0.006352841 0.2601176 0.1415423 0.006269037 0.2644447 0.1428505 0.00616604 0.2687816 0.1441442 0.006042242 0.2731302 0.1454223 0.005896329 0.2774891 0.1466848 0.005726933 0.2818593 0.1479318 0.005532562 0.2862407 0.1491635 0.005311965 0.2906354 0.1503785 0.005063712 0.2950407 0.1515777 0.00478655 0.2994598 0.1527555 0.004483401 0.303893 0.1539034 0.004160761 0.3083437 0.1550124 0.003825306 0.3128151 0.1560727 0.003483712 0.3173089 0.1574947 0.002997338 0.3237558 0.1591982 0.002367675 0.332722 0.1605619 0.001828134 0.3418256 0.1616477 0.001374125 0.352678 0.162056 0.00119704 0.3620871 0.1619961 0.001227974 0.3691681 0.1617784 0.001332879 0.3741816 0.1613956 0.001518368 0.3792584 0.1608383 0.001791059 0.3844003 0.1600983 0.002157688 0.3896121 0.1590952 0.002665638 0.3954499 0.1566468 0.003852963 0.405681 0.1549974 0.00459069 0.4111787 0.1530449 0.005394518 0.4167425 0.1507568 0.006252169 0.4223698 0.1481024 0.007151067 0.4280593 0.1181793 0.01311892 0.4683933 0.145047 0.008079111 0.4338074 0.1415609 0.009023964 0.4396122 0.1376113 0.009972929 0.4454713 0.1137584 0.01454371 0.4677764 0.1022098 0.01514846 0.4811844 0.09736984 0.01507455 0.4854208 -0.009207844 0.008668303 -0.06614661 -0.02288413 0.008574068 -0.09192752 0.001304745 0.008730292 -0.04620516 0.0157814 0.01039958 -0.003623366 0.007624447 0.01171481 -0.0045861 0.00151211 0.01227629 -0.008972883 0.04664069 0.007845163 0.03544795 0.05435782 0.007788717 0.05143988 0.05821931 0.007750451 0.05958783 0.06200551 0.007705211 0.06767773 0.06568068 0.007652938 0.0756306 0.06935906 0.007593035 0.08370685 0.07472169 0.007495045 0.09567648 0.08867323 0.007224857 0.1281113 0.08182466 0.007354497 0.1119514 0.09493309 0.007127285 0.1433069 0.1041128 0.007056593 0.1663867 0.1109186 0.007093966 0.1841787 0.1190712 0.007269382 0.2063561 0.1228147 0.007364153 0.2169337 0.1257434 0.00742352 0.2253732 0.1286138 0.007457077 0.2338131 0.131428 0.007454395 0.242267 0.1334781 0.007421135 0.2485549 0.1348572 0.007382929 0.2528468 0.1362218 0.007329463 0.2571473 0.1375727 0.007259368 0.2614582 0.1389091 0.007171154 0.2657786 0.1402305 0.007063567 0.2701087 0.1415379 0.00693506 0.2744506 0.1428297 0.006784439 0.2788024 0.1441065 0.006610155 0.2831653 0.1453678 0.006410837 0.2875395 0.1466141 0.006185233 0.2919268 0.147844 0.005931913 0.2963246 0.1490583 0.005649626 0.300736 0.1502516 0.005341112 0.3051614 0.1514154 0.005013048 0.3096039 0.1525411 0.004671871 0.314067 0.1536189 0.004324257 0.3185518 0.155041 0.0038383 0.3248535 0.1568849 0.003158986 0.3341764 0.1589684 0.002323567 0.3492743 0.1596675 0.002028822 0.3583648 0.1598653 0.001948058 0.3653252 0.1598421 0.00196588 0.3702592 0.1596658 0.002056539 0.3752517 0.1593278 0.00222671 0.3803059 0.1588185 0.00248295 0.3854234 0.1581301 0.002831935 0.3906092 0.1572529 0.003280222 0.3958647 0.1561715 0.003828644 0.4011912 0.1535031 0.005087256 0.411441 0.151399 0.005958318 0.4175763 0.149193 0.006787955 0.423162 0.1466268 0.007656335 0.4288068 0.11757 0.01335322 0.4687019 0.1436697 0.00855112 0.4345051 0.1402888 0.009459733 0.4402566 0.1364543 0.01036942 0.4460574 -0.03180438 0.01034832 -0.09234458 -0.005771756 0.009540855 -0.05242758 -0.06002551 0.01500254 -0.03733468 -0.06761193 0.01490682 -0.04433476 -0.07055228 0.01480746 -0.04249256 -0.02610951 0.01394975 -0.03226715 -0.01998645 0.0131815 -0.0354402 -0.02303671 0.01359063 -0.03383922 0.01877868 0.009639263 -0.00521332 0.02277177 0.01109176 0.01769989 0.02379924 0.0104025 0.01216161 0.0513975 0.008706331 0.05300253 0.05520617 0.008667171 0.06102663 0.05898737 0.008621096 0.0690962 0.06363582 0.008553683 0.0791614 0.0682488 0.008472919 0.08933275 0.07354408 0.008370578 0.1012163 0.0876919 0.008092343 0.1342745 0.08056813 0.008227944 0.1173928 0.09720426 0.00796777 0.1576735 0.1031101 0.007945775 0.1727133 0.108902 0.007982432 0.1878384 0.1175752 0.008167028 0.2114434 0.1215006 0.00825113 0.2225447 0.1244191 0.008292138 0.2309643 0.1272899 0.008302032 0.2394152 0.1301205 0.00827074 0.2479428 0.1321626 0.008211553 0.2542118 0.13354 0.008154213 0.2585058 0.1349038 0.008080124 0.2628101 0.1362534 0.007987856 0.2671238 0.1375883 0.007876038 0.2714472 0.1389093 0.007743418 0.2757821 0.1402152 0.007588446 0.2801268 0.1415061 0.00740987 0.2844825 0.142782 0.007206141 0.2888494 0.144043 0.006975948 0.2932292 0.1452879 0.00671792 0.2976194 0.1465175 0.006430923 0.3020231 0.1477264 0.006117761 0.3064405 0.1489062 0.00578463 0.3108749 0.1500487 0.005438327 0.3153294 0.1515888 0.0049389 0.3216357 0.1534689 0.0042755 0.3302614 0.1560375 0.003288149 0.3452317 0.157067 0.002864301 0.3547876 0.1574972 0.002687692 0.3615857 0.1576541 0.002628087 0.3664454 0.1576699 0.002633929 0.3713596 0.1575354 0.002711713 0.3763309 0.1572425 0.002868056 0.3813622 0.1567815 0.003109395 0.3864552 0.156145 0.003442406 0.3916147 0.1553236 0.003873527 0.3968421 0.1542849 0.004424452 0.4024572 0.1515407 0.005714058 0.4129297 0.1497388 0.006468832 0.4184173 0.1476149 0.007273018 0.4239614 0.1451398 0.00811392 0.4295601 0.1169545 0.01356416 0.4690137 0.1422798 0.008978664 0.4352091 0.1390051 0.009854316 0.4409069 0.1352875 0.01072835 0.4466485 0.1015654 0.01521283 0.4815107 -0.04129183 0.01224088 -0.08753859 -0.04317128 0.0125485 -0.08658653 -5.71668e-4 0.01034456 -0.03523176 0.008624255 0.01229053 0.004902362 0.03480488 0.009625852 0.026596 0.030739 0.01106894 0.03370398 0.04836958 0.009539484 0.05446767 0.05222088 0.009499967 0.06258153 0.05598133 0.009453058 0.07059609 0.0606327 0.009384274 0.08065342 0.0669279 0.009270668 0.09454369 0.08224529 0.008955717 0.129779 0.07408297 0.009124815 0.1107581 0.09403288 0.008781194 0.1585331 0.1001641 0.008750617 0.174065 0.1061367 0.008782029 0.1895867 0.114799 0.00895226 0.2130113 0.1187091 0.0090276 0.2239798 0.121651 0.009063065 0.2324002 0.1245458 0.009067058 0.24085 0.1273924 0.009028434 0.2493337 0.1294505 0.00896424 0.2555857 0.1308406 0.008903324 0.2598732 0.1322174 0.008825659 0.2641709 0.1335802 0.008729636 0.2684779 0.1349287 0.008614122 0.2727944 0.1362635 0.008477628 0.2771223 0.1375835 0.008318722 0.2814599 0.1388888 0.008136153 0.2858084 0.1401792 0.007928431 0.2901678 0.1414551 0.007694125 0.2945401 0.1427151 0.007432043 0.2989227 0.14396 0.007140755 0.3033186 0.1451846 0.006823122 0.3077281 0.1463807 0.006485521 0.3121543 0.1480071 0.005989551 0.3183869 0.1500616 0.005298912 0.327033 0.153071 0.0041821 0.3425043 0.1542795 0.003698706 0.3513515 0.1549115 0.003443241 0.3579397 0.1552351 0.003315448 0.3627316 0.1554284 0.00324583 0.3675729 0.1554832 0.003240764 0.3724672 0.155391 0.003306865 0.3774171 0.1551433 0.003450572 0.3824256 0.1547312 0.003678381 0.3874939 0.1541469 0.003996908 0.3926268 0.1533815 0.004412472 0.3978258 0.1522659 0.005010962 0.4039561 0.1483748 0.006814062 0.4184448 0.146027 0.007713735 0.4247657 0.143642 0.008529424 0.4303188 0.1408802 0.009366869 0.4359181 0.1377134 0.01021283 0.4415612 0.130555 0.01186615 0.4490457 0.1279612 0.01237851 0.4540119 0.1317451 0.01162093 0.4484429 0.1341126 0.01105433 0.4472436 0.106688 0.01505732 0.4767449 0.12902 0.01213777 0.4534754 -0.03828489 0.01170581 -0.08906179 -0.04483944 0.01280415 -0.08574151 -0.0339902 0.01083844 -0.0912373 -0.05079936 0.01359355 -0.08272248 -0.04926222 0.01340878 -0.0835011 -0.002498924 0.0110408 -0.03157591 -0.01172643 0.0132246 -0.0196008 -0.01487988 0.01363343 -0.01819509 0.01471704 0.01109296 0.00177741 0.03178167 0.01038563 0.02813035 0.04735589 0.01027911 0.06019556 0.05297052 0.01020985 0.07212591 0.05669629 0.01015442 0.08016109 0.06038916 0.01009124 0.08823782 0.065732 0.009988307 0.1001061 0.07942479 0.009702563 0.1316928 0.07280802 0.009839296 0.1162165 0.08926486 0.009538948 0.1554747 0.09564834 0.009487032 0.1714664 0.1024128 0.009500086 0.1888755 0.111794 0.00965923 0.2139508 0.1159054 0.009734272 0.2254303 0.1188474 0.009763598 0.2337709 0.1217722 0.009762108 0.2422319 0.1246414 0.009717822 0.2507032 0.1267243 0.009649157 0.2569667 0.1281271 0.009585022 0.2612478 0.129517 0.00950402 0.2655388 0.1308931 0.009404718 0.2698391 0.1322553 0.009285748 0.2741487 0.133604 0.009145855 0.2784695 0.1349381 0.008983314 0.2828 0.1362578 0.008797168 0.2871412 0.1375629 0.008585751 0.2914931 0.1388537 0.008347749 0.2958579 0.1401289 0.008081734 0.3002328 0.1413891 0.007786512 0.3046209 0.1426295 0.007465064 0.3090224 0.1438419 0.007123351 0.3134403 0.145482 0.006624758 0.3196225 0.1475343 0.005938947 0.3280674 0.1505796 0.004820287 0.3431675 0.1519227 0.004291951 0.3524841 0.1526038 0.004023015 0.3591088 0.1529612 0.003886699 0.3638835 0.1531909 0.003807902 0.3687062 0.1532852 0.003792941 0.3735806 0.1532354 0.003848373 0.3785091 0.1530334 0.003980636 0.3834944 0.1526702 0.004196166 0.3885379 0.1521385 0.004501461 0.3936442 0.1514294 0.004902958 0.3988147 0.150528 0.005401134 0.40405 0.1494075 0.005984544 0.4093482 0.1465469 0.007300376 0.4197971 0.1444311 0.008114755 0.4255741 0.1421362 0.008907616 0.4310816 0.1394742 0.009720146 0.4366303 0.1364154 0.01053905 0.4422187 0.1269653 0.01246893 0.4508641 0.1247649 0.01297485 0.455631 0.1329315 0.01135104 0.4478419 0.1009214 0.0152564 0.4818367 0.09688919 0.01510876 0.4856641 -0.01076066 0.01164025 -0.0400052 -0.001444339 0.01168674 -0.02215558 0.00961554 0.01280629 0.01444739 0.01664578 0.01228886 0.0207526 0.04622673 0.0109471 0.065737 0.05184036 0.01087099 0.07773125 0.05551266 0.01081132 0.08569473 0.06090539 0.01071047 0.09757393 0.07419824 0.01042824 0.1279407 0.08577215 0.01021665 0.1556245 0.0680198 0.01056039 0.1136297 0.09264445 0.01015549 0.1727835 0.09732002 0.01015353 0.1847177 0.1008936 0.01017826 0.1939924 0.1090254 0.01030939 0.2156156 0.1130816 0.0103771 0.2268669 0.1160476 0.01040142 0.2352023 0.1189883 0.01039457 0.243629 0.1218856 0.01034498 0.2521016 0.1239863 0.01027214 0.2583536 0.125402 0.01020503 0.2626282 0.126805 0.01012104 0.2669126 0.1281945 0.01001876 0.2712061 0.1295703 0.009896636 0.2755087 0.1309329 0.009753525 0.2798225 0.1322813 0.009587824 0.2841458 0.1336155 0.009398341 0.2884796 0.1349352 0.009183526 0.2928242 0.136241 0.008942127 0.2971813 0.1375314 0.008672714 0.3015486 0.1388072 0.008374035 0.3059288 0.1400634 0.008048832 0.3103223 0.1412922 0.007703542 0.3147319 0.1429399 0.007205069 0.3208265 0.1450369 0.006510019 0.3292239 0.1482082 0.005351006 0.3447621 0.1491613 0.004983127 0.3508993 0.1497779 0.004744708 0.3555698 0.1502861 0.004550337 0.3602828 0.1506775 0.004406332 0.3650404 0.1509439 0.004319131 0.3698444 0.1510778 0.004295229 0.3746988 0.1510705 0.004340946 0.3796057 0.1509143 0.004462778 0.3845678 0.1506003 0.004667103 0.3895864 0.1501215 0.004960417 0.394666 0.1494688 0.00534904 0.3998078 0.1486281 0.005833446 0.4050124 0.1474899 0.006457149 0.4108244 0.1447021 0.007738351 0.4209686 0.142828 0.008479416 0.4263862 0.1147809 0.01415795 0.4701155 0.140625 0.009251654 0.4318471 0.1380621 0.01004141 0.4373456 0.1351112 0.01083564 0.4428794 0.1257628 0.01262885 0.4514733 0.1245594 0.01276922 0.4520829 0.1226212 0.01327824 0.4567168 0.1057193 0.0151543 0.4772357 -0.03798222 0.01204037 -0.08426946 -0.0567457 0.01419138 -0.0797103 -0.05757766 0.01501929 -0.04012966 -0.05451929 0.01499778 -0.04175949 -0.01384949 0.0122084 -0.03852576 -0.005594551 0.01225054 -0.02270984 -0.009715914 0.01402324 -6.69445e-4 -0.006695508 0.01366341 -0.002354681 5.67435e-4 0.01279598 -0.003309369 -0.003554463 0.01325416 -0.0037871 0.01571428 0.01172298 0.0112906 0.02370572 0.01171118 0.02720755 0.03933566 0.01161497 0.05918627 0.04697889 0.01152437 0.07534015 0.05422198 0.01140552 0.09102827 0.06147009 0.01125848 0.1071407 0.08277124 0.01083195 0.1570969 0.06955343 0.0110799 0.1255835 0.08970624 0.01076209 0.174291 0.09439265 0.01075637 0.1861964 0.09801852 0.01077771 0.1955516 0.1062316 0.01089996 0.2172435 0.1102415 0.01096093 0.2282866 0.113247 0.01098144 0.2366694 0.1162032 0.01096957 0.2450607 0.1191256 0.0109148 0.2535241 0.1212384 0.01083827 0.2597455 0.1226671 0.01076853 0.2640136 0.1240832 0.01068186 0.2682914 0.1254862 0.01057672 0.272578 0.1268757 0.01045185 0.2768737 0.1282524 0.01030582 0.2811804 0.129615 0.01013725 0.2854965 0.1309637 0.009944617 0.2898229 0.1322982 0.009726822 0.29416 0.1336191 0.009482324 0.2985095 0.1349248 0.009209752 0.302869 0.1362161 0.008907854 0.3072413 0.1374882 0.008579432 0.3116268 0.1387334 0.008230626 0.3160281 0.139944 0.007867932 0.3204481 0.1417003 0.007309675 0.3270796 0.1450325 0.006131768 0.3419625 0.1465102 0.005576491 0.3502743 0.1474203 0.005230426 0.356764 0.1479601 0.005029559 0.3614611 0.1483857 0.00487852 0.3662013 0.1486889 0.004783749 0.3709868 0.1488624 0.004751622 0.3758211 0.1488979 0.004788517 0.3807063 0.1487876 0.004900932 0.3856452 0.148523 0.005095124 0.3906387 0.1480971 0.005377411 0.3956914 0.1475012 0.005754351 0.4008045 0.1467213 0.006226241 0.4059783 0.1455336 0.006890892 0.4122123 0.1414679 0.008724391 0.426601 0.1391075 0.009564161 0.4326158 0.1366446 0.01033341 0.4380637 0.1338025 0.01110523 0.4435423 0.1268987 0.01259744 0.45455 0.1093907 0.01475691 0.4699944 0.1111537 0.01432472 0.4659605 0.1002712 0.01528012 0.4821661 0.09632349 0.01512432 0.4859513 -0.04719746 0.0131402 -0.08454704 -0.05637657 0.01434212 -0.07496982 -0.01689684 0.01272141 -0.03695034 -0.008684515 0.01276373 -0.02121132 0.02458459 0.01226538 0.03668808 0.03243809 0.01221728 0.05274927 0.04014414 0.01214081 0.06883567 0.04576146 0.0120629 0.08081287 0.0503298 0.01198613 0.09070438 0.05662244 0.01186114 0.1045967 0.06508141 0.01167291 0.1237279 0.0796858 0.01138812 0.1583505 0.08674913 0.01131194 0.1757806 0.09149694 0.01130217 0.1877747 0.09514242 0.01132088 0.1971341 0.1034387 0.01143527 0.2189002 0.1073979 0.01148992 0.2297247 0.1104274 0.01150649 0.2381038 0.1134154 0.01149052 0.2465156 0.1163511 0.01143115 0.2549316 0.1184822 0.01135122 0.2611417 0.1199238 0.01127916 0.2654032 0.1213532 0.01118993 0.2696743 0.1227697 0.01108235 0.273954 0.124173 0.01095485 0.2782428 0.1255637 0.01080626 0.2825424 0.1269406 0.01063495 0.2868512 0.1283038 0.01043975 0.2911703 0.1296532 0.01021915 0.2954998 0.1309891 0.009971857 0.2998417 0.1323102 0.009696364 0.3041934 0.1336171 0.009391546 0.3085579 0.1349051 0.009060144 0.3129352 0.1366779 0.008562743 0.3190829 0.1389239 0.007860362 0.327421 0.1424703 0.006630778 0.3425819 0.144109 0.006023585 0.3514895 0.1450556 0.005670547 0.3579619 0.145627 0.005463719 0.3626428 0.1460869 0.005306363 0.3673658 0.146427 0.005204737 0.3721325 0.1466403 0.005165219 0.3769467 0.1467186 0.005194127 0.3818102 0.1466546 0.005297958 0.3867257 0.1464394 0.005482912 0.3916941 0.1460666 0.005755364 0.3967199 0.1455277 0.006121635 0.4018042 0.1448085 0.00658226 0.4069473 0.143885 0.00712502 0.4121457 0.1427562 0.007748186 0.4175627 0.1396058 0.009111225 0.4280184 0.1375856 0.009847462 0.4333867 0.1352226 0.01059806 0.438784 0.1324903 0.01134955 0.444207 0.1215472 0.01340353 0.4572609 0.1233542 0.01289004 0.4526934 -0.0305016 0.01311331 -0.05545443 -0.0440846 0.01301062 -0.08116471 -0.001601219 0.01403635 0.01521486 0.002497732 0.01367735 0.01564568 0.01757884 0.01279401 0.03030085 0.03323572 0.01269549 0.06230241 0.04086273 0.01260298 0.07838809 0.04727584 0.01249706 0.09223318 0.05354863 0.01237124 0.1060584 0.07565534 0.01190221 0.1572939 0.06106692 0.01220417 0.1230379 0.05229973 0.01278913 0.111618 0.08375513 0.01180881 0.1772031 0.08852213 0.01179546 0.1891857 0.0927357 0.01181107 0.1998779 0.1019958 0.01194101 0.2242509 0.1060757 0.01197761 0.2353457 0.1090883 0.01197528 0.2436687 0.11208 0.01193523 0.2520849 0.115032 0.01184606 0.2605525 0.1171737 0.01174002 0.2667963 0.1186163 0.01164865 0.2710607 0.1200463 0.01153886 0.2753337 0.1214634 0.01140904 0.2796154 0.1228681 0.01125806 0.2839078 0.1242594 0.01108431 0.2882094 0.1256372 0.01088666 0.2925211 0.1270015 0.01066362 0.2968431 0.1283526 0.01041376 0.3011773 0.129689 0.01013576 0.3055212 0.1310115 0.009828329 0.3098778 0.1323156 0.009494245 0.314247 0.134104 0.008995413 0.3203536 0.1364485 0.00826776 0.328897 0.1400425 0.007029175 0.344067 0.1411813 0.006613969 0.3499466 0.1419803 0.006322741 0.3545369 0.1426848 0.006067931 0.3591628 0.1432881 0.005855858 0.3638277 0.1437823 0.00569266 0.3685332 0.1441594 0.005584836 0.3732812 0.1444125 0.005538642 0.3780752 0.1445339 0.005560338 0.3829169 0.144516 0.005656421 0.3878089 0.1443505 0.005833029 0.3927522 0.144031 0.006096541 0.3977511 0.1435494 0.006453335 0.4028064 0.1428915 0.006903648 0.4079183 0.1420339 0.007435321 0.4130833 0.1408293 0.008108675 0.4189454 0.1364425 0.009975194 0.4332289 0.133798 0.01083695 0.4395056 0.1099829 0.01490551 0.4725452 0.1311745 0.01157015 0.4448735 0.1221472 0.01299124 0.4533048 0.1209393 0.01307284 0.4539167 0.1193937 0.01360172 0.4583518 0.1042672 0.0152409 0.4779711 0.1078001 0.01474636 0.4708008 0.1092677 0.01428824 0.466921 -0.05318045 0.01385593 -0.08151632 -0.06940555 0.01470184 -0.03284949 -0.0767132 0.01431423 -0.03189742 -0.07092398 0.01453953 -0.02827763 -0.04246222 0.01507663 -0.01868438 -0.03325992 0.01504272 -0.008496463 0.004538238 0.01326709 0.01204937 0.01254141 0.01326 0.0279206 0.002298533 0.01434046 0.03062677 0.02821892 0.01317417 0.05980145 0.03590536 0.0130884 0.07590484 0.0424056 0.01298815 0.08983677 0.04708474 0.01289939 0.1000549 0.05897539 0.01263797 0.1267406 0.06921827 0.01241749 0.1506329 0.07579803 0.01230812 0.1664645 0.08060187 0.01225763 0.1782643 0.08482307 0.01223719 0.188783 0.08986479 0.01225137 0.2015129 0.09914404 0.01237243 0.2257645 0.1032185 0.01240432 0.2367518 0.1062708 0.01239901 0.2451197 0.1092892 0.01235538 0.2535383 0.1122569 0.01226246 0.2619609 0.1158734 0.01206022 0.2724501 0.117317 0.01194834 0.2767162 0.118748 0.01181644 0.2809909 0.1201668 0.01166331 0.2852762 0.1215724 0.01148754 0.2895705 0.1144175 0.01215362 0.2681925 0.1229649 0.01128762 0.2938748 0.124344 0.01106232 0.2981892 0.1257103 0.01081025 0.3025158 0.127062 0.01052981 0.3068519 0.1284002 0.01022017 0.3112005 0.1297203 0.009883642 0.3155617 0.1315214 0.009384691 0.3216174 0.1337786 0.008690178 0.3297085 0.1373817 0.00747013 0.3443491 0.1387487 0.006978929 0.3511789 0.1395749 0.006683647 0.3557554 0.1403089 0.006424427 0.3603664 0.1409441 0.006207466 0.365015 0.1414726 0.006039142 0.3697032 0.1418868 0.005925714 0.3744324 0.14218 0.00587356 0.3792061 0.1423444 0.005888819 0.384026 0.1423728 0.005977928 0.3888946 0.1422571 0.006147146 0.3938127 0.1419909 0.006402611 0.3987846 0.1415663 0.006750822 0.4038109 0.1409699 0.007191956 0.4088917 0.1401784 0.007713735 0.4140232 0.1389355 0.008430659 0.4202958 0.1347643 0.01026076 0.4344275 0.1298446 0.01130658 0.440918 0.1282554 0.01150888 0.4420916 0.127211 0.01209813 0.4468813 0.1236944 0.01313543 0.4561732 0.09962016 0.01528483 0.4824959 -0.06273365 0.01460385 -0.07667708 -0.06469625 0.0146985 -0.07568293 -0.01799196 0.0139926 -0.016694 -0.01279127 0.01433271 9.1767e-4 0.0113995 0.01366454 0.03335618 0.02709889 0.01356446 0.06541687 0.03379106 0.01348352 0.079499 0.03844064 0.01341068 0.08944183 0.043805 0.01331138 0.1010993 0.06790113 0.01278275 0.1561263 0.05156147 0.01314276 0.1183354 0.07612216 0.01266574 0.1760621 0.08184283 0.01263087 0.1902259 0.08699887 0.01264262 0.2031731 0.09628409 0.01275575 0.2272729 0.1003685 0.01278364 0.2381969 0.1034387 0.01277518 0.2465383 0.1064788 0.01272845 0.2549368 0.1094744 0.01263242 0.2633608 0.1116562 0.01252114 0.2695913 0.1131254 0.01242595 0.2738421 0.1145825 0.01231223 0.2781013 0.1160274 0.01217854 0.282369 0.1174603 0.01202356 0.2866472 0.1188804 0.01184582 0.2909342 0.1202874 0.01164394 0.2952311 0.1216815 0.01141667 0.299538 0.123063 0.01116251 0.3038568 0.1244302 0.01088017 0.3081851 0.1257841 0.01056832 0.3125258 0.1271202 0.01022964 0.3168787 0.1284315 0.009870469 0.3212466 0.1303899 0.009297132 0.3279138 0.1341648 0.008055329 0.34245 0.1359805 0.007422149 0.3506542 0.137165 0.007004439 0.3569762 0.1379286 0.006741225 0.3615721 0.1385957 0.006520032 0.3662046 0.1391586 0.006347119 0.3708754 0.13961 0.006228744 0.3755857 0.1399433 0.006171226 0.3803391 0.1401507 0.006180822 0.3851372 0.1402257 0.006263732 0.3899823 0.1401596 0.006426215 0.3948752 0.1399471 0.006674647 0.3998199 0.1395797 0.007015228 0.4048172 0.1390448 0.007448136 0.4098669 0.1383193 0.007961153 0.414965 0.1373771 0.008540332 0.4201045 0.1361839 0.009201943 0.425552 0.1329995 0.01053643 0.4357098 0.1249945 0.01222121 0.4472875 0.1258863 0.01223105 0.4475523 0.1285349 0.01194381 0.4462107 0.1201494 0.01303118 0.4536827 0.1177631 0.01371049 0.459204 -0.05970829 0.01441997 -0.07820957 -0.06633991 0.01476252 -0.07485026 -0.05538028 0.01407116 -0.08040195 -0.07351678 0.01489496 -0.07121479 -0.07177948 0.01490783 -0.06713855 -0.07081729 0.01487183 -0.07258224 -0.04837793 0.01482009 -0.04495722 -0.02913492 0.01425915 -0.03059518 -0.02096873 0.01430255 -0.01491802 -0.01287919 0.01459848 0.008343696 -0.005817592 0.01460528 0.02221721 0.006365418 0.01402932 0.03101342 0.02209246 0.013942 0.06297063 0.02979582 0.01385498 0.07908731 0.0353713 0.01376849 0.09099298 0.04073315 0.01366853 0.1026238 0.06344574 0.01316326 0.1542585 0.04842436 0.01350039 0.1196829 0.07142764 0.01303392 0.1734178 0.07813042 0.01297736 0.1898592 0.08411908 0.01298588 0.2048093 0.09343421 0.01309251 0.2288243 0.09752869 0.01311689 0.2396948 0.1006113 0.01310569 0.2479937 0.1036702 0.01305621 0.2563677 0.1066904 0.01295721 0.2647769 0.1088904 0.01284366 0.2709923 0.110373 0.01274693 0.2752364 0.1118437 0.01263165 0.2794888 0.1133024 0.01249635 0.2837494 0.1147494 0.01233965 0.2880204 0.1161839 0.01216024 0.2923001 0.1176057 0.01195675 0.2965896 0.1190147 0.01172763 0.3008888 0.1204113 0.01147174 0.3052 0.1217941 0.01118755 0.3095204 0.1231637 0.01087397 0.3138532 0.1245158 0.01053345 0.318198 0.1258438 0.01017212 0.3225575 0.1277673 0.009614467 0.3290007 0.13164 0.008356928 0.3435835 0.1335281 0.007709026 0.3518818 0.1347512 0.007285952 0.3581989 0.1355444 0.007019221 0.3627799 0.1362434 0.006794333 0.3673962 0.1368409 0.006617426 0.3720494 0.1373295 0.00649476 0.3767409 0.1377028 0.006432533 0.381474 0.1379535 0.006437063 0.3862502 0.1380748 0.006514549 0.3910717 0.1380587 0.006671249 0.3959394 0.1378998 0.006913423 0.4008569 0.1375895 0.007247269 0.4058254 0.1371161 0.007673025 0.4108439 0.1364575 0.008178234 0.415908 0.1355876 0.008749067 0.4210109 0.1343105 0.00947237 0.4269706 0.1049938 0.01520532 0.4776026 0.1033002 0.0152617 0.4784608 0.1080901 0.01416856 0.4671148 0.1062086 0.0146951 0.4716088 0.09864515 0.0152617 0.4829921 -0.06559497 0.01482129 -0.07023459 -0.03115117 0.01452445 -0.02698892 -0.02090883 0.0145753 -0.007276177 -0.02819997 0.0149393 -0.006272614 -0.004778802 0.0143457 0.01659822 0.01708102 0.01426798 0.06055164 0.02481085 0.01418817 0.07662528 0.03226131 0.01407831 0.09245598 0.0394203 0.01393914 0.108022 0.04691666 0.01377052 0.1247001 0.05845737 0.01350903 0.1512238 0.06510084 0.01338332 0.1669299 0.07182353 0.01329672 0.1831689 0.07672744 0.01327276 0.1952415 0.0812298 0.01328158 0.2064375 0.09055572 0.01338201 0.2303103 0.09466993 0.01340347 0.2411441 0.09778064 0.01339012 0.2494539 0.1008539 0.01333808 0.2577797 0.1039072 0.01323646 0.2662065 0.1061207 0.01312136 0.2723953 0.1076166 0.01302325 0.2766327 0.109101 0.01290655 0.2808781 0.1105735 0.01276981 0.2851317 0.1120349 0.01261186 0.2893955 0.1134837 0.01243096 0.2936679 0.1149202 0.01222592 0.2979499 0.1163442 0.01199543 0.3022416 0.117756 0.01173794 0.3065451 0.1191542 0.01145213 0.3108577 0.1205396 0.01113694 0.3151824 0.1219078 0.01079481 0.3195191 0.1232524 0.01043194 0.3238701 0.1249353 0.009950101 0.3294087 0.1290339 0.00864309 0.3444185 0.1304383 0.008167028 0.3503834 0.1314254 0.007833123 0.3548885 0.1323339 0.007528245 0.3594233 0.1331568 0.007258653 0.3639893 0.1338878 0.007030427 0.3685894 0.1345199 0.006850123 0.3732251 0.1350458 0.006723642 0.3778978 0.1354593 0.006657421 0.3826105 0.1357532 0.00665766 0.3873649 0.1359214 0.006730437 0.3921626 0.1359552 0.006882131 0.397005 0.1358498 0.00711894 0.4018954 0.1355975 0.007447063 0.4068345 0.1351857 0.007866561 0.4118217 0.1345931 0.008365154 0.4168525 0.1337945 0.008928716 0.4219192 0.1325057 0.009690105 0.4282059 0.1234762 0.01237213 0.4484313 0.1252413 0.01124 0.4400343 0.107738 0.01505017 0.4736843 0.1187748 0.01312482 0.4546886 0.1173112 0.01320481 0.4557545 0.1204713 0.01351141 0.4578059 0.1070701 0.01414173 0.4677973 0.09558951 0.01510185 0.4863228 -0.05943715 0.01455032 -0.07337325 -0.07710158 0.01486909 -0.06939888 -0.07794994 0.01482504 -0.06401622 -0.03424996 0.01473313 -0.02544087 -0.0250557 0.01477968 -0.007741391 0.01005291 0.01455557 0.05404144 0.01786339 0.01449066 0.07011353 0.02358812 0.01442116 0.08211177 0.02916342 0.01433634 0.09396034 0.03636145 0.01419621 0.1095961 0.04322278 0.01404166 0.1248298 0.05571103 0.01375555 0.1533917 0.06372815 0.01360988 0.1723675 0.06867432 0.01355051 0.1842956 0.07297039 0.01352244 0.1947913 0.07806426 0.01352864 0.2074105 0.087484 0.0136221 0.2312629 0.09180998 0.0136435 0.2426042 0.094931 0.01362812 0.25086 0.09804511 0.01357424 0.2592393 0.1011165 0.01347041 0.2676216 0.1033477 0.01335382 0.2738 0.104857 0.01325464 0.2780305 0.106355 0.01313686 0.2822691 0.1078414 0.01299893 0.2865157 0.109317 0.01283961 0.2907723 0.1107802 0.01265764 0.2950373 0.1122316 0.01245135 0.2993119 0.1136704 0.01221954 0.303596 0.1150975 0.01196086 0.3078917 0.1165112 0.01167374 0.3121965 0.1179124 0.01135724 0.3165132 0.1192968 0.01101374 0.3208417 0.120658 0.01064944 0.3251844 0.1224967 0.0101267 0.3311637 0.1265943 0.008832335 0.3459393 0.1279652 0.008374452 0.3516361 0.1289778 0.008038341 0.3561283 0.1299139 0.007731139 0.3606492 0.1307664 0.007459044 0.3652002 0.1315295 0.007228255 0.3697841 0.1321961 0.007044911 0.3744022 0.1327594 0.00691533 0.379056 0.1332128 0.006845712 0.3837485 0.1335507 0.006842315 0.3884806 0.1337652 0.006911218 0.3932548 0.133849 0.007058739 0.3980719 0.1337971 0.007291018 0.4029352 0.1336019 0.007614314 0.4078453 0.1332526 0.008028626 0.412801 0.132726 0.008521735 0.4177983 0.1319996 0.009079217 0.4228284 0.1310507 0.009687244 0.4278839 0.1297329 0.01041162 0.4335833 0.1023178 0.01525527 0.4789588 0.1046172 0.01460659 0.4724175 0.1056281 0.01408404 0.4687424 -0.06869441 0.01483219 -0.07365757 -0.03638166 0.01489824 -0.02202749 -0.01697438 0.01480579 0.007952451 -0.02945512 0.01516473 0.0140531 -0.02523636 0.01514619 0.014669 -0.008883476 0.01481431 0.0238406 0.006972908 0.01476442 0.05563271 0.01475137 0.01469945 0.07162541 0.02149194 0.01461619 0.08575421 0.02789491 0.01451206 0.09941804 0.03684806 0.01432549 0.1189302 0.05334538 0.01394742 0.1565007 0.06071394 0.01381319 0.1738753 0.06565731 0.01375287 0.1857516 0.06997108 0.01372355 0.1962387 0.07512694 0.01372796 0.2089332 0.08464908 0.01381832 0.2328805 0.08894032 0.01383703 0.2440432 0.09209555 0.01382023 0.2523304 0.09522294 0.01376467 0.2606554 0.09832572 0.013659 0.2690551 0.100572 0.01354134 0.275206 0.1020946 0.01344126 0.2794299 0.1036064 0.01332253 0.2836614 0.1051067 0.01318377 0.287901 0.1065964 0.01302343 0.2921504 0.1080742 0.01284044 0.2964081 0.1095402 0.01263314 0.3006752 0.1109941 0.01240032 0.3049517 0.1124365 0.01214063 0.3092398 0.1152826 0.01153486 0.3178454 0.1166831 0.01119035 0.3221657 0.118061 0.01082491 0.3264999 0.1198405 0.01032441 0.3322016 0.1138657 0.01185256 0.3135366 0.1240718 0.009007513 0.3471412 0.1254897 0.008541643 0.3528901 0.1265279 0.008203864 0.3573694 0.1274914 0.007894754 0.3618764 0.1283737 0.007620632 0.3664122 0.1291689 0.007387757 0.3709799 0.12987 0.007202029 0.3755806 0.1304703 0.007070064 0.3802155 0.1309648 0.006997644 0.3848872 0.1313454 0.006991267 0.3895976 0.1316064 0.007057011 0.3943484 0.1317411 0.007201135 0.3991397 0.1317427 0.007429838 0.4039759 0.1316054 0.007749259 0.4088566 0.1313168 0.008159458 0.4137816 0.130858 0.008647918 0.4187446 0.1302039 0.009200632 0.4237381 0.1293326 0.009803354 0.4287542 0.1279613 0.01058602 0.4349055 0.1235247 0.01137018 0.4413796 0.1208087 0.01198637 0.4464626 0.1064537 0.01507765 0.4743353 -0.05517828 0.0149036 -0.05044817 -0.04331868 0.0149874 -0.02783381 -0.0200479 0.01496577 0.009563386 -0.01198649 0.01497429 0.02539575 0.004903495 0.01491808 0.05928105 0.01359564 0.01483809 0.07721596 0.0193457 0.01476138 0.08930784 0.02556461 0.01465773 0.1025806 0.03446739 0.01446801 0.1220515 0.04927015 0.01412516 0.1556085 0.05769062 0.01396894 0.1753738 0.06270325 0.01390707 0.1873575 0.06700229 0.01387715 0.1977562 0.07219821 0.01388055 0.2104839 0.08180505 0.0139687 0.2344861 0.08608692 0.01398521 0.2455399 0.0892415 0.01396721 0.2537439 0.09240168 0.01391041 0.2620894 0.09552592 0.0138036 0.2704616 0.09779417 0.01368486 0.2766132 0.09933024 0.01358401 0.2808302 0.1008555 0.01346462 0.2850549 0.1023699 0.01332515 0.2892873 0.1038738 0.01316416 0.2935296 0.1053661 0.01298034 0.29778 0.1068468 0.01277232 0.3020396 0.1083158 0.01253873 0.3063085 0.1097733 0.01227825 0.3105888 0.1112182 0.01198935 0.3148778 0.1126508 0.01167082 0.3191785 0.1140674 0.01132541 0.3234907 0.1154621 0.01095926 0.3278164 0.1171319 0.01049637 0.3330659 0.1213515 0.009204983 0.347601 0.1230123 0.008669614 0.3541451 0.1240761 0.008330523 0.3586114 0.1250672 0.008020043 0.3631044 0.1259792 0.007744431 0.3676252 0.1268062 0.007509768 0.3721767 0.1275426 0.007322311 0.3767595 0.1281803 0.00718832 0.3813755 0.128715 0.007113933 0.3860269 0.1291384 0.00710535 0.3907156 0.1294467 0.00716865 0.3954424 0.1296313 0.007310152 0.4002084 0.1296864 0.007536053 0.4050175 0.1296072 0.007852435 0.4098689 0.1293801 0.008259415 0.4147626 0.1289873 0.008744537 0.4196922 0.1284055 0.009293556 0.4246491 0.1276136 0.009892165 0.429625 0.1265887 0.01052635 0.4346123 0.09735 0.01517587 0.4836477 0.101315 0.01485693 0.4769375 0.1025974 0.01495593 0.4762883 0.1030357 0.01448428 0.4732179 -0.0453611 0.01509571 -0.009224832 -0.04117763 0.01512295 -0.008705675 -0.02522754 0.01507264 0.007073163 -0.0171442 0.01508617 0.02290368 -0.001153111 0.01504802 0.05483776 0.006661713 0.01498991 0.07081347 0.01437878 0.01490116 0.08688926 0.02248239 0.01476931 0.1041346 0.04242509 0.01432096 0.1484003 0.03061211 0.0145967 0.1218829 0.04855012 0.01418882 0.162539 0.05470728 0.01407754 0.1769636 0.05973988 0.01401519 0.1889441 0.06401318 0.01398503 0.1992373 0.06928223 0.0139876 0.2120651 0.07895982 0.01407408 0.23608 0.08321815 0.01408904 0.246996 0.08639383 0.01407027 0.2551881 0.08957523 0.01401263 0.263504 0.09272563 0.01390492 0.271872 0.09501487 0.01378542 0.278021 0.09656429 0.01368421 0.2822313 0.09810334 0.01356422 0.286449 0.09963154 0.01342421 0.2906745 0.1011497 0.01326274 0.2949095 0.1026565 0.01307845 0.2991525 0.104152 0.01286995 0.3034046 0.105636 0.01263576 0.307666 0.1071089 0.01237463 0.3119385 0.1085691 0.01208525 0.3162196 0.1100177 0.01176625 0.3205124 0.1114505 0.01142024 0.3248164 0.1128617 0.01105332 0.3291336 0.1145256 0.01059746 0.3342893 0.118802 0.009307622 0.348739 0.1205337 0.008759438 0.3554006 0.1216233 0.008419334 0.3598539 0.1226413 0.008107841 0.3643332 0.1235831 0.007831156 0.368839 0.1244431 0.00759536 0.3733738 0.1252134 0.007406651 0.3779394 0.1258886 0.007271349 0.3825364 0.1264634 0.007195413 0.3871675 0.1269305 0.00718522 0.391834 0.1272852 0.007246911 0.3965373 0.1275197 0.007386624 0.401278 0.1276293 0.007610559 0.4060595 0.1276071 0.007924854 0.410882 0.1274425 0.008329629 0.4157441 0.1271166 0.008812248 0.4206398 0.1266071 0.009358644 0.4255601 0.1258928 0.009954452 0.4304967 0.1249535 0.01058554 0.4354407 0.1191779 0.01207 0.4477513 0.105162 0.01506912 0.47499 0.1013481 0.0152238 0.4794499 0.09494286 0.01505184 0.4866502 -0.08336466 0.0146988 -0.0662263 -0.08623313 0.0145682 -0.0647732 -0.03435957 0.01511722 -0.003069341 -0.01622015 0.01515114 0.03242421 -3.37352e-4 0.01508831 0.06436401 0.007435142 0.0150153 0.08039027 0.01592135 0.0148971 0.09824413 0.02557933 0.0147072 0.1190881 0.039815 0.01437592 0.1509599 0.04550671 0.01425343 0.1640486 0.05166268 0.01414197 0.1784198 0.05671906 0.01407903 0.1904015 0.06105935 0.01404809 0.2007955 0.06633973 0.01405042 0.2135928 0.07610404 0.01413613 0.2376583 0.08033782 0.0141499 0.2484201 0.08355391 0.01413059 0.2566572 0.08675718 0.01407223 0.264963 0.08992427 0.01396429 0.2732832 0.09223467 0.01384443 0.2794294 0.0937975 0.01374292 0.2836328 0.0953502 0.01362276 0.2878437 0.09689235 0.01348233 0.292062 0.09842473 0.01332062 0.2962898 0.09994602 0.01313596 0.3005256 0.1014563 0.01292711 0.3047702 0.1029553 0.01269263 0.3090239 0.1044435 0.01243126 0.3132886 0.1059193 0.01214146 0.3175619 0.1073836 0.01182216 0.3218467 0.1088326 0.01147574 0.3261425 0.1102605 0.01110851 0.3304513 0.1119262 0.01065039 0.3356313 0.1165081 0.009293675 0.3508132 0.1180543 0.00881201 0.3566566 0.1191692 0.008471429 0.361097 0.1202149 0.008159339 0.3655624 0.121187 0.007882058 0.3700528 0.1220782 0.007645547 0.3745717 0.1228833 0.007456123 0.3791198 0.123596 0.007319927 0.3836978 0.1242109 0.007243216 0.3883085 0.1247218 0.007232129 0.3929529 0.1251237 0.007292747 0.3976323 0.1254082 0.007431447 0.4023476 0.1255713 0.007654249 0.4071021 0.1256071 0.007967352 0.4118952 0.125504 0.008370757 0.4167261 0.125245 0.008852064 0.4215878 0.1248077 0.009396851 0.4264715 0.1112009 0.01378583 0.4626865 0.1241719 0.00999093 0.4313684 0.1233183 0.01062023 0.436269 0.1222251 0.01127052 0.4411677 0.1112612 0.01308733 0.4588192 0.1137079 0.01262229 0.4544245 0.1003793 0.01516973 0.4799407 -0.08127409 0.01477324 -0.06728523 -0.08906626 0.01441252 -0.06333804 -0.0927205 0.01416504 -0.06148695 -0.09552133 0.01394504 -0.06006819 -0.03559404 0.01508164 0.01731157 -0.02134281 0.01517349 0.02998989 -0.004384398 0.01511704 0.06398689 0.004356741 0.01503634 0.08198618 0.01284676 0.01491808 0.09982937 0.02221316 0.01473474 0.1199979 0.03660351 0.01440054 0.1521323 0.04241687 0.01427543 0.1654543 0.04862189 0.01416307 0.1798843 0.05369961 0.01409983 0.1918671 0.05807286 0.0140686 0.2022863 0.06338357 0.01407068 0.2150806 0.07324463 0.01415652 0.2392166 0.07747787 0.01416951 0.2499116 0.08070534 0.01415008 0.2580958 0.08392965 0.01409173 0.2663845 0.08712327 0.01398354 0.2746992 0.08945399 0.01386356 0.280838 0.09103018 0.01376193 0.2850346 0.09259653 0.01364165 0.2892385 0.09415274 0.01350122 0.2934498 0.09569925 0.01333934 0.2976704 0.09723508 0.01315456 0.3018988 0.09876006 0.01294565 0.306136 0.100274 0.01271104 0.3103821 0.1017776 0.01244956 0.3146391 0.1032689 0.01215964 0.3189045 0.1047491 0.01184016 0.3231812 0.1062143 0.01149374 0.3274688 0.1084022 0.01093649 0.3339474 0.1128997 0.009642124 0.3483061 0.1143733 0.009192109 0.3535082 0.1155743 0.008829057 0.3579128 0.1167142 0.008488237 0.3623406 0.1177884 0.008176028 0.3667915 0.1187899 0.007898449 0.371267 0.1197133 0.007661759 0.3757696 0.1205532 0.007472157 0.3803001 0.1213033 0.007335722 0.3848591 0.1219584 0.007258653 0.3894495 0.122513 0.007247209 0.3940718 0.1229613 0.007307648 0.3987277 0.1232958 0.007445931 0.4034177 0.1235133 0.007668316 0.4081445 0.123607 0.007981061 0.4129083 0.1235656 0.008384048 0.417708 0.1233726 0.00886482 0.4225364 0.1230084 0.009409129 0.427383 0.1224511 0.01000273 0.4322401 0.1216823 0.01063156 0.4370977 0.1206826 0.01128113 0.441949 0.101467 0.01433283 0.4740086 0.1000293 0.01473355 0.4775897 -0.05575466 0.01499092 -0.02168023 -0.05469954 0.01479482 -0.004619956 -0.05769544 0.01462197 -0.002865135 -0.03124517 0.01514774 0.01817333 -0.01244139 0.01512402 0.05551141 -0.004559874 0.01507282 0.07153058 0.003197789 0.01499187 0.08757466 0.008846104 0.01490938 0.09947282 0.01412582 0.01481688 0.1107283 0.02096152 0.01467198 0.1255627 0.03346723 0.0143817 0.1534723 0.03938812 0.01425451 0.1669989 0.0456143 0.01414227 0.1814278 0.05072617 0.01407909 0.1934307 0.0550723 0.01404827 0.2037454 0.05924278 0.0140472 0.213733 0.06288319 0.0140686 0.2224614 0.07185494 0.01414626 0.2444804 0.07624024 0.01414418 0.2554631 0.07948881 0.01410681 0.2636905 0.08272129 0.01402503 0.2719707 0.08591747 0.01388847 0.2802656 0.08826285 0.01374292 0.2864364 0.08984297 0.01362276 0.2906334 0.09141308 0.01348245 0.2948376 0.09297388 0.01332062 0.299051 0.09452414 0.01313596 0.303272 0.09606397 0.01292711 0.3075017 0.09759283 0.01269263 0.3117403 0.09911191 0.01243126 0.3159894 0.1006185 0.01214146 0.3202471 0.1021149 0.01182216 0.3245156 0.1035957 0.01147586 0.3287953 0.1057804 0.01092594 0.3351808 0.1103508 0.009631037 0.3495175 0.1118692 0.009174942 0.3547766 0.1130943 0.00881201 0.3591691 0.1142601 0.008471429 0.3635838 0.115362 0.008159339 0.3680206 0.1163929 0.007882058 0.3724812 0.1173484 0.007645547 0.3769676 0.1182231 0.007456123 0.3814804 0.1190107 0.007319927 0.3860205 0.1197059 0.007243216 0.3905905 0.1203042 0.007232129 0.3951906 0.1207989 0.007292747 0.399823 0.1211842 0.007431447 0.4044873 0.1214553 0.007654249 0.409187 0.1216061 0.007967352 0.4139219 0.1216271 0.008370757 0.41869 0.121501 0.008852064 0.4234844 0.1119447 0.01242655 0.4546759 0.1212082 0.009396851 0.4282949 0.1207303 0.00999093 0.4331117 0.1200462 0.01062023 0.4379265 0.1191402 0.01127052 0.4427304 0.1038811 0.01502752 0.475638 0.1094391 0.01300197 0.4598488 0.1076335 0.01287931 0.460834 0.09607607 0.01504355 0.4842925 -0.09880304 0.01365745 -0.05840581 -0.1016935 0.01337677 -0.05694162 -0.05876249 0.01489078 -0.01995033 -0.04466432 0.01505136 -3.24383e-4 -0.01265305 0.01504617 0.06291407 -0.006717979 0.01500231 0.07502436 1.23151e-4 0.01492989 0.08917635 0.007607281 0.01481866 0.1049432 0.0292499 0.01434725 0.1523397 0.01466464 0.01468122 0.1201066 0.03637343 0.01419359 0.1685739 0.04261398 0.01408201 0.1829808 0.04770302 0.01401948 0.1948879 0.05210644 0.01398879 0.2052748 0.05749827 0.01399153 0.2181224 0.06752991 0.0140798 0.2423521 0.05456662 0.01389551 0.2196661 0.07172232 0.01409232 0.2527821 0.07502067 0.01407331 0.261017 0.07827818 0.01401579 0.2692396 0.08152341 0.01390856 0.2775229 0.08389288 0.01378893 0.283655 0.08549612 0.01368761 0.287838 0.08708959 0.01356774 0.2920281 0.08867412 0.01342761 0.296225 0.09024888 0.01326614 0.3004314 0.09181386 0.01308184 0.304645 0.09336858 0.01287323 0.308867 0.09491217 0.01263916 0.3130982 0.09644639 0.01237791 0.3173397 0.09796905 0.01208853 0.3215892 0.09948056 0.01176941 0.32585 0.1009783 0.01142346 0.3301212 0.1031525 0.01088362 0.3363876 0.1078022 0.009586632 0.3507331 0.1093661 0.009124934 0.3560446 0.1106144 0.008762419 0.3604253 0.111806 0.008422434 0.3648269 0.1129356 0.008110821 0.3692498 0.1139959 0.007834136 0.3736954 0.1149835 0.007598221 0.3781656 0.115893 0.007409512 0.3826608 0.1167181 0.00727415 0.3871818 0.1174543 0.007198214 0.3917311 0.1180954 0.007187962 0.3963095 0.1186374 0.007249534 0.400918 0.1190727 0.007389247 0.4055569 0.1193972 0.007613122 0.4102296 0.1196061 0.007927358 0.414935 0.1196886 0.008332014 0.419672 0.1196295 0.008814632 0.4244325 0.1194089 0.009360849 0.4292064 0.1190086 0.009956538 0.4339839 0.118411 0.01058763 0.4387548 0.1175978 0.01123976 0.4435117 0.09989058 0.01415538 0.4748054 0.09875768 0.01459026 0.4782321 -0.044384 0.01496583 0.007774174 -0.04680299 0.01466435 0.01827847 -0.03266566 0.01498919 0.03070342 -0.0136587 0.01493304 0.06872469 -0.003932416 0.01484191 0.08872318 0.004508614 0.01471871 0.1064629 0.02376967 0.01430445 0.1484526 0.01153147 0.01458251 0.1215326 0.03082805 0.01414608 0.1643779 0.03783124 0.01401203 0.1804147 0.04296475 0.01394045 0.1923288 0.04648405 0.01390719 0.2005614 0.04994189 0.01389044 0.2087089 0.06466639 0.01398605 0.243891 0.0688638 0.01399886 0.2542662 0.07217675 0.01398038 0.2624761 0.07545584 0.0139237 0.2706804 0.0787326 0.01381641 0.2789885 0.08111315 0.01369845 0.2850631 0.08272981 0.01359766 0.2892393 0.08433753 0.01347815 0.2934222 0.08593547 0.01333856 0.2976123 0.08752447 0.01317745 0.3018115 0.08910369 0.01299363 0.3060178 0.09067273 0.01278555 0.3102327 0.09223234 0.01255184 0.3144557 0.09378176 0.01229125 0.3186894 0.09531956 0.01200222 0.3229313 0.09684717 0.01168376 0.327184 0.09836095 0.01133835 0.331447 0.1005159 0.01080983 0.3375832 0.1052522 0.009510457 0.3519468 0.1068638 0.009043514 0.3573122 0.1081353 0.008681833 0.3616811 0.1093528 0.008342564 0.3660696 0.1105091 0.008031964 0.3704789 0.1115998 0.007756114 0.3749092 0.1126204 0.007521331 0.3793626 0.1135638 0.007333755 0.3838406 0.1144263 0.007199525 0.3883427 0.1152027 0.00712496 0.3928716 0.1158875 0.007116138 0.3974279 0.1164759 0.00717926 0.4020129 0.1169612 0.007320523 0.4066266 0.1173401 0.007546126 0.4112716 0.1176061 0.00786221 0.4159482 0.117751 0.008268952 0.4206535 0.1107029 0.01088154 0.4470217 0.1177579 0.008753716 0.4253805 0.1176105 0.009302318 0.4301174 0.1172887 0.009900629 0.4348551 0.1167759 0.01053446 0.4395831 0.1101075 0.01156532 0.4515292 0.1092984 0.01224452 0.4559868 0.1038181 0.0138967 0.4695036 -0.08720189 0.01441562 -0.05937474 -0.04373782 0.0148378 0.01665079 -0.03567117 0.01485103 0.03245872 -0.02071499 0.01481765 0.06227898 -0.0138334 0.01477217 0.0762521 -0.00610429 0.0146923 0.09220308 0.001433253 0.01458102 0.1080452 0.02046108 0.01417404 0.1494357 0.008445024 0.0144456 0.1230676 0.02779412 0.01401066 0.1659209 0.03479272 0.0138778 0.1818997 0.03995937 0.0138067 0.1938396 0.04350316 0.01377397 0.2020882 0.04789388 0.01375561 0.2123832 0.05253326 0.01377058 0.2233583 0.06182992 0.01385766 0.2455033 0.06599467 0.01387095 0.2557145 0.06931096 0.01385402 0.2638504 0.07263177 0.01379817 0.2720909 0.07592976 0.01369231 0.2803744 0.07833522 0.01357465 0.2864702 0.07996433 0.01347434 0.2906401 0.08158546 0.01335543 0.2948163 0.08319765 0.01321655 0.2989992 0.08480095 0.01305615 0.3031911 0.08639538 0.01287281 0.3073897 0.08797866 0.01266545 0.3115974 0.08955347 0.01243245 0.3158127 0.09111803 0.01217252 0.3200387 0.09267103 0.01188421 0.3242729 0.09421467 0.01156646 0.3285175 0.09574455 0.01122164 0.3327724 0.09769392 0.01075404 0.3382131 0.1025919 0.009428977 0.3528745 0.1043615 0.008931934 0.3585797 0.105658 0.008571326 0.362936 0.1069005 0.008233249 0.3673118 0.1080844 0.007923841 0.3717072 0.1092046 0.007649362 0.3761225 0.1102573 0.007416009 0.3805597 0.1112355 0.007229924 0.38502 0.1121355 0.007097423 0.3895032 0.112952 0.007024645 0.3940117 0.1136806 0.007017731 0.3985459 0.1143153 0.007082939 0.4031074 0.1148505 0.007226467 0.4076957 0.1152839 0.007454454 0.4123132 0.1156069 0.00777316 0.4169608 0.1151416 0.01046156 0.440411 0.1158143 0.008182644 0.4216345 0.1158881 0.00867033 0.4263277 0.1158121 0.009222149 0.4310284 0.1155688 0.009823918 0.4357264 0.09939855 0.0150941 0.4804379 0.102696 0.01312655 0.4669152 0.1017407 0.01373839 0.4708325 0.09430438 0.01498031 0.4869735 0.09693717 0.01435989 0.4791596 0.09761011 0.01386976 0.4759821 -0.07870048 0.01408308 -0.02822929 -0.08284866 0.01380741 -0.02872109 -0.06756746 0.01361924 0.008209824 -0.069292 0.01389354 -0.002658426 -0.01695579 0.01459914 0.07775455 -0.009203791 0.01451951 0.09373474 -0.002602815 0.0144239 0.1075817 0.004526317 0.01429212 0.1227815 0.01781541 0.01399326 0.1519058 0.02471578 0.01384115 0.1673702 0.03181207 0.01370835 0.1834996 0.03700381 0.01363837 0.1954501 0.04052037 0.01360678 0.2036023 0.04494559 0.01358944 0.2139254 0.04959249 0.01360559 0.2248559 0.0589537 0.01369595 0.247003 0.06313258 0.0137099 0.2571918 0.06647711 0.01369386 0.2653396 0.06981873 0.01363909 0.2735649 0.07313024 0.01353538 0.2817924 0.07555818 0.01341891 0.287877 0.07720071 0.01331943 0.2920401 0.07883608 0.01320123 0.296209 0.08046168 0.01306313 0.3003851 0.08207923 0.01290351 0.3045698 0.083687 0.01272106 0.3087617 0.08528637 0.01251453 0.3129612 0.08687543 0.01228231 0.3171693 0.0884552 0.01202321 0.3213877 0.09002423 0.01173585 0.3256137 0.09158396 0.01141893 0.3298501 0.09312897 0.01107501 0.3340973 0.09524935 0.01056897 0.3399843 0.1001738 0.009263396 0.3544308 0.1018611 0.008791744 0.3598464 0.1031807 0.008432447 0.3641909 0.104449 0.00809586 0.3685536 0.1056607 0.007787942 0.3729349 0.1068112 0.007515132 0.3773349 0.1078951 0.007283627 0.3817563 0.1089081 0.007099509 0.386199 0.1098455 0.006969034 0.3906632 0.1107022 0.006898522 0.3951514 0.1114745 0.006894052 0.3996634 0.1121556 0.006961822 0.4042013 0.1127417 0.007108151 0.408764 0.1132276 0.007339239 0.4133548 0.1138497 0.009727537 0.4365972 0.1136096 0.007661163 0.4179726 0.1094789 0.01007336 0.4432912 0.1138776 0.008074045 0.4226155 0.1140183 0.008565545 0.4272749 0.1140145 0.009121358 0.431939 0.1066524 0.01201266 0.4573166 0.1063511 0.01280367 0.4616677 -0.1047024 0.01306015 -0.05541741 -0.1081537 0.01266938 -0.05366915 -0.06305378 0.01440197 -0.00566399 -0.04969751 0.01445978 0.0202127 -0.05921226 0.01393938 0.0168603 -0.05824083 0.01365405 0.02633708 -0.03512287 0.01421916 0.05666488 -0.02203816 0.01440781 0.07525056 -0.01422977 0.01433581 0.09127044 -0.006536841 0.01423197 0.1073338 0.01399737 0.01380681 0.1517246 3.71442e-4 0.01410734 0.1220214 0.02166289 0.01363831 0.1688637 0.02775305 0.01352399 0.1826565 0.03408366 0.01343506 0.1971365 0.03925818 0.01339745 0.2091107 0.04279214 0.01339209 0.217324 0.04667687 0.0134086 0.2264071 0.05609756 0.01350283 0.2485486 0.06025254 0.01351815 0.2585964 0.06362628 0.01350378 0.2667464 0.06698548 0.01345127 0.2749339 0.07033139 0.01334846 0.2831902 0.07278203 0.01323294 0.2892833 0.07443886 0.01313436 0.2934391 0.07608675 0.01301711 0.2976017 0.0777266 0.01287984 0.3017706 0.07935839 0.01272124 0.305948 0.08098137 0.01253974 0.3101322 0.08259499 0.01233416 0.3143245 0.08419924 0.01210302 0.3185249 0.08579415 0.01184493 0.3227356 0.08737921 0.01155865 0.3269535 0.08895409 0.01124274 0.3311823 0.09051609 0.01089996 0.3354209 0.09263271 0.01040011 0.3412423 0.09763318 0.009098529 0.355664 0.09936237 0.008624315 0.3611121 0.1007052 0.008266627 0.3654449 0.1019994 0.007931649 0.3697945 0.1032387 0.007625639 0.3741618 0.1044178 0.007354855 0.3785473 0.1055347 0.007125437 0.382952 0.1065824 0.006943643 0.3873771 0.1075565 0.006815731 0.3918227 0.1084542 0.006747841 0.3962902 0.1092693 0.006746351 0.4007805 0.1099968 0.006817221 0.4052949 0.1106328 0.006966948 0.4098322 0.1122179 0.009001016 0.4328491 0.1111732 0.007201552 0.4143955 0.1116122 0.007527351 0.4189844 0.1076266 0.01061284 0.4485728 0.1119427 0.007944464 0.4235957 0.107234 0.01131385 0.4529751 0.1121494 0.008440315 0.4282216 0.0984373 0.01500153 0.480924 0.1006904 0.01292204 0.4680854 0.09476196 0.01487207 0.484958 -0.06393522 0.01417565 1.48144e-4 -0.05196177 0.01422101 0.02341097 -0.02864128 0.0141896 0.0697081 -0.02118968 0.01413649 0.08485937 -0.01341772 0.01404911 0.1009273 -0.004162609 0.01390075 0.1204268 0.01157695 0.01355648 0.1546767 0.01859503 0.01340454 0.1703149 0.0247423 0.01329076 0.1841925 0.03107511 0.01320326 0.1986299 0.0363149 0.01316756 0.2106776 0.03981626 0.01316308 0.2187865 0.04373514 0.01318079 0.2279038 0.05324417 0.01327973 0.2501024 0.05740535 0.01329618 0.2601011 0.06079012 0.01328337 0.2682142 0.06417351 0.01323246 0.2763919 0.06753998 0.01313215 0.2846128 0.07000768 0.01301831 0.2906886 0.07167786 0.01292073 0.2948377 0.07334005 0.01280462 0.2989931 0.07499325 0.01266843 0.3031552 0.07663935 0.01251083 0.3073254 0.07827657 0.01233053 0.3115023 0.07990539 0.01212602 0.315687 0.08152389 0.01189613 0.3198801 0.08313482 0.01163923 0.3240827 0.08473509 0.01135402 0.328293 0.08632516 0.01103931 0.332514 0.08790409 0.01069784 0.336744 0.090025 0.01020407 0.3425045 0.09511137 0.00890398 0.3569385 0.09686452 0.008431136 0.3623774 0.09823149 0.008075237 0.366698 0.09955066 0.007742226 0.3710349 0.1008176 0.007438361 0.3753882 0.1020269 0.007169842 0.3797584 0.1031751 0.006942927 0.3841472 0.1042577 0.006763815 0.3885547 0.1052692 0.006638765 0.3929814 0.106207 0.006574034 0.3974285 0.1070649 0.006575822 0.4018971 0.1078398 0.006650328 0.4063876 0.1102823 0.008295834 0.4291673 0.1085257 0.006803929 0.4108996 0.1091197 0.007042765 0.4154357 0.1096166 0.007372915 0.4199953 0.1100087 0.007794737 0.4245754 0.1040212 0.01173591 0.4586412 0.1046659 0.01257336 0.4621883 -0.04002565 0.01395583 0.05460119 -0.03018999 0.01391273 0.07437604 -0.02238905 0.01384931 0.09029781 -0.01455688 0.01375359 0.1065415 -0.006400406 0.0136156 0.1237759 0.008441567 0.01329243 0.1560342 0.01555413 0.01314043 0.1718314 0.02272498 0.01301145 0.1879714 0.02798545 0.01294505 0.1999334 0.03156292 0.01291662 0.2081019 0.03515279 0.01290476 0.2163419 0.03927111 0.01291346 0.2258664 0.04435157 0.01296126 0.2376364 0.0517283 0.01303744 0.2548694 0.05624669 0.01304537 0.2655906 0.05965077 0.01301687 0.2737193 0.06305813 0.01294463 0.2819247 0.06644046 0.01281768 0.2901496 0.0689187 0.01268023 0.2962354 0.07059425 0.01256525 0.300384 0.07226264 0.01243036 0.3045384 0.07392299 0.01227402 0.3087014 0.07557451 0.01209491 0.3128711 0.07721751 0.01189172 0.3170485 0.07885122 0.01166301 0.321234 0.08047646 0.01140755 0.3254293 0.08209276 0.01112365 0.3296315 0.08369886 0.01081043 0.3338444 0.08529299 0.01047033 0.3380667 0.08730655 0.01001644 0.3433892 0.09236687 0.008733928 0.3576376 0.09436851 0.00821352 0.3636417 0.09575867 0.007859647 0.3679506 0.09710371 0.00752896 0.3722745 0.09839743 0.00722742 0.3766142 0.09963709 0.006961524 0.380969 0.1008174 0.006737351 0.3853415 0.1019347 0.006561219 0.3897314 0.1029837 0.006439566 0.3941391 0.1039617 0.006378233 0.3985659 0.1048633 0.006383836 0.4030123 0.1033231 0.00714147 0.4279663 0.1056845 0.006462454 0.4074794 0.108416 0.008133113 0.4301127 0.1064204 0.006620347 0.4119661 0.1060043 0.00845021 0.4360024 0.1070679 0.006863832 0.4164751 0.107622 0.007199048 0.4210057 0.1045796 0.01029396 0.450115 0.1071736 0.007544159 0.4260171 -0.1260565 0.01028698 -0.04460036 -0.1291113 0.009839475 -0.04305291 -0.09364229 0.01283067 -0.0270437 -0.07898253 0.01355785 -0.01382511 -0.09410035 0.01173168 -0.005532324 -0.09141814 0.01213276 -0.007844507 -0.07939308 0.01257008 0.007882893 -0.04037827 0.01331388 0.06938922 -0.02931529 0.01358711 0.08398616 -0.01949024 0.01348453 0.1042137 -0.009556651 0.01332151 0.1251422 0.005552709 0.01299655 0.157898 0.0125463 0.01284837 0.1734079 0.01771867 0.01275515 0.1850028 0.02235126 0.01268595 0.1954506 0.0267902 0.01264131 0.2055262 0.03039067 0.01262223 0.2137307 0.03390526 0.01262032 0.2217917 0.03855353 0.01264935 0.232402 0.04885727 0.01276004 0.2563495 0.05339419 0.01277053 0.2670307 0.05682533 0.01274472 0.275147 0.06025594 0.01267457 0.2833446 0.06366372 0.01254898 0.2915791 0.06616216 0.01241463 0.2976318 0.06785112 0.01230096 0.3017736 0.06953287 0.01216733 0.3059212 0.07120752 0.01201236 0.310077 0.07287329 0.01183474 0.3142395 0.0745306 0.01163291 0.3184096 0.07618033 0.01140576 0.322587 0.07782077 0.01115161 0.3267746 0.07945221 0.01086926 0.330969 0.08107441 0.01055753 0.3351738 0.08268457 0.01021891 0.339388 0.0847063 0.009771525 0.3446543 0.08982652 0.008495032 0.3588678 0.0918734 0.007973134 0.3649057 0.09328758 0.007621645 0.3692023 0.09465855 0.007293343 0.3735131 0.09597992 0.006994426 0.3778388 0.09724903 0.00673145 0.3821787 0.09846144 0.006510317 0.386535 0.09961265 0.006337523 0.3909077 0.1006991 0.006219446 0.3952963 0.1017172 0.006162047 0.3997029 0.1026616 0.006171762 0.4041276 0.1035301 0.006254851 0.4085707 0.1056878 0.007867395 0.4315007 0.104316 0.006417632 0.4130321 0.1040609 0.006570339 0.418002 0.1046947 0.006913423 0.422492 0.1022579 0.01229965 0.4633923 0.1014081 0.01142352 0.4599617 0.09704941 0.01484322 0.4816299 0.09842318 0.01257234 0.4689891 0.09344595 0.01486277 0.4874085 0.09445405 0.01340448 0.4775096 0.09437835 0.01399391 0.4804515 -0.1110445 0.01232075 -0.05220478 -0.08211106 0.01323515 -0.01237165 -0.06487381 0.01332241 0.02096378 -0.03241944 0.01326429 0.08549988 -0.02359414 0.01317453 0.1036401 -0.01390993 0.01302498 0.1239543 0.002419173 0.0126791 0.1592491 0.009542047 0.01253074 0.1749892 0.01672196 0.01240628 0.1910442 0.02294713 0.01233422 0.2050942 0.02833241 0.01230782 0.217319 0.0339744 0.01232486 0.230187 0.04352456 0.01243686 0.2520225 0.04710799 0.01246398 0.2604423 0.05054038 0.01247215 0.2684565 0.05400788 0.01244765 0.2766137 0.05746132 0.0123803 0.2847882 0.06088352 0.01225978 0.292942 0.06340652 0.01212573 0.2990276 0.06510972 0.01201355 0.3031622 0.06680488 0.01188135 0.3073031 0.06849384 0.01172786 0.3114516 0.07017385 0.01155173 0.3156068 0.07184636 0.01135152 0.3197693 0.0735104 0.01112586 0.3239395 0.07516682 0.01087331 0.328119 0.07681345 0.01059263 0.3323057 0.07845079 0.01028251 0.3365028 0.08007788 0.009945631 0.3407084 0.08211827 0.009501099 0.3459594 0.08727955 0.008236765 0.3600762 0.08938091 0.007711827 0.3661683 0.09081923 0.007362723 0.3704527 0.09221428 0.007037162 0.3747512 0.09356415 0.006741166 0.3790625 0.0948618 0.00648123 0.3833879 0.09610635 0.006263554 0.387728 0.09729236 0.006094336 0.3920831 0.09841626 0.005980014 0.3964527 0.09844684 0.005815148 0.4013665 0.1004627 0.005941212 0.4052415 0.1003708 0.005919814 0.4101747 0.1012317 0.006090581 0.4145979 0.1029711 0.009394347 0.4465821 0.1011115 0.00849837 0.4430559 0.1043811 0.01101446 0.4544153 0.09987235 0.01199895 0.4645957 0.09600305 0.01223677 0.4702266 -0.1138146 0.01197111 -0.05080157 -0.1001212 0.01129758 -0.009677648 -0.07957792 0.01292121 1.02085e-5 -0.06617772 0.01297903 0.02601516 -0.0543456 0.01299309 0.04925954 -0.034083 0.01290386 0.08996373 -0.02770161 0.01284092 0.1030493 -0.01946902 0.01272314 0.12024 -0.001914083 0.01236397 0.1579611 0.006492078 0.01219081 0.1764601 0.01371204 0.01206809 0.1925516 0.0189644 0.0120086 0.2043555 0.02257943 0.01198381 0.2125099 0.02624809 0.01197564 0.2207952 0.03104579 0.01199418 0.2316945 0.04177081 0.0121259 0.2560658 0.04595559 0.01214987 0.2658555 0.04944944 0.01214522 0.2739884 0.05291837 0.01210397 0.282095 0.05639237 0.01201403 0.290272 0.05983877 0.01186281 0.2984862 0.06237018 0.01170492 0.3045499 0.06407964 0.01157432 0.3086836 0.06578195 0.01142251 0.3128253 0.06747716 0.01124793 0.3169729 0.06916385 0.01104944 0.3211281 0.0708431 0.01082545 0.3252906 0.07251381 0.01057463 0.3294629 0.07417649 0.01029562 0.3336415 0.07582992 0.009987354 0.3378305 0.07747215 0.009652256 0.3420284 0.07957881 0.00918287 0.3475445 0.08499878 0.007903575 0.3619436 0.08576667 0.007297396 0.3680319 0.08721798 0.006951808 0.3722921 0.08867657 0.006632983 0.3765646 0.09005123 0.006340801 0.380854 0.09247732 0.006212651 0.3845959 0.09268826 0.005874097 0.3894705 0.09390264 0.005708634 0.3938043 0.09511333 0.005604147 0.3981364 0.09999412 0.006113529 0.420063 0.1007367 0.006468594 0.4244964 0.09726864 0.005578041 0.4068647 0.101548 0.01067638 0.4558502 0.09349715 0.01468735 0.4855976 -0.09520441 0.01247322 -0.0225743 -0.09243744 0.01092565 0.01268827 -0.05748015 0.01262462 0.05071139 -0.03741186 0.01254034 0.09098792 -0.02935665 0.01245307 0.1075721 -0.02246713 0.01235461 0.1219457 -0.005129277 0.01200348 0.1591246 0.003404498 0.01182955 0.1778635 0.01072418 0.01170885 0.1940999 0.01597905 0.01165133 0.2058677 0.01960748 0.01162821 0.2140154 0.02322542 0.0116223 0.2221634 0.0281139 0.01164287 0.2331905 0.03892922 0.01178175 0.2576215 0.04313319 0.01180696 0.2674098 0.04662358 0.01180583 0.2754454 0.05010944 0.01176726 0.283528 0.05360776 0.01167875 0.2917199 0.05708342 0.01153159 0.2999051 0.05842447 0.01123106 0.306522 0.06014853 0.01110202 0.3106523 0.06307178 0.01109826 0.3141981 0.0647813 0.01092541 0.3183385 0.0652768 0.01058083 0.323095 0.06700253 0.01036536 0.3272027 0.068677 0.0101127 0.3313981 0.0715413 0.00998032 0.3349764 0.07203507 0.009531021 0.3397392 0.07486909 0.009340763 0.343347 0.0769639 0.008880972 0.3487686 0.08249354 0.007602155 0.3632296 0.08904534 0.005797922 0.3863458 0.09707814 0.005594849 0.4167036 0.09400373 0.005284905 0.403618 0.09453368 0.006477713 0.4371463 0.09176653 0.005638241 0.4338164 0.09610927 0.005411088 0.4123334 0.09977316 0.008992493 0.4482012 0.1015424 0.009931325 0.4516515 0.0987448 0.01107335 0.4613038 0.09747457 0.01167327 0.4658082 0.09512507 0.01458281 0.4826018 -0.1169346 0.01156115 -0.04922109 -0.0764274 0.01220971 0.02115464 -0.04417306 0.01217848 0.08507519 -0.03667044 0.0121172 0.1003624 -0.02656424 0.01198679 0.1213169 -0.0273 0.01154226 0.1277872 -0.01063758 0.01167219 0.1553406 -0.003206372 0.01151919 0.1714953 0.004085063 0.01138544 0.1875518 0.01131999 0.01128834 0.2036338 0.01663732 0.01125425 0.2155199 0.02026998 0.01125019 0.2236605 0.02389574 0.01126581 0.2317994 0.02790075 0.01130682 0.240751 0.0373367 0.01143109 0.26207 0.04199427 0.01145339 0.2727459 0.04553335 0.01143705 0.2808764 0.04906129 0.01137864 0.2890149 0.05164641 0.01130104 0.294998 0.05217605 0.01107269 0.2997046 0.05393427 0.01098561 0.3037972 0.05916982 0.01060503 0.31616 0.06090086 0.01043492 0.320291 0.06775957 0.009503304 0.3368725 0.07113492 0.008870244 0.3452157 0.07436418 0.008556008 0.3500632 0.0799756 0.007288277 0.3644797 0.08081859 0.00667721 0.3705279 0.08234471 0.006339371 0.3747633 0.08384537 0.006026625 0.379009 0.08527213 0.005740642 0.3832734 0.08801394 0.005287289 0.3918356 0.08931463 0.005132198 0.3961285 0.09061801 0.00503993 0.4004138 0.09593302 0.005603551 0.4221197 0.09292125 0.005032122 0.4090668 0.09652 0.008551478 0.449849 0.09845441 0.009526193 0.4532131 0.09867376 0.01029902 0.4573019 0.09130573 0.0129255 0.479123 -0.1201131 0.0111283 -0.04761099 -0.1086536 0.009982824 -0.003697633 -0.07719057 0.01181459 0.02722054 -0.06241279 0.01183217 0.05625784 -0.04478508 0.01175647 0.09163498 -0.03583025 0.01167076 0.1099641 -0.01356357 0.01126956 0.1571442 -0.006210267 0.0111224 0.1730605 0.00103724 0.01099056 0.1889987 0.008315026 0.01089626 0.2051078 0.01366853 0.01086449 0.2170238 0.01731592 0.01086235 0.2251569 0.02224272 0.01088786 0.2361668 0.03314173 0.01104497 0.2603893 0.03725957 0.01107263 0.2698765 0.04094916 0.01107633 0.2783111 0.04449778 0.01104635 0.2863548 0.0470975 0.01099133 0.2923117 0.0476334 0.01077175 0.2970252 0.05294549 0.0105133 0.3093009 0.05468654 0.01038539 0.3134351 0.05989927 0.009875953 0.3258213 0.06166625 0.009665012 0.3299223 0.06339943 0.009422183 0.3340632 0.06678861 0.008843243 0.342401 0.07177716 0.008213639 0.3513953 0.0774511 0.006962358 0.3657126 0.08427816 0.005173742 0.3887572 0.08953821 0.004700064 0.4058785 0.09181594 0.00484848 0.4145075 0.09289711 0.005047023 0.4188203 0.09528011 0.007114052 0.4414308 0.09765064 0.00804454 0.4448056 0.0939961 0.011173 0.4675736 0.0949285 0.01053726 0.4632408 -0.1230276 0.01072102 -0.04613465 -0.06557703 0.01141363 0.05765593 -0.05266237 0.0109266 0.09119486 -0.06172138 0.01051819 0.08071076 -0.04579371 0.01132619 0.09736144 -0.03513133 0.01120406 0.119337 -0.02476221 0.0110228 0.1411963 -0.01332741 0.01079273 0.1657304 -0.005599021 0.01064324 0.1825488 0.001735329 0.01053059 0.1986689 0.005727529 0.01029157 0.2111899 0.009420514 0.01027625 0.2193244 0.01301807 0.01027148 0.2273969 0.01802009 0.01048105 0.2347758 0.02209901 0.01052761 0.2437935 0.0316416 0.01066255 0.2651346 0.03621733 0.01069349 0.2753872 0.03989428 0.01068389 0.2837291 0.0425201 0.0106514 0.289642 0.04301702 0.01043421 0.2943834 0.04660433 0.01031631 0.302538 0.04840117 0.01023441 0.3066132 0.0536791 0.009858489 0.3189635 0.05547988 0.009699702 0.3230382 0.06244611 0.008781254 0.3395801 0.06590545 0.00816071 0.3478705 0.06917905 0.007865309 0.3526695 0.0739448 0.006518125 0.3672026 0.07582634 0.006001234 0.373048 0.07741743 0.00567162 0.3772572 0.07892477 0.005360722 0.3814894 0.08043777 0.005085349 0.3857216 0.08142226 0.003759086 0.4050628 0.08506017 0.004075229 0.4081446 0.08848506 0.004430592 0.4113121 0.08326762 0.004643976 0.3942335 0.08465993 0.004501044 0.3984858 0.08599549 0.004413545 0.4027497 0.0888291 0.00486344 0.4305272 0.09172105 0.006604552 0.4432337 0.09421205 0.007564246 0.4465465 0.09328562 0.008088529 0.4514856 0.095384 0.009097158 0.4547657 0.09583717 0.009903609 0.458741 0.09260833 0.01420676 0.4838792 0.09184956 0.01360577 0.4817295 0.09191203 0.01444047 0.4864 0.09182786 0.01460969 0.4882283 -0.1055056 0.01084965 -0.01254409 -0.113666 0.009064972 0.001582205 -0.1034154 0.009574055 0.01389032 -0.09569466 0.009151875 0.03645336 -0.06475913 0.01097929 0.06692224 -0.04357546 0.01084142 0.1097735 -0.03572446 0.0107389 0.1260496 -0.01762574 0.01038753 0.1646013 -0.008655607 0.01022106 0.1840105 -0.00130403 0.01011174 0.2001014 0.01373809 0.009881973 0.2368847 0.01875406 0.01011312 0.244374 0.02425181 0.01019608 0.2565371 0.02860403 0.01008683 0.2697987 0.03218847 0.01011508 0.2777255 0.03469318 0.01009505 0.2836346 0.036659 0.01010936 0.2875794 0.0384522 0.01008093 0.2916969 0.0420593 0.009993851 0.2998464 0.04744553 0.009744763 0.3120986 0.04922789 0.009622931 0.3162051 0.05458307 0.009134531 0.3285055 0.05633056 0.008919656 0.3326309 0.05805218 0.008674144 0.3367882 0.06153088 0.008108139 0.3450734 0.06656932 0.007508456 0.3539228 0.07169145 0.005993127 0.3701217 0.07946813 0.004502773 0.3911881 0.08749693 0.004245579 0.4166924 0.09079837 0.005942821 0.4390375 -0.1085721 0.01041024 -0.01099073 -0.09550875 0.01048558 0.01424407 -0.07217705 0.01054108 0.0598948 -0.0520305 0.01045417 0.1003054 -0.04420733 0.01037311 0.116345 -0.03647387 0.01026129 0.1324343 -0.02075499 0.009954988 0.1659266 -0.01377421 0.009827673 0.1809597 -0.007945835 0.009731054 0.1936402 -0.002623319 0.009666323 0.2053007 -1.53715e-4 0.009443044 0.2142949 0.003539979 0.009431064 0.2223724 0.007174432 0.009432792 0.2304018 0.01428335 0.009504497 0.2459116 0.0213617 0.009782016 0.2580012 0.03748166 0.009643256 0.2971636 0.0411148 0.009530544 0.3053197 0.04290288 0.009446799 0.3094073 0.04831838 0.009092688 0.3216583 0.05007129 0.008924305 0.3257904 0.05718183 0.008027374 0.3422485 0.06066977 0.007409691 0.3505364 0.06397509 0.007134735 0.3552513 0.06742405 0.005972802 0.3672444 0.07091557 0.005298078 0.3755398 0.07250398 0.004969239 0.3797405 0.0740652 0.004665374 0.3839502 0.07562756 0.004397392 0.3881548 0.08005177 0.003841459 0.4008206 0.08408701 0.003801047 0.4135373 0.07859337 0.003974795 0.3966019 0.08036196 0.003220677 0.4251686 0.08794271 0.00507909 0.4357542 0.08711123 0.005393207 0.4409054 0.08815217 0.0060727 0.4450414 0.0908209 0.007068216 0.448265 0.09001982 0.007601618 0.4531375 0.09295588 0.009481728 0.4601977 0.09199625 0.01161646 0.4721497 -0.132105 0.009394407 -0.04153639 -0.08948194 0.01007634 0.03346705 -0.05974811 0.01004356 0.09239858 -0.04970628 0.009953439 0.1128791 -0.04184257 0.009851336 0.1291699 -0.02381241 0.009507954 0.1674633 -0.0183019 0.009160637 0.1832532 -0.01094102 0.009291291 0.1951793 -0.006882965 0.009030997 0.2076154 0.007861673 0.009023547 0.2398396 0.0184729 0.009359061 0.2594645 0.02288216 0.009256362 0.2725677 0.02654325 0.009286105 0.2806473 0.0290544 0.009270071 0.2864909 0.03089624 0.009261727 0.290544 0.03273403 0.009242117 0.2945992 0.03648608 0.009177803 0.3026803 0.04199659 0.008947312 0.3148639 0.04381507 0.008831977 0.3189379 0.04917985 0.008343756 0.3312479 0.05094486 0.008130669 0.3353714 0.05278158 0.007903933 0.3394504 0.05636358 0.007353544 0.3476808 0.06060004 0.006587982 0.3573849 0.06668561 0.00526148 0.3726511 0.07476353 0.003814399 0.3935734 0.080603 0.003423511 0.4104012 0.09097796 0.008449077 0.4569978 -0.1363691 0.008746266 -0.03937637 -0.1290162 0.008060038 -0.01312494 -0.08564525 0.009634554 0.04853522 -0.07405805 0.009627282 0.07146918 -0.06161671 0.009439408 0.09859859 -0.05179977 0.009308099 0.1192592 -0.04258459 0.009358286 0.1355297 -0.03029823 0.009132444 0.1615092 -0.0175693 0.008647024 0.1928818 -0.01382839 0.008596122 0.2009832 -0.006125628 0.008555054 0.2172858 -0.002421379 0.008546769 0.2253201 0.001360177 0.008640348 0.2319923 0.01000374 0.00883311 0.2488065 0.01617884 0.008774876 0.2655273 0.03069025 0.008628487 0.3006091 0.03555351 0.008701264 0.3081409 0.03741949 0.008629858 0.3121796 0.04295122 0.008293867 0.3243675 0.04473114 0.008128404 0.3284959 0.05195003 0.007248282 0.3448938 0.05547791 0.006636619 0.3531594 0.05698734 0.006146848 0.3583713 0.06237578 0.005220234 0.3698017 0.06584101 0.004543662 0.3780949 0.06753247 0.004228889 0.3822551 0.07390904 0.003276765 0.3989744 0.06919896 0.003939986 0.3864178 0.07544308 0.003154635 0.4031552 0.07076704 0.003673374 0.3906125 0.07688164 0.003082275 0.4073624 0.08183127 0.003576934 0.4292587 0.08310925 0.004006981 0.4334248 0.08238399 0.004233419 0.4385687 0.08179265 0.004573464 0.4436004 0.08302527 0.005282282 0.447638 -0.1699033 0.003351926 -0.02238941 -0.1402269 0.006118655 -0.00494796 -0.1249041 0.007623791 0.002278625 -0.08365786 0.009168624 0.06008762 -0.07712924 0.00916171 0.07302492 -0.05779135 0.009052276 0.111974 -0.04736578 0.008694529 0.1370049 -0.03008145 0.008718311 0.1682817 -0.02433615 0.008246481 0.1863099 -0.01308065 0.008100807 0.2105979 -0.001860082 0.008080899 0.2348707 0.001080572 0.008120596 0.2409091 0.005631446 0.008167266 0.2510214 0.01720917 0.008390963 0.2755621 0.02084392 0.008423924 0.2835134 0.02459311 0.008440554 0.2914898 0.02714651 0.008395671 0.2974296 0.02978104 0.008160531 0.3060696 0.03657907 0.008127629 0.3175996 0.03845781 0.008021771 0.3216382 0.04392135 0.007547855 0.3339053 0.04572921 0.007341563 0.3380043 0.04747623 0.00709939 0.3421468 0.05117428 0.006567656 0.3503103 0.06036603 0.004468858 0.3744612 0.07003146 0.003097891 0.3959694 0.08531904 0.006876707 0.4555176 0.08594053 0.006326019 0.4507362 0.08886069 0.008858919 0.4622721 0.08967334 0.009742021 0.4658989 0.08700364 0.01221781 0.4812134 0.08801227 0.01299113 0.4836775 -0.1428983 0.007730901 -0.03606903 -0.1208277 0.008569359 -0.004782497 -0.107784 0.008641719 0.02046221 -0.0945608 0.008687794 0.04624438 -0.08672922 0.008696556 0.06164348 -0.08020001 0.008689701 0.07458043 -0.06737172 0.008358359 0.1046317 -0.05759531 0.00831902 0.1237338 -0.03305929 0.008248746 0.1699892 -0.04238361 0.00778836 0.1598148 -0.03283208 0.007743954 0.1781114 -0.02358412 0.007722854 0.1959286 -0.01982289 0.007675051 0.2040198 -0.01203846 0.007734596 0.2188118 -0.009499251 0.00761187 0.2262635 -0.001047968 0.007660031 0.2444349 0.00554043 0.007768154 0.2585422 0.01169073 0.008082449 0.2678819 0.02888441 0.007675409 0.3115121 0.03079038 0.007610499 0.3155289 0.03754079 0.007461667 0.3271227 0.03933769 0.007300496 0.3312208 0.04435747 0.006077349 0.3487434 0.04916828 0.005663752 0.356371 0.05256444 0.005427837 0.3609267 0.06435883 0.003196775 0.3888676 0.0609135 0.003786683 0.3805902 0.06384718 0.002606511 0.3941186 0.06046593 0.003139615 0.3858323 0.06715142 0.002235054 0.4023958 0.06877362 0.002126634 0.4065316 0.07425051 0.002267479 0.4282625 0.07362079 0.002287924 0.4334172 0.07516431 0.002759754 0.4374485 0.08836758 0.01106572 0.4740754 0.08922183 0.01043993 0.4699882 -0.1172346 0.008132398 0.009635269 -0.09763073 0.008210182 0.04779946 -0.08832496 0.007935881 0.07060265 -0.08327007 0.008212089 0.07613563 -0.05174374 0.0079512 0.1401693 -0.03036743 0.007308483 0.1893651 -0.01877671 0.007292926 0.2122343 -0.01057916 0.007151365 0.2318023 -0.007751822 0.007164478 0.2378552 -0.001829028 0.007336497 0.2485699 0.008772194 0.007386505 0.2740083 0.01330143 0.007516741 0.2824978 0.01701045 0.007552623 0.2903282 0.01734709 0.007175445 0.2973953 0.01923459 0.007162094 0.3014458 0.02113598 0.007140278 0.3054679 0.02871495 0.006898999 0.3216106 0.03173953 0.006974577 0.3250557 0.03623116 0.006348431 0.3378037 0.0380218 0.006138086 0.3419222 0.0398972 0.005917847 0.3459799 0.04357564 0.005381405 0.3541694 0.05657589 0.003709316 0.3777651 0.06532585 0.002366185 0.398356 0.0651046 0.001009106 0.4182493 0.07909971 0.005242228 0.4541996 0.08490145 0.007505655 0.4600771 0.08925664 0.01400709 0.4877465 -0.1488019 0.006794691 -0.03307849 -0.161656 0.004712283 -0.02656716 -0.1006999 0.007727682 0.04935419 -0.06845653 0.007636427 0.1136263 -0.05878537 0.007358968 0.1360406 -0.04694312 0.007069408 0.1621245 -0.03842681 0.006942927 0.1797433 -0.02959603 0.006778001 0.1989741 -0.02581542 0.006733298 0.2070553 -0.02109396 0.006695032 0.217155 -0.01974672 0.006445705 0.2239649 -0.008801639 0.006716609 0.2433753 -0.003037035 0.006871223 0.2542833 0.0225625 0.00702697 0.3097307 0.03087157 0.006410777 0.3305167 0.03280037 0.006271719 0.334533 0.04743534 0.004640221 0.3633766 0.05138546 0.00382483 0.372854 0.05736142 0.002094268 0.392414 0.05488485 0.002837836 0.3836458 0.06905078 0.001486301 0.4211543 0.06843072 0.001315832 0.4263512 0.08302599 0.007934212 0.4652259 0.0843414 0.008897483 0.4686009 0.08428847 0.00965178 0.4724866 0.08932614 0.0136798 0.48554 -0.1300121 0.007126033 -1.30137e-4 -0.1039077 0.007067263 0.05337733 -0.09596395 0.007003188 0.07006996 -0.08540636 0.007232189 0.0872153 -0.07151877 0.00715065 0.1151775 -0.06367754 0.007068216 0.131209 -0.03909087 0.006191492 0.1897227 -0.01838839 0.006208479 0.2307664 -0.01701772 0.00598067 0.2375594 -0.007027864 0.006114959 0.2585589 0.002597928 0.006411671 0.2770111 0.007371485 0.006600618 0.2850165 0.01140195 0.006662368 0.2931817 0.02170139 0.006536662 0.3151586 0.02360439 0.006470382 0.3191897 0.04022836 0.00424546 0.3608965 0.04936319 0.00256288 0.3814228 0.05835026 0.001257777 0.4018863 0.07457345 0.00299555 0.4425239 0.0742641 0.003371059 0.4474148 0.07574272 0.0041188 0.4513261 0.07877463 0.00583136 0.4588323 0.08404946 0.0103752 0.4762889 -0.1551563 0.005771219 -0.0298596 -0.1325604 0.006639897 0.002409696 -0.09247672 0.006751954 0.08079934 -0.07655364 0.006677091 0.1127278 -0.06868875 0.006602466 0.1287463 -0.06615591 0.006088614 0.141122 -0.0489974 0.00603801 0.1734965 -0.03944081 0.005439281 0.2003399 -0.03275668 0.005785048 0.2080725 -0.02989768 0.005565702 0.2171629 -0.01563096 0.005766451 0.2443406 -0.01276385 0.005802869 0.2503697 0.01451086 0.0057379 0.3138074 0.02215552 0.005439579 0.3299292 0.03491133 0.004570364 0.3535266 0.04215645 0.003772199 0.3662441 0.04492962 0.002473533 0.3786461 0.05050009 0.001547336 0.3908838 0.05408298 0.001046776 0.3990641 0.06039041 8.45323e-5 0.4255411 0.06580859 9.09385e-4 0.432539 0.0787236 0.00651139 0.4632028 -0.1547499 0.003864109 5.35111e-4 -0.1091606 0.006012141 0.05926197 -0.1036103 0.006015896 0.07019472 -0.09908378 0.006013274 0.07914745 -0.09357362 0.006001234 0.09010255 -0.07523459 0.00588417 0.1270608 -0.0674144 0.005790174 0.143105 -0.04608112 0.005168855 0.1916992 -0.03221887 0.004748404 0.2252755 -0.02526581 0.005252659 0.2317541 -0.02292037 0.005027413 0.2405495 -0.01301157 0.005129456 0.2619356 -0.006322383 0.005155861 0.2781178 0.001685857 0.005685329 0.2878966 0.002048909 0.00531423 0.2951843 0.004038691 0.005338847 0.2991628 0.005938351 0.005338847 0.3031941 0.007924318 0.005343317 0.3071644 0.009885847 0.005330681 0.3111637 0.01377069 0.005258083 0.3191781 0.01572775 0.005200266 0.3231856 0.01767057 0.005122721 0.3272014 0.02152907 0.004906892 0.3352367 0.02337169 0.004751205 0.3393274 0.02532923 0.004594624 0.3433281 0.02719378 0.004396319 0.3474031 0.02919679 0.004196166 0.3514021 0.03292798 0.003668546 0.3595609 0.0462296 0.001443743 0.38803 0.06030905 -6.18493e-6 0.4304656 0.06562715 9.93852e-4 0.4374665 0.06739139 0.001501619 0.441385 0.0673722 0.001823127 0.4461734 -0.1402158 0.005641698 0.002540588 -0.1236363 0.005483686 0.03848576 -0.06657981 0.005237162 0.1526871 -0.05510205 0.005046367 0.1766278 -0.04368776 0.00445342 0.2068947 -0.03813385 0.004562735 0.2161529 -0.02556538 0.004419863 0.2448297 -0.01862031 0.004854023 0.2533363 -0.004076421 0.005169034 0.2833425 0.03456443 0.00270456 0.3687759 0.03643155 0.002332687 0.3731698 0.05086117 -7.68071e-4 0.4156029 0.05661988 -3.7229e-4 0.4225473 0.06678384 0.002146065 0.4512036 0.06931918 0.003067672 0.4545814 0.07256889 0.00417906 0.4575077 0.07221603 0.004757344 0.4621548 0.07775628 0.007076084 0.4678943 0.07936972 0.008087277 0.4711152 0.08437865 0.01285815 0.4880453 -0.1208403 0.004620492 0.05732786 -0.1152954 0.005012452 0.06236964 -0.1056837 0.005054295 0.08075875 -0.0815463 0.004573702 0.1344051 -0.07742571 0.004845023 0.1381733 -0.07351773 0.00479561 0.1461968 -0.03119498 0.004286527 0.2347576 -0.003997981 0.004759132 0.2907758 0.02431744 0.002837717 0.3589225 0.03036016 0.002640485 0.3658841 0.03980964 0.001008212 0.3862558 0.05460339 -9.36567e-4 0.4382131 0.07775288 0.008578419 0.4757938 -0.1662089 0.001841068 0.008213281 -0.1289962 0.004728794 0.03932708 -0.0672096 0.004219949 0.1661376 -0.05708742 0.004054903 0.1872723 -0.05876326 0.003196418 0.1965358 -0.03187268 0.003118157 0.2524775 -0.0297544 0.003162205 0.2565885 -0.02589464 0.003234386 0.2645299 -0.01666432 0.00406599 0.2722817 -0.01406723 0.003528118 0.2884188 0.004622936 0.004114151 0.3188934 0.01250135 0.003857851 0.3348384 0.03716528 0.001204133 0.3825723 0.04146289 6.87007e-5 0.3954584 0.05211174 -8.74181e-4 0.4199113 0.05554896 -4.56027e-4 0.4473822 0.07052576 0.005161166 0.4673568 0.0807954 0.01179069 0.4873325 -0.13372 0.003970623 0.04140764 -0.1136161 0.004005312 0.08088606 -0.105839 0.003992617 0.09631568 -0.1013434 0.003976702 0.1052861 -0.08017462 0.003521442 0.1521359 -0.07823687 0.003491759 0.1561601 -0.05031543 0.003098666 0.2141763 -0.04627138 0.003071308 0.2226017 -0.04229503 0.003059327 0.2308744 -0.03959345 0.003062188 0.2364759 -0.0376504 0.00306946 0.2404963 -0.03376239 0.003099024 0.2485186 -0.01803773 0.003427803 0.280452 -0.01605772 0.003478109 0.2844322 -0.01209115 0.003570318 0.2923895 -0.01010763 0.003609418 0.2963607 -0.005296409 0.004107832 0.2989078 -0.003319442 0.004130542 0.3028902 -0.001341521 0.004143834 0.3068744 6.3543e-4 0.004146337 0.310859 0.002613306 0.004136681 0.3148455 0.007776796 0.004046618 0.3252628 0.01051652 0.003948748 0.3308169 0.01445907 0.003745615 0.3388233 0.01642721 0.003611922 0.3428326 0.01839232 0.003454923 0.3468469 0.02035427 0.003273308 0.3508661 0.02231317 0.003065586 0.3548924 0.02388775 0.002188622 0.3640872 0.03701531 -7.13648e-5 0.3926973 0.05719155 -3.98716e-4 0.4417398 0.06311339 0.002613186 0.4622984 -0.09366828 0.003069698 0.1332731 -0.07627123 0.003470182 0.1600973 -0.07432758 0.003440201 0.1641156 -0.07238799 0.003409504 0.1681349 -0.0704506 0.003378272 0.1721565 -0.06851589 0.00334686 0.1761794 -0.06658345 0.003315567 0.1802023 -0.06465321 0.003284752 0.1842275 -0.06272429 0.003254652 0.1882522 -0.06079626 0.003225564 0.1922774 -0.05694293 0.003171801 0.2003268 -0.05415779 0.00313723 0.2061485 -0.03569233 0.003082156 0.2445238 -0.02788776 0.003188014 0.2605239 -0.02395921 0.003275454 0.2685028 -0.02198982 0.003324627 0.2724879 -0.02001595 0.003375589 0.2764708 -0.01037067 0.002696573 0.2986297 -0.008349835 0.00267136 0.302619 -0.006329417 0.002645194 0.3066076 -0.004309058 0.002618014 0.310596 -0.002288639 0.002589941 0.3145845 -2.68281e-4 0.002560853 0.3185729 0.002739608 0.002516984 0.3245118 0.005792856 0.00246787 0.3305383 0.02195513 0.002180099 0.3624453 0.02016794 3.22349e-4 0.3760942 0.02202659 -4.88623e-5 0.380474 0.0260846 -5.54051e-4 0.3875958 0.03465509 -0.002155482 0.4089038 0.04751187 -0.0020442 0.4320624 0.04839044 -0.001980125 0.4365016 0.05675607 6.50935e-5 0.4515523 0.07207417 0.006878912 0.4748099 0.07674896 0.009161889 0.4799594 0.08116835 0.01127386 0.4842758 -0.1432793 0.002942264 0.03781807 -0.1336338 0.002975404 0.05666726 -0.1247875 0.002989351 0.07405006 -0.1159796 0.002986311 0.09145534 -0.1094707 0.002969145 0.104404 -0.08514207 0.002953052 0.1510236 -0.07503634 0.002994358 0.170973 -0.07301503 0.002999961 0.1749632 -0.07099419 0.00300467 0.1789526 -0.06897288 0.003008365 0.1829428 -0.06695204 0.003011107 0.1869322 -0.06493121 0.003012895 0.1909216 -0.0629099 0.00301367 0.1949118 -0.05999082 0.003013432 0.2006744 -0.05606424 0.003009676 0.2084258 -0.05238199 0.003002822 0.215695 -0.04335778 0.002973854 0.2335097 -0.04068017 0.002959072 0.2387956 -0.03865933 0.002948284 0.2427849 -0.03663891 0.002936601 0.2467734 -0.03461807 0.002923905 0.2507628 -0.03259724 0.002910256 0.2547522 -0.0305764 0.002895653 0.2587415 -0.02855598 0.002880096 0.26273 -0.02653515 0.002863526 0.2667194 -0.02451431 0.002846062 0.2707087 -0.02249389 0.002827584 0.2746972 -0.02047306 0.002808153 0.2786865 -0.0184527 0.002787768 0.282675 -0.01643228 0.00276643 0.2866634 -0.01441144 0.002744078 0.2906528 -0.01239103 0.002720832 0.2946413 0.007813274 0.002434968 0.3345268 0.009833633 0.002401053 0.3385153 0.01185405 0.002366244 0.3425037 0.01387447 0.002330422 0.3464922 0.01589483 0.002293646 0.3504807 0.01791524 0.002255916 0.3544691 0.01993519 0.002217173 0.3584567 0.01669925 3.76736e-4 0.3728181 0.02662026 -0.00117594 0.3929358 0.03783732 -0.002929508 0.4222027 0.04431992 -0.002409517 0.4287788 0.06020379 0.001555502 0.4591968 0.07022917 0.005829513 0.4717051 -0.1819596 0.001349031 -0.0162822 -0.08312058 0.002962172 0.1550137 -0.08109974 0.002971649 0.1590031 -0.07907849 0.002980172 0.1629934 -0.07705718 0.002987742 0.1669836 0.04103374 -0.002712965 0.4255201 0.06121176 0.002928256 0.4677305 -0.1458485 0.001938521 0.04786372 -0.1376785 0.001929879 0.06433802 -0.1285119 0.001507103 0.08884084 -0.118101 0.001958906 0.1025271 -0.09232634 0.001761078 0.1546628 0.009196817 -2.41324e-4 0.3714333 0.04602527 -0.002259075 0.4473969 -0.1148177 3.67432e-4 0.1321105 0.01912736 -0.003648877 0.4067667 0.02344983 -0.004027545 0.4145767 0.03381562 -0.002782762 0.4143171 0.05402541 2.51964e-5 0.4576675 0.08935254 0.01419597 0.4894821 -0.1613842 3.79936e-4 0.04011881 -0.1499467 9.23257e-4 0.05493658 -0.1426136 8.14609e-4 0.07121056 -0.1231276 7.37425e-4 0.1106972 -0.1038323 8.14706e-4 0.1465485 0.002674102 -0.001035392 0.3722122 0.03213089 -0.003501713 0.4201372 0.02759933 -0.004962384 0.4323269 0.0372169 -0.003841876 0.4470229 0.06058281 0.004216134 0.4765967 0.085886 0.01344138 0.4894535 -0.1947562 -7.91013e-4 -0.009799957 -0.1072868 -7.40324e-4 0.1622412 0.03587859 -0.004074335 0.4428369 0.06680673 0.006750762 0.4813416 0.0704661 0.008087038 0.483028 -0.178184 -9.44467e-4 0.02614527 -0.1581031 -1.08308e-4 0.05407136 -0.1486116 -8.4304e-5 0.07268726 -0.1459197 -0.001104533 0.0931878 -0.1381815 -4.64205e-4 0.09895271 -0.1301116 -8.98298e-5 0.1092361 -7.98876e-4 -0.002551257 0.3816784 0.003302276 -0.002498507 0.3846423 0.01639837 -0.004678428 0.4131616 0.03125375 -0.004596292 0.4353929 0.03356504 -0.004377841 0.4391247 0.04300093 -0.002556025 0.453737 0.04553717 -0.001812815 0.4572324 0.05311399 9.39149e-4 0.4673607 0.06432288 0.0055812 0.4787343 0.07593852 0.01039129 0.4868994 0.0200445 -0.005091428 0.4212779 0.02184063 -0.005231618 0.4253374 0.02456611 -0.005155146 0.4289171 0.05052065 -6.5914e-5 0.4640986 0.05394977 0.001705348 0.4713999 0.0578134 0.003037452 0.4737997 -0.19937 -0.001567721 -0.007462739 -0.1637124 -8.82617e-4 0.05441451 -0.15283 -8.54429e-4 0.07576113 -0.1337767 -0.001274287 0.1194346 -0.003539919 -0.002416729 0.3781961 0.0128979 -0.004696428 0.4098972 0.01733076 -0.005057811 0.4176608 0.02662926 -0.00538516 0.4377293 0.02904105 -0.005149662 0.4414138 0.03143709 -0.004832267 0.4450814 0.03834897 -0.003551125 0.4512814 0.04583817 -0.001353204 0.4618043 0.0608316 0.004983544 0.4805058 0.07850086 0.0113992 0.4884954 0.08215141 0.01247942 0.4891738 -0.1721972 -0.001415252 0.04533916 -0.1558915 -0.001370191 0.07731193 -0.1297655 -0.001406431 0.1290578 -0.1296598 -0.002495467 0.1446292 0.004769444 -0.004676342 0.4025634 0.006098806 -0.005266964 0.4083342 0.03193819 -0.004757344 0.4496892 0.03449642 -0.004221916 0.4532321 0.03893935 -0.003249287 0.4557919 0.04149281 -0.002503514 0.4592744 0.04682564 -6.96974e-4 0.4659663 0.04962188 3.42795e-4 0.4691269 0.06765508 0.007627189 0.4845594 0.07409417 0.01002001 0.487584 0.08041453 0.01216143 0.4900497 0.08456534 0.0132001 0.4901174 -0.2056925 -0.00265634 -0.004260063 -0.1782007 -0.001951336 0.0411427 -0.1622586 -0.001895487 0.07235902 -0.1488713 -0.001886129 0.09874486 -0.1388286 -0.001903831 0.1186507 -0.128835 -0.00194925 0.1385862 -0.0102697 -0.003228724 0.3787692 0.01283711 -0.005840659 0.4199422 0.01058787 -0.005684673 0.4160882 0.01509791 -0.005951106 0.4237766 0.017425 -0.006000339 0.4275736 0.01978248 -0.005986869 0.4313382 0.02214229 -0.005908668 0.4350805 0.04242569 -0.001947224 0.4635358 0.0389344 -0.002958059 0.4605787 0.05096435 0.00118649 0.4729183 0.05396479 0.002368152 0.4757373 0.05711901 0.003614187 0.4783443 0.06375885 0.006220161 0.482874 -0.2085258 -0.003162384 -0.002824783 -0.1654452 -0.002428889 0.07369238 -0.1519443 -0.002419292 0.1003015 -0.1404904 -0.002438127 0.1229968 -0.1266851 -0.003664731 0.1658223 -0.007000029 -0.003631114 0.3848497 0.002262532 -0.005124568 0.4038428 0.008292496 -0.005498051 0.4122267 0.02362853 -0.005919337 0.4392593 0.02607965 -0.005676567 0.4429209 0.02856725 -0.005342841 0.4465437 0.03627383 -0.003723084 0.4571477 0.04731345 -6.70087e-5 0.4703017 -0.186206 -0.003035128 0.04055553 -0.1714694 -0.002982378 0.06942355 -0.1600456 -0.002966284 0.09191036 -0.1495217 -0.002970635 0.1127077 -0.139063 -0.002990603 0.133309 -0.1320952 -0.003047823 0.1474608 -0.01026064 -0.003573119 0.3814404 -0.00203818 -0.005961894 0.4063574 4.57831e-4 -0.006314575 0.4112792 0.002729535 -0.006529927 0.4151242 0.005039215 -0.006709516 0.4189459 0.007343769 -0.006855368 0.4227746 0.009708464 -0.00694555 0.4265485 0.01449865 -0.006959795 0.4340447 0.01696223 -0.006862223 0.4377317 0.01944875 -0.006689906 0.4413918 0.02197688 -0.006432652 0.4450145 0.02456808 -0.006079673 0.4485822 0.0271877 -0.005630195 0.4521124 0.02983868 -0.005077242 0.4556081 0.03257757 -0.004403531 0.4590285 0.0353347 -0.003620266 0.4624133 0.03819537 -0.002723097 0.4656933 0.04444336 -0.001119911 0.4671808 0.0411204 -0.00173068 0.4688756 0.04724872 5.06055e-4 0.4748155 0.05047935 0.001731157 0.4775246 0.05384367 0.00301522 0.4800205 0.05737382 0.004352092 0.4822698 0.05996555 0.005537867 0.4848601 0.0638644 0.006937861 0.4864973 0.07257336 0.009761333 0.4884703 0.07618713 0.01097279 0.489647 -0.1901337 -0.003598451 0.04031753 -0.1779718 -0.003552079 0.06413602 -0.1696293 -0.003532052 0.08052295 -0.1580319 -0.003524184 0.1033853 -0.1555867 -0.004041314 0.1151643 -0.1214467 -0.003157138 0.169414 -0.01412969 -0.003897964 0.3807244 -0.01282984 -0.004047632 0.3827418 -0.01296979 -0.004713714 0.3877657 -0.004386603 -0.005862712 0.4036208 0.01208627 -0.006984114 0.4303104 0.04413479 -6.50992e-4 0.4719233 -0.1813033 -0.004118204 0.06524491 -0.1665512 -0.00409007 0.09424847 -0.1447394 -0.004129469 0.1374663 -0.1353377 -0.00418812 0.1562564 -0.1244244 -0.003672361 0.1709224 -0.01670515 -0.004346311 0.3820291 -0.01546502 -0.004529953 0.3840767 -0.01381051 -0.006148755 0.3986347 -0.005743026 -0.006446719 0.4069014 -0.01132494 -0.006446897 0.4029071 -0.00895369 -0.00672537 0.4069488 -0.006561875 -0.006983876 0.4109755 -0.002343952 -0.006802618 0.4126323 -0.004149138 -0.007223665 0.4149861 -3.50326e-5 -0.007013916 0.4164757 0.00229758 -0.0071913 0.4202993 -0.001708805 -0.007428765 0.4189737 0.004656374 -0.007327377 0.4240995 7.58633e-4 -0.007596194 0.4229375 0.007045984 -0.007414758 0.4278718 0.003259479 -0.007714748 0.4268742 0.005796432 -0.007776141 0.4307781 0.007080256 -0.007782936 0.4327173 0.009467124 -0.007446169 0.4316158 0.01192432 -0.007414221 0.4353269 0.01231926 -0.007628977 0.4403797 0.01695489 -0.007130861 0.4426399 0.01441937 -0.007311582 0.439002 0.01500803 -0.007427275 0.4441474 0.01953542 -0.006864726 0.4462359 0.01774835 -0.007132232 0.4478687 0.0221613 -0.006505787 0.4497888 0.02054435 -0.006732344 0.4515382 0.02483659 -0.006046831 0.453293 0.02339595 -0.006225883 0.455156 0.02756434 -0.005480349 0.4567483 0.02631258 -0.005594134 0.4587141 0.03034776 -0.004799067 0.4601496 0.0331912 -0.004000782 0.4634879 0.0292924 -0.004842102 0.462211 0.03610801 -0.003093838 0.466741 0.03235 -0.003962755 0.4656247 0.03911143 -0.002087891 0.4698817 0.03549295 -0.002965748 0.4689414 0.03874522 -0.001865983 0.4721153 0.040412 -0.001277327 0.4736508 0.04221433 -9.92749e-4 0.4728847 0.04542946 1.81981e-4 0.4757242 0.04743683 0.001271784 0.4792754 0.05225247 0.002731204 0.4808132 0.04877156 0.001426517 0.4783762 0.05118626 0.002649605 0.48174 0.05588603 0.004086315 0.4830116 0.05510604 0.004085063 0.4839458 0.0592184 0.005562841 0.4858523 0.06349366 0.007053256 0.487443 0.07130205 0.009488821 0.488876 0.06792455 0.008541464 0.4887037 0.07242661 0.009958505 0.4896158 0.07700103 0.01130652 0.4901773 0.08155465 0.01250493 0.4903614 0.08868342 0.01407426 0.4898203 0.08609431 0.01355963 0.4901704 0.08832418 0.01400363 0.489923 -0.2077394 -0.004758059 0.02102011 -0.1928719 -0.004687368 0.05007374 -0.1764801 -0.004641294 0.0822938 -0.16328 -0.004633247 0.1083211 -0.1494696 -0.004664838 0.1357182 -0.1378697 -0.004732012 0.1588546 -0.01014131 -0.00658673 0.4049295 -0.007760226 -0.006856381 0.4089639 -0.005358636 -0.007107913 0.4129835 -0.002932131 -0.007329821 0.4169815 -4.79788e-4 -0.007520437 0.4209596 0.00200504 -0.007660984 0.4249089 0.00452286 -0.007754504 0.4288305 0.009676814 -0.007745742 0.4365685 0.01913857 -0.006946504 0.4497102 0.02196395 -0.006492137 0.4533537 0.02484673 -0.00592488 0.4569423 0.02779358 -0.005233585 0.4604715 0.03081208 -0.004418015 0.4639275 0.03390657 -0.003476262 0.4673035 0.03710734 -0.002429425 0.4705438 0.0438565 -4.41591e-5 0.4765603 0.06133764 0.006311833 0.4866922 0.06568855 0.007796406 0.4881135 0.07016777 0.009259819 0.4892041 0.07470643 0.01064282 0.4899407 0.07927721 0.01192116 0.4903156 0.08383524 0.01305806 0.4903159 -0.2134838 -0.005200564 0.01722943 -0.2103925 -0.005181908 0.0232644 -0.2056537 -0.00515592 0.0325272 -0.1989279 -0.005126237 0.04569631 -0.1940237 -0.005109429 0.05531871 -0.1894327 -0.00509727 0.06433737 -0.1849181 -0.005088686 0.07322007 -0.1818135 -0.005085051 0.07933455 -0.1777633 -0.005082547 0.08732146 -0.1725045 -0.005083322 0.09770441 -0.1660667 -0.005090892 0.1104421 -0.1616028 -0.005100548 0.1192882 -0.1586162 -0.005108773 0.125214 -0.1555435 -0.005118966 0.1313163 -0.1515382 -0.005134522 0.1392803 -0.1475181 -0.005153179 0.1472826 -0.1444655 -0.005169153 0.1533661 -0.1414384 -0.005186736 0.1594048 -0.1374685 -0.005212366 0.1673333 -0.01250547 -0.006307363 0.400882 0.008372545 -0.007775068 0.4346487 0.01099228 -0.007696628 0.4384793 0.01365697 -0.007541358 0.4422703 0.01637244 -0.007290899 0.4460132 0.04211735 -6.7187e-4 0.4751275 0.04562669 6.05791e-4 0.4779481 0.04929178 0.001951992 0.4805362 0.05311888 0.003364503 0.4828864 0.05713939 0.004817843 0.4849347 0.09053701 0.01440036 0.4895778 -0.09186172 -0.002179861 0.1488226 -0.09297233 -0.001210451 0.1493852 -0.09311151 -0.001264095 0.1494557 -0.09239518 -0.001264095 0.1490928 -0.09204995 -0.001565635 0.1489179 -0.09214895 -0.001444101 0.1489681 -0.09226584 -0.001342654 0.1490273 -0.09253436 -0.001210451 0.1491633 -0.09196877 -0.001703917 0.1488769 -0.09190988 -0.001855134 0.148847 -0.09267973 -0.001183271 0.149237 -0.09282696 -0.001183271 0.1493116 -0.09187334 -0.002015233 0.1488285 -0.09196877 -0.002655923 0.1488769 -0.09190988 -0.002504646 0.148847 -0.09335774 -0.001444101 0.1495804 -0.09324175 -0.001342654 0.1495217 -0.09187334 -0.002344489 0.1488285 -0.09345763 -0.001565635 0.149631 -0.09353792 -0.001703917 0.1496717 -0.09204995 -0.002794206 0.1489179 -0.09239518 -0.003095746 0.1490928 -0.09363335 -0.002015233 0.14972 -0.09364587 -0.002179861 0.1497264 -0.09214985 -0.00291568 0.1489686 -0.09359681 -0.001855134 0.1497015 -0.09226584 -0.003017127 0.1490273 -0.09359771 -0.002504408 0.149702 -0.09353792 -0.002655565 0.1496717 -0.09282785 -0.003176391 0.149312 -0.09363335 -0.002344489 0.14972 -0.09267973 -0.00317645 0.149237 -0.09253436 -0.003149271 0.1491633 -0.09335774 -0.002915322 0.1495804 -0.09324175 -0.003016829 0.1495217 -0.0931124 -0.003095448 0.1494562 -0.09297233 -0.003149151 0.1493852 -0.09345763 -0.002793848 0.149631 -0.1119613 -0.006342947 0.1646091 -0.1199547 -0.002899646 0.1686582 -0.1173253 -0.006125211 0.1673263 -0.09133738 -0.002504646 0.1541619 -0.09137392 -0.002344489 0.1541804 -0.1057158 -4.77895e-4 0.1614454 -0.09771567 8.61132e-4 0.1573929 -0.0907129 -0.001210451 0.1538456 -0.09056752 -0.001183271 0.1537719 -0.09133738 -0.001855134 0.1541619 -0.09127849 -0.001703917 0.1541321 -0.09138643 -0.002179861 0.1541867 -0.09137392 -0.002015233 0.1541804 -0.1110796 -0.001383125 0.1641625 -0.1155153 -0.002138316 0.1664094 -0.1065963 -0.006552696 0.1618914 -0.1012322 -0.006754398 0.1591742 -0.0904203 -0.001183271 0.1536973 -0.093086 0.001633644 0.1550476 -0.08514189 0.002952158 0.1510235 -0.09127849 -0.002655923 0.1541321 -0.0911982 -0.002794206 0.1540914 -0.08960229 -0.002179861 0.1532829 -0.08961391 -0.002015233 0.1532889 -0.0910983 -0.00291568 0.1540408 -0.08514189 -0.007311403 0.1510235 -0.1226858 -0.005858838 0.1700417 -0.1244244 -0.003672361 0.1709224 -0.1289754 -0.004464566 0.1732277 -0.1280436 -0.005564033 0.1727557 -0.1333996 -0.005240976 0.1754689 -0.08988952 -0.001444101 0.1534285 -0.09000641 -0.001342654 0.1534877 -0.08965045 -0.001855134 0.1533074 -0.09098231 -0.001342654 0.1539821 -0.0910983 -0.001444101 0.1540408 -0.08979052 -0.001565635 0.1533783 -0.08970934 -0.001703917 0.1533372 -0.09085208 -0.001264095 0.1539161 -0.09013575 -0.001264095 0.1535532 -0.09027493 -0.001210451 0.1536237 -0.0911982 -0.001565635 0.1540914 -0.0907129 -0.003149271 0.1538456 -0.09586912 -0.006948113 0.1564575 -0.09056752 -0.00317645 0.1537719 -0.09098142 -0.003017127 0.1539816 -0.09085208 -0.003095746 0.1539161 -0.09050506 -0.007133781 0.1537403 -0.0904203 -0.003176391 0.1536973 -0.09027493 -0.003149151 0.1536237 -0.09000551 -0.003016829 0.1534872 -0.09013575 -0.003095448 0.1535532 -0.08978962 -0.002793848 0.1533778 -0.08988952 -0.002915322 0.1534285 -0.08965045 -0.002504408 0.1533074 -0.08970934 -0.002655565 0.1533372 -0.08961391 -0.002344489 0.1532889 -0.09187334 -0.002015233 0.1488285 -0.09186172 -0.002179861 0.1488226 -0.08960229 -0.002179861 0.1532829 -0.09204995 -0.001565635 0.1489179 -0.09196877 -0.001703917 0.1488769 -0.08970934 -0.001703917 0.1533372 -0.09190988 -0.001855134 0.148847 -0.08961391 -0.002015233 0.1532889 -0.08965045 -0.001855134 0.1533074 -0.09000641 -0.001342654 0.1534877 -0.09239518 -0.001264095 0.1490928 -0.09226584 -0.001342654 0.1490273 -0.08979052 -0.001565635 0.1533783 -0.08988952 -0.001444101 0.1534285 -0.09214895 -0.001444101 0.1489681 -0.09267973 -0.001183271 0.149237 -0.0904203 -0.001183271 0.1536973 -0.09282696 -0.001183271 0.1493116 -0.09253436 -0.001210451 0.1491633 -0.09013575 -0.001264095 0.1535532 -0.09027493 -0.001210451 0.1536237 -0.09324175 -0.001342654 0.1495217 -0.09311151 -0.001264095 0.1494557 -0.09085208 -0.001264095 0.1539161 -0.0907129 -0.001210451 0.1538456 -0.09297233 -0.001210451 0.1493852 -0.09056752 -0.001183271 0.1537719 -0.0911982 -0.001565635 0.1540914 -0.09353792 -0.001703917 0.1496717 -0.09345763 -0.001565635 0.149631 -0.09098231 -0.001342654 0.1539821 -0.0910983 -0.001444101 0.1540408 -0.09335774 -0.001444101 0.1495804 -0.09363335 -0.002015233 0.14972 -0.09137392 -0.002015233 0.1541804 -0.09364587 -0.002179861 0.1497264 -0.09359681 -0.001855134 0.1497015 -0.09127849 -0.001703917 0.1541321 -0.09133738 -0.001855134 0.1541619 -0.09353792 -0.002655565 0.1496717 -0.09359771 -0.002504408 0.149702 -0.09133738 -0.002504646 0.1541619 -0.09137392 -0.002344489 0.1541804 -0.09363335 -0.002344489 0.14972 -0.09138643 -0.002179861 0.1541867 -0.0910983 -0.00291568 0.1540408 -0.09324175 -0.003016829 0.1495217 -0.09335774 -0.002915322 0.1495804 -0.09127849 -0.002655923 0.1541321 -0.0911982 -0.002794206 0.1540914 -0.09345763 -0.002793848 0.149631 -0.09297233 -0.003149151 0.1493852 -0.0907129 -0.003149271 0.1538456 -0.09282785 -0.003176391 0.149312 -0.0931124 -0.003095448 0.1494562 -0.09098142 -0.003017127 0.1539816 -0.09085208 -0.003095746 0.1539161 -0.09267973 -0.00317645 0.149237 -0.0904203 -0.003176391 0.1536973 -0.09253436 -0.003149271 0.1491633 -0.09056752 -0.00317645 0.1537719 -0.09027493 -0.003149151 0.1536237 -0.09239518 -0.003095746 0.1490928 -0.09226584 -0.003017127 0.1490273 -0.09013575 -0.003095448 0.1535532 -0.09000551 -0.003016829 0.1534872 -0.09214985 -0.00291568 0.1489686 -0.08988952 -0.002915322 0.1534285 -0.09204995 -0.002794206 0.1489179 -0.09196877 -0.002655923 0.1488769 -0.08978962 -0.002793848 0.1533778 -0.08970934 -0.002655565 0.1533372 -0.09190988 -0.002504646 0.148847 -0.08965045 -0.002504408 0.1533074 -0.09187334 -0.002344489 0.1488285 -0.08961391 -0.002344489 0.1532889 0.00923115 -0.002418994 0.04941093 0.1258184 -0.00241959 0.2795661 0.1256738 -0.001779198 0.2796393 0.1256251 -0.001120805 0.279664 0.009037911 -0.001120805 0.04950881 0.009086668 -0.001779377 0.04948413 0.1263775 -0.003577649 0.2792829 0.01018881 -0.004062831 0.04892581 0.1267767 -0.004063725 0.2790806 0.009789884 -0.003576755 0.04912787 0.1260552 -0.003024578 0.2794461 0.00946772 -0.003023803 0.04929107 0.01172918 -0.004997968 0.04814553 0.1283175 -0.004998385 0.2783002 0.12776 -0.004783928 0.2785825 0.01117175 -0.004783272 0.04842787 0.1272417 -0.004469454 0.2788451 0.01065367 -0.004468679 0.04869031 0.1300693 -0.004998385 0.2774127 0.1294881 -0.005107164 0.2777072 0.01348108 -0.004998683 0.04725807 0.1288987 -0.005107164 0.2780057 0.01231032 -0.005106925 0.04785114 0.01289975 -0.005107164 0.04755258 0.1311451 -0.004469454 0.2768678 0.01502245 -0.004064261 0.04647731 0.1316101 -0.004063725 0.2766323 0.01403862 -0.004784345 0.04697561 0.01455712 -0.00446999 0.04671299 0.1306268 -0.004783928 0.2771304 0.1320093 -0.003577649 0.27643 0.01542174 -0.003578245 0.04627501 0.0157442 -0.003025054 0.0461117 0.01598107 -0.002419948 0.04599171 0.1323316 -0.003024578 0.2762668 0.01612585 -0.001779377 0.04591834 0.1325684 -0.00241959 0.2761468 0.132713 -0.001779198 0.2760736 0.01617455 -0.001120805 0.04589366 0.1327617 -0.001120805 0.2760489 -0.02696096 -0.001120805 0.007211327 -0.02876847 -0.001120805 0.003642976 -0.02252399 -0.001120805 4.79817e-4 -0.06183826 -0.001120805 -0.07713061 -0.05737787 -0.001120805 -0.07939004 -0.01625603 -0.001120805 0.001788675 -0.01621413 -0.00180453 0.001767396 -0.02696096 -0.001120805 0.007211327 -0.01625603 -0.001120805 0.001788675 -0.0160892 -0.00247538 0.001704156 -0.02696096 -0.003120839 0.007211327 -0.01588368 -0.003120839 0.001600027 -0.001423299 -0.003120839 0.03014642 -0.01250052 -0.003120839 0.03575766 -0.02696096 -0.003120839 0.007211327 -0.01588368 -0.003120839 0.001600027 -0.01250052 -0.003120839 0.03575766 -0.001628816 -0.00247538 0.03025054 -0.001753687 -0.00180453 0.03031378 -0.01250052 -0.001120805 0.03575766 -0.001423299 -0.003120839 0.03014642 -0.001795649 -0.001120805 0.030335 0.009037911 -0.001120805 0.04950881 0.1256251 -0.001120805 0.279664 0.07729649 -0.001120805 0.1886841 -0.004900336 -0.001120805 0.03527069 -0.01114487 -0.001120805 0.0384339 -0.01250052 -0.001120805 0.03575766 0.07820028 -0.001120805 0.1904682 0.1202726 -0.001120805 0.2823753 0.07463192 -0.001120805 0.1922758 0.07234328 -0.001120805 0.1822253 0.07372814 -0.001120805 0.1904916 0.07011306 -0.001120805 0.183355 0.008145868 -0.001120805 0.04996067 0.07008379 -0.001120805 0.1777649 0.06785362 -0.001120805 0.1788946 -0.001795649 -0.001120805 0.030335 0.008145868 -0.001120805 0.04996067 0.009086668 -0.001779377 0.04948413 0.009037911 -0.001120805 0.04950881 0.01294106 -0.006106615 0.04753166 0.01360011 -0.005994975 0.04719781 0.01289975 -0.005107164 0.04755258 0.008921861 -0.003938734 0.04956758 0.009789884 -0.003576755 0.04912787 0.008588254 -0.003291606 0.04973655 0.008344352 -0.002595663 0.04986011 0.00923115 -0.002418994 0.04941093 0.008195817 -0.001866638 0.0499354 0.009337604 -0.00452274 0.04935699 0.009826004 -0.005030512 0.04910957 0.01065367 -0.004468679 0.04869031 0.01018881 -0.004062831 0.04892581 0.0109772 -0.005775392 0.0485264 0.01172918 -0.004997968 0.04814553 0.01037603 -0.005450963 0.04883098 0.01117175 -0.004783272 0.04842787 0.01227432 -0.006106853 0.04786938 0.01231032 -0.005106925 0.04785114 0.01161468 -0.00599569 0.04820352 0.01403862 -0.004784345 0.04697561 0.01348108 -0.004998683 0.04725807 0.01483643 -0.005450963 0.04657149 0.01423656 -0.005774736 0.04687535 0.01538765 -0.005029559 0.0462923 0.01455712 -0.00446999 0.04671299 0.01587659 -0.004520833 0.04604458 0.01542174 -0.003578245 0.04627501 0.01629227 -0.003936111 0.04583406 0.01662546 -0.003288626 0.04566526 0.01502245 -0.004064261 0.04647731 0.01598107 -0.002419948 0.04599171 0.01686877 -0.0025931 0.045542 0.01701664 -0.001866638 0.04546707 0.0157442 -0.003025054 0.0461117 0.01706659 -0.001120805 0.0454418 0.01612585 -0.001779377 0.04591834 0.01617455 -0.001120805 0.04589366 0.00946772 -0.003023803 0.04929107 -0.04845714 -0.001120805 -0.08390897 -0.04399675 -0.001120805 -0.0861684 -0.004682481 -0.001120805 -0.008557915 0.005710899 -0.001120805 0.01195973 0.01706659 -0.001120805 0.0454418 -0.001912653 -0.001120805 0.007974684 -0.007335305 -0.001120805 -0.00273019 0.007900118 -0.001120805 0.003003895 0.01284748 -0.001120805 0.00834465 0.01617455 -0.001120805 0.04589366 0.1327617 -0.001120805 0.2760489 0.1381142 -0.001120805 0.2733376 0.002477467 -0.001120805 -0.00770092 0.002454042 -0.001120805 -0.01217299 0.07729649 -0.001120805 0.1886841 0.07372814 -0.01095235 0.1904916 0.07372814 -0.001120805 0.1904916 0.07729649 -0.01100546 0.1886841 0.07372814 -0.001120805 0.1904916 0.07011306 -0.01102268 0.183355 0.07011306 -0.001120805 0.183355 0.07372814 -0.01095235 0.1904916 0.07011306 -0.001120805 0.183355 0.07234328 -0.01105862 0.1822253 0.07234328 -0.001120805 0.1822253 0.07011306 -0.01102268 0.183355 0.07234328 -0.001120805 0.1822253 0.07008379 -0.01109296 0.1777649 0.07008379 -0.001120805 0.1777649 0.07234328 -0.01105862 0.1822253 0.07008379 -0.001120805 0.1777649 0.06785362 -0.0110563 0.1788946 0.06785362 -0.001120805 0.1788946 0.07008379 -0.01109296 0.1777649 0.06785362 -0.001120805 0.1788946 0.03147709 -0.01092863 0.1070836 -0.004900336 -0.001120805 0.03527069 0.04966509 -0.01100349 0.1429886 0.06785362 -0.0110563 0.1788946 0.01328814 -0.01083177 0.07117664 -0.004900336 -0.01071292 0.03527069 -0.004900336 -0.001120805 0.03527069 -0.01114487 -0.01056456 0.0384339 -0.01114487 -0.001120805 0.0384339 -0.004900336 -0.01071292 0.03527069 -0.02696096 -0.003120839 0.007211327 -0.01250052 -0.003120839 0.03575766 -0.01114487 -0.01056456 0.0384339 -0.02876847 -0.01057291 0.003642976 -0.02876847 -0.001120805 0.003642976 -0.01250052 -0.001120805 0.03575766 -0.01114487 -0.001120805 0.0384339 -0.02696096 -0.001120805 0.007211327 -0.02876847 -0.001120805 0.003642976 -0.02252399 -0.01072102 4.79817e-4 -0.02252399 -0.001120805 4.79817e-4 -0.02876847 -0.01057291 0.003642976 -0.02252399 -0.001120805 4.79817e-4 -0.04218113 -0.01078361 -0.03832542 -0.06183826 -0.001120805 -0.07713061 -0.02252399 -0.01072102 4.79817e-4 -0.06183826 -0.01087468 -0.07713061 -0.04850709 -0.001866638 -0.08388364 -0.04865562 -0.002595722 -0.08380842 -0.04399675 -0.001120805 -0.0861684 -0.04845714 -0.001120805 -0.08390897 -0.04399675 -0.01110303 -0.0861684 -0.05068731 -0.005450963 -0.08277922 -0.04994428 -0.01106387 -0.08315563 -0.04923313 -0.003938734 -0.08351588 -0.04889953 -0.003291606 -0.08368486 -0.05258554 -0.006106853 -0.08181768 -0.05589139 -0.01098775 -0.08014303 -0.05618786 -0.004520833 -0.07999289 -0.06183826 -0.01087468 -0.07713061 -0.05569893 -0.005029559 -0.08024054 -0.04964888 -0.00452274 -0.08330529 -0.05013728 -0.005030512 -0.08305788 -0.05128848 -0.005775392 -0.0824747 -0.05192595 -0.00599569 -0.08215177 -0.05325227 -0.006106615 -0.0814799 -0.05391138 -0.005994975 -0.08114606 -0.05454784 -0.005774736 -0.08082365 -0.0551477 -0.005450963 -0.08051979 -0.06183826 -0.001120805 -0.07713061 -0.05660355 -0.003936111 -0.0797823 -0.05717998 -0.0025931 -0.0794903 -0.05693674 -0.003288626 -0.0796135 -0.05732792 -0.001866638 -0.07941538 -0.05737787 -0.001120805 -0.07939004 -0.04399675 -0.001120805 -0.0861684 -0.02433961 -0.01102381 -0.04736316 -0.004682481 -0.001120805 -0.008557915 -0.04399675 -0.01110303 -0.0861684 -0.004682481 -0.01096922 -0.008557915 -0.004682481 -0.001120805 -0.008557915 0.002454042 -0.01095527 -0.01217299 0.002454042 -0.001120805 -0.01217299 -0.004682481 -0.01096922 -0.008557915 0.002454042 -0.001120805 -0.01217299 0.01284748 -0.01094609 0.00834465 0.01284748 -0.001120805 0.00834465 0.002454042 -0.01095527 -0.01217299 0.01284748 -0.001120805 0.00834465 0.005710899 -0.0109589 0.01195973 0.005710899 -0.001120805 0.01195973 0.01284748 -0.01094609 0.00834465 0.06245815 -0.01124483 0.1239848 0.08137297 -0.0110054 0.1613245 0.005710899 -0.001120805 0.01195973 0.005710899 -0.0109589 0.01195973 0.1381142 -0.009282588 0.2733376 0.1381142 -0.001120805 0.2733376 0.1256738 -0.001779198 0.2796393 0.1202726 -0.001120805 0.2823753 0.1256251 -0.001120805 0.279664 0.1202726 -0.009592831 0.2823753 0.12776 -0.004783928 0.2785825 0.1262215 -0.009589791 0.2793619 0.1258184 -0.00241959 0.2795661 0.1288987 -0.005107164 0.2780057 0.1321687 -0.009486377 0.2763493 0.1381142 -0.009282588 0.2733376 0.1316101 -0.004063725 0.2766323 0.1320093 -0.003577649 0.27643 0.1306268 -0.004783928 0.2771304 0.1311451 -0.004469454 0.2768678 0.1260552 -0.003024578 0.2794461 0.1263775 -0.003577649 0.2792829 0.1267767 -0.004063725 0.2790806 0.1272417 -0.004469454 0.2788451 0.1283175 -0.004998385 0.2783002 0.1294881 -0.005107164 0.2777072 0.1300693 -0.004998385 0.2774127 0.1323316 -0.003024578 0.2762668 0.1325684 -0.00241959 0.2761468 0.1381142 -0.001120805 0.2733376 0.132713 -0.001779198 0.2760736 0.1327617 -0.001120805 0.2760489 0.1202726 -0.001120805 0.2823753 0.1202726 -0.009592831 0.2823753 0.1088616 -0.009746432 0.2598487 0.09745097 -0.01002067 0.2373229 0.08604121 -0.01041567 0.2147989 0.07463192 -0.001120805 0.1922758 0.07463192 -0.01093137 0.1922758 0.07463192 -0.001120805 0.1922758 0.07820028 -0.010984 0.1904682 0.07820028 -0.001120805 0.1904682 0.07463192 -0.01093137 0.1922758 0.07820028 -0.001120805 0.1904682 0.07729649 -0.01100546 0.1886841 0.07729649 -0.001120805 0.1886841 0.07820028 -0.010984 0.1904682 -0.001954555 -0.00180453 0.007995903 0.01701664 -0.001866638 0.04546707 -0.002079427 -0.00247538 0.008059144 0.01037603 -0.005450963 0.04883098 -0.05454784 -0.005774736 -0.08082365 0.0109772 -0.005775392 0.0485264 -0.0551477 -0.005450963 -0.08051979 0.01662546 -0.003288626 0.04566526 -0.007707655 -0.003120839 -0.002541542 -0.002285003 -0.003120839 0.008163273 0.009826004 -0.005030512 0.04910957 0.01686877 -0.0025931 0.045542 -0.001912653 -0.001120805 0.007974684 0.01706659 -0.001120805 0.0454418 -0.05013728 -0.005030512 -0.08305788 -0.04964888 -0.00452274 -0.08330529 0.01538765 -0.005029559 0.0462923 0.01629227 -0.003936111 0.04583406 -0.04923313 -0.003938734 -0.08351588 -0.04889953 -0.003291606 -0.08368486 0.01360011 -0.005994975 0.04719781 0.01294106 -0.006106615 0.04753166 -0.05192595 -0.00599569 -0.08215177 0.01483643 -0.005450963 0.04657149 0.01423656 -0.005774736 0.04687535 -0.05068731 -0.005450963 -0.08277922 -0.05391138 -0.005994975 -0.08114606 -0.05325227 -0.006106615 -0.0814799 0.01227432 -0.006106853 0.04786938 0.01161468 -0.00599569 0.04820352 -0.05569893 -0.005029559 -0.08024054 0.009337604 -0.00452274 0.04935699 -0.05618786 -0.004520833 -0.07999289 -0.05717998 -0.0025931 -0.0794903 -0.0160892 -0.00247538 0.001704156 -0.05732792 -0.001866638 -0.07941538 0.008921861 -0.003938734 0.04956758 -0.05660355 -0.003936111 -0.0797823 0.008588254 -0.003291606 0.04973655 -0.001423299 -0.003120839 0.03014642 -0.01588368 -0.003120839 0.001600027 -0.05693674 -0.003288626 -0.0796135 0.008344352 -0.002595663 0.04986011 -0.001628816 -0.00247538 0.03025054 -0.001753687 -0.00180453 0.03031378 0.008195817 -0.001866638 0.0499354 0.008145868 -0.001120805 0.04996067 -0.001795649 -0.001120805 0.030335 -0.01621413 -0.00180453 0.001767396 -0.05737787 -0.001120805 -0.07939004 -0.01625603 -0.001120805 0.001788675 -0.05258554 -0.006106853 -0.08181768 -0.05128848 -0.005775392 -0.0824747 0.01587659 -0.004520833 0.04604458 -0.04865562 -0.002595722 -0.08380842 -0.007502138 -0.00247538 -0.002645671 -0.04850709 -0.001866638 -0.08388364 -0.007377207 -0.00180453 -0.002708971 -0.04845714 -0.001120805 -0.08390897 -0.007335305 -0.001120805 -0.00273019 -0.007377207 -0.00180453 -0.002708971 0.002477467 -0.001120805 -0.00770092 0.002477467 -0.003120839 -0.00770092 -0.007502138 -0.00247538 -0.002645671 -0.007707655 -0.003120839 -0.002541542 -0.007335305 -0.001120805 -0.00273019 0.007900118 -0.001120805 0.003003895 0.007900118 -0.003120839 0.003003895 0.002477467 -0.003120839 -0.00770092 0.002477467 -0.001120805 -0.00770092 0.007900118 -0.001120805 0.003003895 -0.001912653 -0.001120805 0.007974684 -0.001954555 -0.00180453 0.007995903 -0.002079427 -0.00247538 0.008059144 -0.002285003 -0.003120839 0.008163273 0.007900118 -0.003120839 0.003003895 0.07011306 -0.01102268 0.183355 0.07372814 -0.01095235 0.1904916 0.07234328 -0.01105862 0.1822253 -0.02433961 -0.01102381 -0.04736316 -0.04399675 -0.01110303 -0.0861684 -0.04994428 -0.01106387 -0.08315563 0.04966509 -0.01100349 0.1429886 0.06785362 -0.0110563 0.1788946 0.06852126 -0.010643 0.17316 0.07729649 -0.01100546 0.1886841 0.07008379 -0.01109296 0.1777649 0.01950287 -0.01118618 0.06247746 -0.005513906 -0.0111128 0.02996087 -0.004900336 -0.01071292 0.03527069 -0.004033923 -0.01094216 0.001181244 -0.01624011 -0.01123791 -0.009804189 -0.00394988 -0.01094102 0.001607 -0.02876847 -0.01057291 0.003642976 -0.01114487 -0.01056456 0.0384339 -0.003870189 -0.0109483 -2.23748e-4 -0.004682481 -0.01096922 -0.008557915 -0.06183826 -0.01087468 -0.07713061 -0.03503096 -0.01117068 -0.04549312 -0.05589139 -0.01098775 -0.08014303 -0.02252399 -0.01072102 4.79817e-4 -0.002411305 -0.0109604 -0.001861512 -0.002795457 -0.01095789 -0.001629292 -0.003438651 -0.01095306 -0.001007616 -0.003140211 -0.01095545 -0.001342654 0.07820028 -0.010984 0.1904682 0.07563894 -0.01068949 0.1695545 0.05279457 -0.01088613 0.1359644 0.03645509 -0.01106721 0.09907025 0.01328814 -0.01083177 0.07117664 0.06004494 -0.01093345 0.1322917 0.03147709 -0.01092863 0.1070836 -0.04218113 -0.01078361 -0.03832542 0.005710899 -0.0109589 0.01195973 0.001132607 -0.01096141 0.002866208 7.43557e-4 -0.01095956 0.003214955 0.1321687 -0.009486377 0.2763493 0.1381142 -0.009282588 0.2733376 0.1192004 -0.009856879 0.2359997 0.09058737 -0.01038324 0.2071354 0.08604121 -0.01041567 0.2147989 0.09745097 -0.01002067 0.2373229 0.1048898 -0.01001465 0.2450335 0.1088616 -0.009746432 0.2598487 0.1202726 -0.009592831 0.2823753 0.001937806 -0.0112431 0.0261861 -0.001925826 -0.01096248 -0.002056658 0.001455485 -0.0109629 0.002455115 2.99972e-4 -0.01095736 0.003490865 -8.91454e-4 -0.0109654 -0.002181112 -3.73993e-4 -0.01096636 -0.002107203 0.001815199 -0.01096707 -5.48884e-5 0.001922488 -0.01096659 4.57197e-4 0.01284748 -0.01094609 0.00834465 0.001865148 -0.01096516 0.00149697 0.001702249 -0.01096415 0.001993954 5.84666e-4 -0.01096737 -0.001697599 1.23139e-4 -0.01096695 -0.001944363 0.001939296 -0.01096594 9.79692e-4 9.96139e-4 -0.01096755 -0.001374542 0.002454042 -0.01095527 -0.01217299 0.001620531 -0.01096737 -5.40979e-4 0.001344501 -0.01096755 -9.84743e-4 -0.001413941 -0.01096415 -0.002164185 -0.003683805 -0.01095068 -6.31906e-4 -0.003025591 -0.01094108 0.003077566 -0.003344833 -0.01094037 0.002754092 -0.004055023 -0.01094377 7.24301e-4 -0.003814697 -0.01094037 0.00199449 -0.002669394 -0.01094228 0.003343939 -0.002286434 -0.010944 0.003550827 -0.001882374 -0.01094615 0.00369817 -0.001441895 -0.01094853 0.003789663 -9.94515e-4 -0.01095086 0.003814041 -1.13748e-4 -0.01095527 0.003662884 -5.48497e-4 -0.01095306 0.003771483 -0.003998279 -0.01094591 2.39089e-4 -0.00361979 -0.01094013 0.002367913 0.02692019 -0.01123458 0.05872011 0.04380536 -0.01111519 0.09534686 0.07463192 -0.01093137 0.1922758 0.0435425 -0.01114952 0.08664333 0.06245809 -0.01124483 0.1239846 0.08137327 -0.01100534 0.1613251 0.09753948 -0.01035243 0.2036138 0.1116436 -0.009984731 0.2416123 0.1002866 -0.01043111 0.1986619 0.1262215 -0.009589791 0.2793619 -0.002833366 -0.003120839 -0.001601874 -0.007707655 -0.003120839 -0.002541542 -0.002411305 -0.003120839 -0.001861512 7.44045e-4 -0.003120839 0.003214836 0.001133561 -0.003120839 0.00286585 0.007900118 -0.003120839 0.003003895 -0.003610849 -0.003120839 0.002386689 -0.003834724 -0.003120839 0.00194472 0.002477467 -0.003120839 -0.00770092 -0.001926064 -0.003120839 -0.002056241 2.99972e-4 -0.003120839 0.003490865 -0.002285003 -0.003120839 0.008163273 -1.59018e-4 -0.003120839 0.003677546 -0.003521621 -0.003120839 -8.93757e-4 -0.003206849 -0.003120839 -0.001276254 -0.003942787 -0.003120839 -4.24683e-7 -0.003769218 -0.003120839 -4.64559e-4 -0.004051029 -0.003120839 9.81122e-4 -0.004037559 -0.003120839 4.85882e-4 -0.003982841 -0.003120839 0.001471817 -0.003317177 -0.003120839 0.002785861 -0.002554655 -0.003120839 0.003413259 -0.002961874 -0.003120839 0.003131151 -0.00162959 -0.003120839 0.003759205 -0.002106487 -0.003120839 0.003624558 -6.42475e-4 -0.003120839 0.003786027 -0.001137077 -0.003120839 0.003813505 0.001922786 -0.003120839 4.56125e-4 0.001815199 -0.003120839 -5.56931e-5 0.001703023 -0.003120839 0.001993298 0.001456439 -0.003120839 0.002454519 0.001939833 -0.003120839 9.78746e-4 0.001865744 -0.003120839 0.001496434 0.001620531 -0.003120839 -5.40979e-4 9.95468e-4 -0.003120839 -0.001374542 0.001344442 -0.003120839 -9.85056e-4 1.22957e-4 -0.003120839 -0.001944065 5.84174e-4 -0.003120839 -0.00169748 -8.9163e-4 -0.003120839 -0.002180814 -3.739e-4 -0.003120839 -0.002106785 -0.001414239 -0.003120839 -0.002163827 -0.003834724 -0.003120839 0.00194472 -0.003814697 -0.01094037 0.00199449 -0.003610849 -0.003120839 0.002386689 -0.00361979 -0.01094013 0.002367913 -0.003344833 -0.01094037 0.002754092 -0.003025591 -0.01094108 0.003077566 -0.003317177 -0.003120839 0.002785861 -0.002669394 -0.01094228 0.003343939 -0.002961874 -0.003120839 0.003131151 -0.002554655 -0.003120839 0.003413259 -0.002286434 -0.010944 0.003550827 -0.001882374 -0.01094615 0.00369817 -0.002106487 -0.003120839 0.003624558 -0.001441895 -0.01094853 0.003789663 -0.00162959 -0.003120839 0.003759205 -0.001137077 -0.003120839 0.003813505 -9.94515e-4 -0.01095086 0.003814041 -5.48497e-4 -0.01095306 0.003771483 -1.59018e-4 -0.003120839 0.003677546 -6.42475e-4 -0.003120839 0.003786027 -1.13748e-4 -0.01095527 0.003662884 2.99972e-4 -0.003120839 0.003490865 2.99972e-4 -0.01095736 0.003490865 -0.00394988 -0.01094102 0.001607 -0.003982841 -0.003120839 0.001471817 -0.004033923 -0.01094216 0.001181244 -0.004051029 -0.003120839 9.81122e-4 -0.004055023 -0.01094377 7.24301e-4 -0.003998279 -0.01094591 2.39089e-4 -0.004037559 -0.003120839 4.85882e-4 -0.003942787 -0.003120839 -4.24683e-7 -0.003870189 -0.0109483 -2.23748e-4 -0.003769218 -0.003120839 -4.64559e-4 -0.003683805 -0.01095068 -6.31906e-4 -0.003438651 -0.01095306 -0.001007616 -0.003521621 -0.003120839 -8.93757e-4 -0.003206849 -0.003120839 -0.001276254 -0.003140211 -0.01095545 -0.001342654 -0.002833366 -0.003120839 -0.001601874 -0.002795457 -0.01095789 -0.001629292 -0.002411305 -0.003120839 -0.001861512 -0.002411305 -0.0109604 -0.001861512 7.43557e-4 -0.01095956 0.003214955 2.99972e-4 -0.003120839 0.003490865 2.99972e-4 -0.01095736 0.003490865 0.001702249 -0.01096415 0.001993954 0.001456439 -0.003120839 0.002454519 0.001455485 -0.0109629 0.002455115 0.001132607 -0.01096141 0.002866208 0.001133561 -0.003120839 0.00286585 7.44045e-4 -0.003120839 0.003214836 0.001939833 -0.003120839 9.78746e-4 0.001939296 -0.01096594 9.79692e-4 0.001922488 -0.01096659 4.57197e-4 0.001703023 -0.003120839 0.001993298 0.001865148 -0.01096516 0.00149697 0.001865744 -0.003120839 0.001496434 0.001620531 -0.01096737 -5.40979e-4 0.001344501 -0.01096755 -9.84743e-4 0.001620531 -0.003120839 -5.40979e-4 0.001815199 -0.01096707 -5.48884e-5 0.001815199 -0.003120839 -5.56931e-5 0.001922786 -0.003120839 4.56125e-4 1.23139e-4 -0.01096695 -0.001944363 5.84174e-4 -0.003120839 -0.00169748 5.84666e-4 -0.01096737 -0.001697599 9.95468e-4 -0.003120839 -0.001374542 0.001344442 -0.003120839 -9.85056e-4 9.96139e-4 -0.01096755 -0.001374542 -8.91454e-4 -0.0109654 -0.002181112 -3.739e-4 -0.003120839 -0.002106785 -3.73993e-4 -0.01096636 -0.002107203 1.22957e-4 -0.003120839 -0.001944065 -0.001413941 -0.01096415 -0.002164185 -8.9163e-4 -0.003120839 -0.002180814 -0.001414239 -0.003120839 -0.002163827 -0.001925826 -0.01096248 -0.002056658 -0.002411305 -0.0109604 -0.001861512 -0.001926064 -0.003120839 -0.002056241 -0.002411305 -0.003120839 -0.001861512 0.1287136 -0.005213558 0.2780998 -0.05551886 -0.005248069 -0.08705735 0.1293021 -0.005248129 0.2778016 -0.05919164 -0.001040697 -0.08519691 0.1256306 -0.001040697 0.2796615 0.1257098 -3.86078e-4 0.2796214 0.1298877 -0.005173683 0.277505 -0.0549333 -0.005173385 -0.087354 -0.05436676 -0.00499165 -0.087641 0.1304544 -0.004992127 0.277218 -0.05383461 -0.004707872 -0.08791053 0.1309866 -0.004708588 0.2769483 0.13147 -0.004330635 0.2767035 -0.05335146 -0.00432986 -0.08815526 -0.05293035 -0.003867864 -0.08836859 0.1318913 -0.003868639 0.2764901 -0.05258285 -0.003334522 -0.0885446 0.132239 -0.003335297 0.276314 0.1325036 -0.002744972 0.2761799 -0.05231839 -0.002744436 -0.08867859 -0.05214416 -0.002114176 -0.08876681 0.132678 -0.002113938 0.2760916 -0.05206483 -0.00145936 -0.08880704 0.1327574 -0.0014593 0.2760514 -0.05610746 -0.005213737 -0.0867592 0.1281382 -0.005070865 0.2783913 -0.05668294 -0.005071222 -0.08646768 0.1275916 -0.004823982 0.2786682 -0.05722969 -0.004824519 -0.0861907 -0.05773282 -0.004480183 -0.08593589 0.1270886 -0.004479587 0.2789229 0.1266431 -0.004047095 0.2791486 -0.05817848 -0.004047751 -0.0857101 0.1262672 -0.00353831 0.279339 -0.05855458 -0.003538906 -0.08551961 -0.05885082 -0.002967596 -0.08536952 0.1259711 -0.002967059 0.279489 0.125763 -0.002349019 0.2795944 -0.05905908 -0.002349436 -0.08526402 0.1256484 -0.001700997 0.2796525 -0.05917376 -0.001701235 -0.08520597 -0.0589379 2.44928e-4 -0.08532541 -0.05911231 -3.86129e-4 -0.08523708 0.1258842 2.4498e-4 0.279533 -0.0579043 0.001830518 -0.08584898 -0.05832558 0.001368582 -0.0856356 0.1269179 0.001830577 0.2790094 -0.05867326 8.35202e-4 -0.08545947 0.1261489 8.35254e-4 0.279399 0.1264966 0.001368641 0.2792228 -0.05688863 0.00249207 -0.08636349 0.1285002 0.002673625 0.2782079 -0.05632197 0.002673566 -0.08665055 0.1274013 0.00220853 0.2787646 0.1279336 0.002492129 0.2784949 -0.0574209 0.002208471 -0.08609384 0.1302497 0.002570867 0.2773216 -0.05457246 0.002570807 -0.08753675 -0.05514788 0.002713501 -0.08724528 0.1296743 0.002713561 0.2776131 -0.05573642 0.002748072 -0.08694714 0.1290858 0.002748131 0.2779113 -0.05307739 0.001546978 -0.08829408 -0.05352288 0.00197947 -0.08806842 0.1317448 0.001547038 0.2765643 -0.05402582 0.002323865 -0.08781367 0.1307964 0.002323925 0.2770447 0.1312993 0.001979529 0.27679 0.1324167 4.67063e-4 0.2762239 -0.05270153 0.001038193 -0.08848452 0.1321207 0.001038253 0.2763739 0.1326249 -1.50985e-4 0.2761185 -0.05240541 4.67012e-4 -0.08863449 -0.05219727 -1.51036e-4 -0.08873993 0.1327395 -7.99016e-4 0.2760604 -0.05208265 -7.99067e-4 -0.08879798 -0.05510872 -0.004192948 -0.08726513 -0.05468362 -0.00405693 -0.08748042 -0.0549333 -0.005173385 -0.087354 -0.05270153 0.001038193 -0.08848452 -0.05240541 4.67012e-4 -0.08863449 -0.05321115 3.77384e-5 -0.08822637 -0.05436676 -0.00499165 -0.087641 -0.05428433 -0.00384432 -0.08768272 -0.05551886 -0.005248069 -0.08705735 -0.05554795 -0.004248619 -0.08704262 -0.05383461 -0.004707872 -0.08791053 -0.05392163 -0.0035609 -0.08786642 -0.05598938 -0.004222512 -0.08681899 -0.05610746 -0.005213737 -0.0867592 -0.05642092 -0.004115343 -0.08660042 -0.05668294 -0.005071222 -0.08646768 -0.05683082 -0.003930032 -0.08639281 -0.05722969 -0.004824519 -0.0861907 -0.05293035 -0.003867864 -0.08836859 -0.05335146 -0.00432986 -0.08815526 -0.05773282 -0.004480183 -0.08593589 -0.05720788 -0.003671586 -0.08620178 -0.05258285 -0.003334522 -0.0885446 -0.05360555 -0.003214418 -0.08802658 -0.05301523 -0.001898109 -0.08832561 -0.05206483 -0.00145936 -0.08880704 -0.05214416 -0.002114176 -0.08876681 -0.05817848 -0.004047751 -0.0857101 -0.05754184 -0.003347158 -0.08603262 -0.05219727 -1.51036e-4 -0.08873993 -0.05305498 -4.25797e-4 -0.08830547 -0.0574209 0.002208471 -0.08609384 -0.05697274 0.001343846 -0.08632087 -0.05733525 0.001060366 -0.08613723 -0.05352288 0.00197947 -0.08806842 -0.05404925 0.001172065 -0.08780181 -0.05442643 0.001430392 -0.08761078 -0.0537151 8.47743e-4 -0.08797109 -0.05343317 4.66152e-4 -0.0881139 -0.05526798 0.001722574 -0.08718448 -0.05570936 0.001748502 -0.08696085 -0.05514788 0.002713501 -0.08724528 -0.05765122 7.1393e-4 -0.08597719 -0.05867326 8.35202e-4 -0.08545947 -0.05832558 0.001368582 -0.0856356 -0.05614852 0.001692652 -0.0867384 -0.05573642 0.002748072 -0.08694714 -0.05657351 0.001556515 -0.08652311 -0.05632197 0.002673566 -0.08665055 -0.0579043 0.001830518 -0.08584898 -0.05688863 0.00249207 -0.08636349 -0.05483639 0.001615583 -0.08740305 -0.05402582 0.002323865 -0.08781367 -0.05457246 0.002570807 -0.08753675 -0.05911231 -3.86129e-4 -0.08523708 -0.0582413 -6.02115e-4 -0.08567827 -0.05919164 -0.001040697 -0.08519691 -0.05791199 3.1388e-4 -0.08584511 -0.05811053 -1.28824e-4 -0.08574455 -0.0589379 2.44928e-4 -0.08532541 -0.05905908 -0.002349436 -0.08526402 -0.05917376 -0.001701235 -0.08520597 -0.05828738 -0.001588463 -0.08565497 -0.05307739 0.001546978 -0.08829408 -0.05208265 -7.99067e-4 -0.08879798 -0.05296909 -9.11818e-4 -0.08834898 -0.05820155 -0.002073884 -0.08569842 -0.05295568 -0.001407027 -0.08835577 -0.05855458 -0.003538906 -0.08551961 -0.05782359 -0.002965569 -0.08588987 -0.0580455 -0.00253725 -0.08577746 -0.05885082 -0.002967596 -0.08536952 -0.05334466 -0.002814352 -0.08815872 -0.05231839 -0.002744436 -0.08867859 -0.05314606 -0.002371549 -0.08825933 -0.05830079 -0.001093029 -0.08564817 0.1293021 -0.005248129 0.2778016 0.1297152 -0.004192471 0.2775924 0.129276 -0.004248499 0.2778149 0.1316111 3.77898e-5 0.2766321 0.1324167 4.67063e-4 0.2762239 0.1321207 0.001038253 0.2763739 0.1288346 -0.00422275 0.2780385 0.1287136 -0.005213558 0.2780998 0.1298877 -0.005173683 0.277505 0.1301401 -0.004056155 0.2773772 0.1284029 -0.004115879 0.2782572 0.1281382 -0.005070865 0.2783913 0.1304544 -0.004992127 0.277218 0.1305391 -0.003843367 0.277175 0.13147 -0.004330635 0.2767035 0.1309866 -0.004708588 0.2769483 0.1309015 -0.003559827 0.2769915 0.1318913 -0.003868639 0.2764901 0.1275916 -0.004823982 0.2786682 0.1279928 -0.003930807 0.2784649 0.1312174 -0.003213346 0.2768315 0.132239 -0.003335297 0.276314 0.1276155 -0.003672599 0.278656 0.1270886 -0.004479587 0.2789229 0.1269992 -0.002966642 0.2789682 0.1262672 -0.00353831 0.279339 0.1272813 -0.00334829 0.2788254 0.1266431 -0.004047095 0.2791486 0.125763 -0.002349019 0.2795944 0.1266208 -0.002074539 0.2791599 0.1265348 -0.001588404 0.2792035 0.1327574 -0.0014593 0.2760514 0.131807 -0.001898109 0.2765328 0.132678 -0.002113938 0.2760916 0.1265809 -6.02064e-4 0.2791801 0.1257098 -3.86078e-4 0.2796214 0.1256306 -0.001040697 0.2796615 0.1317672 -4.25746e-4 0.276553 0.1326249 -1.50985e-4 0.2761185 0.1278495 0.001343846 0.2785375 0.1269179 0.001830577 0.2790094 0.1274869 0.001060426 0.2787212 0.130773 0.001172125 0.2770566 0.1312993 0.001979529 0.27679 0.1303958 0.001430451 0.2772477 0.1286736 0.001692712 0.2781201 0.1291128 0.001748561 0.2778975 0.1290858 0.002748131 0.2779113 0.1295542 0.001722633 0.277674 0.1296743 0.002713561 0.2776131 0.1279336 0.002492129 0.2784949 0.1282486 0.001556575 0.2783353 0.1285002 0.002673625 0.2782079 0.1307964 0.002323925 0.2770447 0.1299858 0.001615643 0.2774553 0.1302497 0.002570867 0.2773216 0.1269102 3.13932e-4 0.2790133 0.1258842 2.4498e-4 0.279533 0.1267117 -1.28773e-4 0.2791139 0.1271709 7.13982e-4 0.2788813 0.1264966 0.001368641 0.2792228 0.1261489 8.35254e-4 0.279399 0.1265214 -0.001093029 0.2792103 0.1256484 -0.001700997 0.2796525 0.131107 8.47795e-4 0.2768874 0.1317448 0.001547038 0.2765643 0.1327395 -7.99016e-4 0.2760604 0.1318531 -9.11767e-4 0.2765095 0.1318665 -0.001406967 0.2765027 0.126777 -0.002538204 0.2790808 0.1259711 -0.002967059 0.279489 0.1274013 0.00220853 0.2787646 0.1325036 -0.002744972 0.2761799 0.131478 -0.002813339 0.2766995 0.1316763 -0.002370774 0.276599 0.131389 4.66203e-4 0.2767446 -0.05296909 -9.11818e-4 -0.08834898 -0.05295568 -0.001407027 -0.08835577 0.1318665 -0.001406967 0.2765027 -0.05343317 4.66152e-4 -0.0881139 -0.05321115 3.77384e-5 -0.08822637 0.1316111 3.77898e-5 0.2766321 -0.05305498 -4.25797e-4 -0.08830547 0.1318531 -9.11767e-4 0.2765095 0.1317672 -4.25746e-4 0.276553 0.130773 0.001172125 0.2770566 -0.05442643 0.001430392 -0.08761078 -0.05404925 0.001172065 -0.08780181 0.131389 4.66203e-4 0.2767446 0.131107 8.47795e-4 0.2768874 -0.0537151 8.47743e-4 -0.08797109 -0.05526798 0.001722574 -0.08718448 0.1295542 0.001722633 0.277674 -0.05570936 0.001748502 -0.08696085 -0.05483639 0.001615583 -0.08740305 0.1303958 0.001430451 0.2772477 0.1299858 0.001615643 0.2774553 -0.05697274 0.001343846 -0.08632087 -0.05657351 0.001556515 -0.08652311 0.1282486 0.001556575 0.2783353 0.1286736 0.001692712 0.2781201 -0.05614852 0.001692652 -0.0867384 0.1291128 0.001748561 0.2778975 0.1271709 7.13982e-4 0.2788813 -0.05791199 3.1388e-4 -0.08584511 -0.05765122 7.1393e-4 -0.08597719 0.1278495 0.001343846 0.2785375 0.1274869 0.001060426 0.2787212 -0.05733525 0.001060366 -0.08613723 -0.0582413 -6.02115e-4 -0.08567827 0.1265809 -6.02064e-4 0.2791801 -0.05830079 -0.001093029 -0.08564817 -0.05811053 -1.28824e-4 -0.08574455 0.1269102 3.13932e-4 0.2790133 0.1267117 -1.28773e-4 0.2791139 -0.0580455 -0.00253725 -0.08577746 -0.05820155 -0.002073884 -0.08569842 0.1266208 -0.002074539 0.2791599 0.1265348 -0.001588404 0.2792035 -0.05828738 -0.001588463 -0.08565497 0.1265214 -0.001093029 0.2792103 0.1272813 -0.00334829 0.2788254 -0.05720788 -0.003671586 -0.08620178 -0.05754184 -0.003347158 -0.08603262 0.126777 -0.002538204 0.2790808 0.1269992 -0.002966642 0.2789682 -0.05782359 -0.002965569 -0.08588987 -0.05642092 -0.004115343 -0.08660042 0.1284029 -0.004115879 0.2782572 -0.05598938 -0.004222512 -0.08681899 -0.05683082 -0.003930032 -0.08639281 0.1276155 -0.003672599 0.278656 0.1279928 -0.003930807 0.2784649 -0.05554795 -0.004248619 -0.08704262 0.129276 -0.004248499 0.2778149 -0.05510872 -0.004192948 -0.08726513 0.1288346 -0.00422275 0.2780385 0.1297152 -0.004192471 0.2775924 -0.05468362 -0.00405693 -0.08748042 -0.05428433 -0.00384432 -0.08768272 0.1301401 -0.004056155 0.2773772 0.1305391 -0.003843367 0.277175 -0.05392163 -0.0035609 -0.08786642 0.1309015 -0.003559827 0.2769915 -0.05360555 -0.003214418 -0.08802658 -0.05334466 -0.002814352 -0.08815872 0.1312174 -0.003213346 0.2768315 0.131478 -0.002813339 0.2766995 -0.05314606 -0.002371549 -0.08825933 0.1316763 -0.002370774 0.276599 -0.05301523 -0.001898109 -0.08832561 0.131807 -0.001898109 0.2765328 + + + + + + + + + + -0.02938252 0 -0.9995683 -0.8803405 0 -0.4743426 -0.8509604 0 0.5252298 0.02938252 0 0.9995683 0.8803405 0 0.4743426 0.8509604 0 -0.5252298 0 1 0 0 1 1.47752e-6 0 1 1.52887e-6 0 1 -2.08637e-7 0 1 -9.15345e-7 0 1 -2.09224e-7 0 1 -1.93937e-6 0 1 2.20029e-6 0 1 -8.57613e-7 0 1 -3.02115e-7 0 1 -3.6427e-7 0 1 2.18216e-7 0 1 -1.66959e-6 0 1 5.48999e-7 0 1 2.09237e-7 0 1 -3.42195e-6 0 1 3.5325e-6 0 1 -2.99999e-6 0 1 -2.01421e-7 0 1 1.47868e-6 0 1 -3.64358e-7 0 1 -5.87679e-7 0 -1 0 -0.164587 0 0.9863626 0 0 1 -0.6142068 0 0.7891451 -0.4759479 0 0.8794736 -0.3246934 0 0.9458194 -0.8371744 0 0.546936 -0.9157767 0 0.401688 -0.7357248 0 0.6772807 -0.9965868 0 0.08255296 -0.9965868 0 -0.08255296 -0.9694057 0 0.2454643 -0.8371744 0 -0.546936 -0.9157767 0 -0.401688 -0.9694057 0 -0.2454643 -0.6142068 0 -0.7891451 -0.4759479 0 -0.8794736 -0.7357248 0 -0.6772807 -0.164587 0 -0.9863626 0 0 -1 -0.3246934 0 -0.9458194 0.4757679 0 -0.8795709 0.3246294 0 -0.9458414 0.3247846 0 -0.945788 0.1646217 0 -0.9863569 0.735886 0 -0.6771055 0.8369939 -3.05194e-5 -0.5472124 0.7355343 0 -0.6774875 0.4760679 0 -0.8794087 0.6143611 0 -0.7890251 0.6140188 0 -0.7892915 0.9693129 0 -0.2458302 0.969482 0 -0.245163 0.9965563 0 -0.08291918 0.9156397 -3.05193e-5 -0.4020001 0.8373178 0 -0.5467164 0.9158973 0 -0.4014127 0.9966145 0 0.08221703 0.9965563 0 0.08291918 0.969482 0 0.245163 0.9966145 0 -0.08221703 0.9693129 0 0.2458302 0.9158973 0 0.4014127 0.8373178 0 0.5467164 0.9156397 3.05193e-5 0.4020001 0.8369939 3.05194e-5 0.5472124 0.735886 0 0.6771055 0.7355343 0 0.6774875 0.6143611 0 0.7890251 0.4760679 0 0.8794087 0.6140188 0 0.7892915 0.4757679 0 0.8795709 0.3247846 0 0.945788 0.3246294 0 0.9458414 0.1646217 0 0.9863569 0.0293827 -1.56401e-7 0.9995683 0.029383 0 0.9995683 -0.8509603 0 0.5252302 -0.8509603 -1.3767e-7 0.5252301 -0.8803408 0 -0.4743418 -0.8803408 1.5167e-7 -0.4743417 -0.02938264 1.56196e-7 -0.9995684 -0.02938276 1.56354e-7 -0.9995683 0.8509598 0 -0.5252308 0.85096 0 -0.5252308 0.8803412 -2.10039e-7 0.4743412 0.8803412 0 0.4743412 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.2035e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20348e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 -1 -1.20349e-7 0 1 0 1.26148e-7 1 0 0 1 9.15153e-7 1.40215e-7 1 4.80517e-7 0 1 5.07274e-7 0 1 -5.25383e-7 0 1 0 3.18611e-7 1 -2.44687e-7 0 1 0 0 1 0 0 1 3.25532e-7 0 1 0 0 1 3.59138e-7 0 1 5.05662e-7 0 1 0 0 1 0 0 1 -3.12098e-7 0 1 -2.62516e-7 1.58578e-7 1 0 0 1 1.00838e-6 0 1 -5.09961e-7 0 1 5.25362e-7 0 1 0 -2.55285e-7 1 4.04949e-7 2.57877e-7 1 1.36433e-7 0 1 4.93282e-7 0 1 1.21006e-7 2.04803e-7 1 0 2.62424e-7 1 2.32275e-7 0 1 3.93333e-7 0 1 0 -2.60393e-7 1 0 0 1 0 1.8453e-7 1 0 0 1 2.83294e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 4.63715e-7 0 1 1.35857e-7 3.15902e-7 1 2.82742e-7 0.995017 0 -0.09970617 0.997859 0 0.06540286 -0.1476225 0 0.9890438 0.01718199 0 0.9998524 0.9650338 0 -0.2621256 0.9087332 0 -0.4173776 0.8276246 0 -0.5612819 0.7239609 0 -0.6898411 0.6005468 0 -0.7995897 0.4607492 0 -0.8875305 0.3083614 0 -0.9512693 0.1475883 0 -0.9890489 -0.01721251 0 -0.999852 0.973488 0 0.2287382 0.9225497 0 0.3858784 0.8464499 0 0.5324684 0.7472645 0 0.6645267 0.627694 0 0.7784603 0.4910131 0 0.8711522 0.3409318 0 0.9400881 0.1815275 0 0.9833859 -0.6003369 6.10378e-5 0.7997472 -0.4608703 0 0.8874675 -0.4605675 6.10387e-5 0.8876248 -0.3083062 3.05193e-5 0.9512872 -0.3084532 0 0.9512396 -0.8277861 -3.05197e-5 0.5610438 -0.8274632 9.15572e-5 0.56152 -0.9085908 9.1558e-5 0.4176875 -0.6006835 0 0.799487 -0.7237677 9.15582e-5 0.6900437 -0.7241249 0 0.6896688 -0.9949833 6.10382e-5 0.1000416 -0.9978809 6.10381e-5 -0.06506657 -0.9950505 -6.10386e-5 0.09937071 -0.9649425 6.10375e-5 0.2624614 -0.9651151 -6.10388e-5 0.261826 -0.9088587 -3.05191e-5 0.4171045 -0.8466032 3.05192e-5 -0.5322247 -0.9224182 -9.15582e-5 -0.3861925 -0.9226611 3.05194e-5 -0.385612 -0.9734017 -6.10379e-5 -0.2291057 -0.997835 -6.10371e-5 -0.06576746 -0.9735591 6.10382e-5 -0.2284354 -0.6275084 -6.10387e-5 -0.7786098 -0.7470775 -6.10382e-5 -0.6647369 -0.6278461 0 -0.7783375 -0.8462828 -9.1556e-5 -0.532734 -0.7474228 0 -0.6643487 -0.4911217 0 -0.871091 -0.4908349 -6.10377e-5 -0.8712526 -0.3410226 0 -0.9400552 -0.3408681 -3.05191e-5 -0.9401112 -0.181557 0 -0.9833805 -0.1815865 0 -0.983375 0.8333688 -0.3567744 -0.4221474 0.8744488 -0.1977978 -0.4429621 0.8743775 -0.1981922 -0.4429264 -0.2483922 -0.9604561 0.1257984 -0.3860318 -0.9015243 0.1955337 0.8915555 -0.03415089 -0.4516221 0.8915675 -0.03375458 -0.4516282 0.8843714 0.1311389 -0.4479842 0.8844169 0.1308054 -0.4479919 0.8530501 0.2925292 -0.4321253 0.8531475 0.2921955 -0.4321588 0.7986078 0.4456174 -0.404538 0.7984746 0.4459164 -0.4044713 0.7221491 0.5871009 -0.365805 0.7222689 0.586916 -0.3658649 0.6261375 0.7122939 -0.3171584 0.626254 0.7121655 -0.3172165 0.5131444 0.8179974 -0.2599292 0.5130907 0.8180396 -0.2599024 0.3860661 0.9015026 -0.1955661 0.3860318 0.9015243 -0.1955337 0.2483913 0.9604525 -0.1258284 0.2483922 0.9604561 -0.1257984 0.833457 -0.3564983 -0.4222067 0.7695994 -0.505701 -0.3898506 0.7697501 -0.5054251 -0.3899107 0.6848482 -0.6408091 -0.3469104 0.6850308 -0.6405645 -0.3470016 0.5816056 -0.758251 -0.2946024 0.5814192 -0.75843 -0.2945092 0.462147 -0.855352 -0.2340796 0.4623053 -0.8552405 -0.2341741 0.3302149 -0.9289659 -0.1672742 0.330401 -0.9288828 -0.1673673 0.1894621 -0.9771886 -0.09595179 0.1893104 -0.9772239 -0.09589123 0.04324531 -0.9988242 -0.02191257 0.04333668 -0.9988195 -0.02194297 -0.1039788 -0.9931853 0.05264556 -0.1039184 -0.9931915 0.05264586 -0.5131219 -0.8180102 0.2599333 -0.5131444 -0.8179974 0.2599292 -0.7986078 -0.4456174 0.404538 -0.7222689 -0.586916 0.3658649 -0.7985969 -0.4456419 0.4045325 -0.626254 -0.7121655 0.3172165 -0.8844169 -0.1308054 0.4479919 -0.8915555 0.03415089 0.4516221 -0.8531399 -0.2922234 0.432155 -0.8531475 -0.2921955 0.4321588 -0.7695966 0.5057297 0.3898187 -0.7695994 0.505701 0.3898506 -0.8333688 0.3567744 0.4221474 -0.8333598 0.356801 0.4221428 -0.8743829 0.1981629 0.4429291 -0.462123 0.855364 0.2340829 -0.5814192 0.75843 0.2945092 -0.462147 0.855352 0.2340796 -0.6848482 0.6408091 0.3469104 -0.1893104 0.9772239 0.09589123 -0.3302149 0.9289659 0.1672742 -0.04324531 0.9988242 0.02191257 0.1039788 0.9931853 -0.05264556 -0.45188 -2.94749e-5 -0.8920788 -0.4518632 0 -0.8920873 -0.4518768 2.94769e-5 -0.8920805 -0.4518665 2.94726e-5 -0.8920856 -0.4518855 -2.94783e-5 -0.892076 -0.4518983 0 -0.8920695 -0.4519138 -1.4734e-5 -0.8920616 -0.45187 0 -0.8920838 -0.4518855 2.94795e-5 -0.892076 -0.4518955 -7.36658e-6 -0.8920708 -0.4519507 4.42038e-5 -0.892043 -0.4518811 1.10481e-5 -0.8920782 -0.4518582 1.6574e-5 -0.8920899 -0.4519148 0 -0.8920612 -0.4518975 -1.47304e-5 -0.8920699 -0.4519004 0 -0.8920684 -0.451883 0 -0.8920773 -0.4518653 -2.94704e-5 -0.8920862 -0.4518911 7.36723e-6 -0.8920731 -0.4518961 -2.94707e-5 -0.8920707 -0.4518844 2.55559e-5 -0.8920766 -0.4518833 2.94701e-5 -0.8920771 -0.451896 0 -0.8920707 -0.4519026 1.47358e-5 -0.8920673 -0.4518585 4.42038e-5 -0.8920897 -0.4518641 9.20939e-6 -0.8920869 -0.4518809 -2.21023e-5 -0.8920783 -0.4518581 2.20965e-5 -0.89209 -0.4519007 -1.47349e-5 -0.8920683 -0.4518894 0 -0.8920741 -0.4518935 2.76611e-6 -0.892072 -0.4518777 0 -0.89208 -0.4519203 -2.21118e-5 -0.8920584 -0.4518821 0 -0.8920778 -0.4518445 -4.41999e-5 -0.8920968 -0.4519018 -1.10495e-5 -0.8920677 -0.4518483 2.20972e-5 -0.8920949 -0.4518864 1.47311e-5 -0.8920755 -0.4519134 -1.47295e-5 -0.8920618 -0.451898 -2.21118e-5 -0.8920696 -0.4518557 1.10519e-5 -0.8920911 -0.4518804 -2.21044e-5 -0.8920786 -0.4518809 -2.21006e-5 -0.8920784 -0.4518626 2.21003e-5 -0.8920876 -0.4518954 2.20987e-5 -0.8920711 -0.4519155 -4.41966e-5 -0.8920608 -0.451857 4.41952e-5 -0.8920904 -0.4518836 0 -0.8920769 -0.4518772 0 -0.8920802 -0.4518856 -4.41926e-5 -0.892076 -0.4518839 1.47382e-5 -0.8920769 -0.4519005 -1.47401e-5 -0.8920684 -0.4518648 -1.47401e-5 -0.8920864 -0.4519488 2.95066e-5 -0.8920439 -0.4518654 0 -0.8920862 -0.4518949 1.4735e-5 -0.8920713 -0.4518714 0 -0.8920832 -0.4518647 0 -0.8920866 -0.4518853 0 -0.8920761 -0.4519166 -1.10515e-5 -0.8920603 -0.4518435 0 -0.8920972 -0.4519109 0 -0.8920632 -0.4519132 0 -0.892062 -0.4519032 -4.42035e-5 -0.892067 -0.451852 4.4206e-5 -0.892093 -0.4518965 -4.42061e-5 -0.8920704 -0.4518937 -2.94698e-5 -0.8920719 -0.4518883 2.94702e-5 -0.8920747 -0.4518866 -7.36746e-6 -0.8920754 -0.4518783 0 -0.8920797 -0.4518687 -2.21033e-5 -0.8920845 -0.4519012 4.42044e-5 -0.8920681 -0.4519365 4.05225e-5 -0.8920501 -0.4518504 -1.47355e-5 -0.8920938 -0.4519231 2.21034e-5 -0.8920569 -0.4518895 3.31532e-5 -0.8920739 0.4518603 -2.21009e-5 0.8920887 0.4518831 -1.10512e-5 0.8920773 0.4519087 -1.8417e-6 0.8920642 0.4518553 1.10503e-5 0.8920913 0.451909 1.79566e-5 0.8920641 0.4519171 -9.20821e-6 0.8920601 0.4518591 -1.84174e-6 0.8920894 0.4518153 -1.93414e-5 0.8921115 0.4518733 4.60449e-6 0.8920823 0.4519169 8.28942e-6 0.8920601 0.4518714 -1.10507e-5 0.8920831 0.4518488 -2.07153e-5 0.8920946 0.4518179 -2.7628e-6 0.8921102 0.4519941 2.76182e-6 0.892021 0.4518283 9.68235e-6 0.8921049 0.4519063 -4.60467e-6 0.8920655 0.4518697 -5.5257e-6 0.8920841 0.4519161 1.10515e-5 0.8920605 0.4518483 -9.20967e-6 0.8920949 0.4518731 -2.34844e-5 0.8920823 0.4518733 -5.52574e-6 0.8920822 0.4518823 1.10512e-5 0.8920776 0.4518958 1.6577e-5 0.8920708 0.451947 -1.84185e-6 0.8920449 0.4518922 1.84187e-5 0.8920726 0.4518026 8.28894e-6 0.892118 0.4519166 1.84185e-6 0.8920603 0.4518452 -1.10517e-5 0.8920964 0.4518595 -4.6048e-6 0.8920891 0.4518624 2.76287e-6 0.8920876 0.4518532 3.68391e-6 0.8920924 0.4518674 -9.66733e-6 0.8920853 0.4518924 -1.10512e-5 0.8920724 0.4518561 2.76292e-6 0.8920909 0.451839 1.0363e-5 0.8920995 0.4519085 -8.29088e-6 0.8920643 0.4518578 5.5242e-6 0.89209 0.4518821 2.76284e-6 0.8920778 0.45191 1.84188e-6 0.8920636 0.4519019 5.52393e-6 0.8920676 0.4519432 -1.38111e-6 0.8920468 0.4518844 -1.3812e-5 0.8920766 0.4518992 1.65749e-5 0.892069 0.4519093 0 0.8920639 0.4518567 -2.76277e-6 0.8920906 0.4519046 -8.28838e-6 0.8920663 0.4519057 5.52587e-6 0.8920658 0.4518851 2.76308e-6 0.8920762 0.4518598 8.28979e-6 0.8920891 0.4519387 8.28819e-6 0.8920491 0.4518684 -2.76284e-6 0.8920846 0.4518654 3.68377e-6 0.8920862 0.4519152 1.84185e-6 0.8920609 0.4519262 3.68366e-6 0.8920554 0.4518939 -9.20939e-6 0.8920717 0.4518705 3.68381e-6 0.8920836 0.4518984 9.20941e-7 0.8920695 0.4519066 -2.76281e-6 0.8920654 0.451964 -1.01299e-5 0.8920363 0.4518721 -2.76286e-6 0.8920828 0.4518821 -5.52585e-6 0.8920777 0.4517934 -5.52585e-6 0.8921227 0.4519441 2.76276e-6 0.8920463 0.4519064 0 0.8920654 0.4518726 -1.10515e-5 0.8920825 0.4518729 1.65772e-5 0.8920823 0.4518945 -1.6577e-5 0.8920715 0.4518762 0 0.8920807 0.4519187 -4.60465e-6 0.8920592 0.4518705 5.52571e-6 0.8920836 0.4519354 0 0.8920508 0.4518035 0 0.8921175 0.4519407 -4.60457e-6 0.8920481 0.451897 2.76284e-6 0.8920702 0.4518713 -4.14429e-6 0.8920832 0.4518706 -2.76286e-6 0.8920835 -0.2483913 -0.9604525 0.1258284 0.04324537 -0.9988249 -0.02188205 0.6848616 -0.6407911 -0.3469172 0.462123 -0.855364 -0.2340829 0.8333598 -0.356801 -0.4221428 0.8743953 -0.1981283 -0.4429199 0.8531399 0.2922234 -0.432155 0.7222965 0.5868831 -0.3658635 0.7985969 0.4456419 -0.4045325 0.5131219 0.8180102 -0.2599333 0.6262354 0.7121791 -0.3172226 -0.1891587 0.9772592 0.09583061 -0.04321491 0.9988262 0.02188211 -0.04333668 0.9988195 0.02194297 0.1039184 0.9931915 -0.05264586 0.1039486 0.9931885 -0.05264568 -0.4623293 0.8552285 0.2341707 -0.5811843 0.7586556 0.2943918 -0.4619079 0.8555138 0.23396 -0.1894326 0.9771941 0.09595233 -0.330401 0.9288828 0.1673673 -0.3300287 0.9290488 0.1671811 -0.7694576 0.5059828 0.3897645 -0.7697501 0.5054251 0.3899107 -0.8332441 0.3571395 0.422085 -0.6846432 0.6410918 0.3467926 -0.5816056 0.758251 0.2946024 -0.6850011 0.6405958 0.3470021 -0.8743115 0.1985573 0.4428933 -0.8744559 0.1977925 0.4429503 -0.8915453 0.03448617 0.451617 -0.8334754 0.3564625 0.4222006 -0.8915666 0.0337851 0.4516278 -0.8844467 -0.1305001 0.448022 -0.8532061 -0.2919811 0.4321881 -0.884375 -0.1311089 0.4479861 -0.853066 -0.2924937 0.4321179 -0.7986853 -0.4454571 0.4045614 -0.7985073 -0.4458566 0.4044725 -0.7223614 -0.5867641 0.3659265 -0.6263198 -0.7120794 0.31728 -0.7221491 -0.5871009 0.365805 -0.6261053 -0.7123226 0.3171575 -0.5132109 -0.8179451 0.2599626 -0.5131132 -0.8180269 0.2598984 -0.3860661 -0.9015026 0.1955661 0.8437101 0.324788 -0.4273943 0.8799066 0.1646525 -0.4457062 0.8920711 0 -0.4518952 0.7038697 0.6143562 -0.3565585 0.6040403 0.7358843 -0.3059571 0.784498 0.4760702 -0.3973915 0.2186962 0.969484 -0.1107825 0.3580793 0.9159054 -0.1813743 0.487721 0.837314 -0.2470497 -0.2192804 0.9693203 0.1110594 -0.07394689 0.9965589 0.03744643 0.07333618 0.9966155 -0.03714114 -0.4881579 0.8369948 0.2472682 -0.6043688 0.7355398 0.3061366 -0.3586038 0.9156451 0.1816518 -0.8437696 0.3246347 0.4273936 -0.7846516 0.4757656 0.3974531 -0.7041074 0.6140148 0.3566774 -0.8799034 -0.1645908 0.4457352 -0.8920711 0 0.4518952 -0.879911 0.1646228 0.4457085 -0.7845576 -0.4759472 0.3974213 -0.7039896 -0.6142017 0.356588 -0.8437441 -0.3246977 0.4273961 -0.3583242 -0.9157853 0.1814968 -0.4879119 -0.8371746 0.2471452 -0.6041881 -0.7357258 0.3060463 0.07364153 -0.9965873 -0.03729379 -0.07364153 -0.9965873 0.03729379 -0.2189742 -0.9694072 0.1109062 0.2189742 -0.9694072 -0.1109062 0.3583242 -0.9157853 -0.1814968 0.4879119 -0.8371746 -0.2471452 0.6041881 -0.7357258 -0.3060463 0.7039896 -0.6142017 -0.356588 0.7845576 -0.4759472 -0.3974213 0.8437441 -0.3246977 -0.4273961 0.8799034 -0.1645908 -0.4457352 0.4518905 -5.34874e-7 0.8920735 0.4518883 -2.46823e-6 0.8920745 0.4518932 -3.69025e-6 0.892072 0.4518921 0 0.8920727 0.4518911 0 0.8920732 0.4518866 3.70476e-6 0.8920755 0.4518921 -3.39609e-6 0.8920727 0.4518862 -2.71609e-6 0.8920756 0.4518914 0 0.892073 0.4518847 2.71853e-6 0.8920764 0.4518877 -1.02337e-6 0.8920749 0.4518914 -6.79348e-7 0.8920731 0.451884 2.72127e-6 0.8920767 0.4518873 -1.23221e-6 0.8920751 0.4518921 -1.37296e-6 0.8920726 0.4518842 2.45835e-6 0.8920767 0.451889 1.23026e-6 0.8920742 0.4518821 -6.83518e-7 0.8920777 0.4518856 1.35873e-6 0.8920759 0.4518939 6.16802e-7 0.8920718 0.4518901 -4.10992e-6 0.8920737 0.4518842 -2.46336e-6 0.8920767 0.4518824 2.30349e-6 0.8920775 0.4518792 1.37718e-6 0.8920792 0.4518883 -9.18094e-7 0.8920746 0.4518825 -1.23207e-6 0.8920776 0.4518843 -2.03747e-6 0.8920766 0.4518859 3.40202e-7 0.8920757 0.4518886 1.36453e-6 0.8920744 0.4518948 6.79157e-7 0.8920713 0.451891 -2.43975e-6 0.8920732 0.4518848 -9.24599e-7 0.8920763 0.451887 0 0.8920753 0.4518829 0 0.8920773 0.4518865 1.22792e-6 0.8920755 0.4518844 4.93324e-6 0.8920765 0.4518909 1.21988e-6 0.8920732 0.4518979 0 0.8920698 0.4518859 1.35843e-6 0.8920758 0.4518864 0 0.8920755 0.4518834 -1.6304e-6 0.892077 0.4518819 1.75297e-6 0.8920778 0.4518895 -1.36289e-6 0.8920739 0.4518826 0 0.8920775 0.4518843 -1.35985e-6 0.8920767 0.4518842 -1.23329e-6 0.8920767 0.4518955 1.23221e-6 0.8920709 0.4518868 -1.23276e-6 0.8920754 0.4518892 0 0.8920741 0.4518845 0 0.8920765 0.4518873 -1.21722e-6 0.8920751 0.4518802 1.02735e-6 0.8920787 0.451889 -4.0928e-6 0.8920743 0.4518832 3.74121e-6 0.8920772 0.4518924 0 0.8920725 0.4518867 -3.70314e-6 0.8920754 0.451893 -6.16128e-7 0.8920723 0.4519002 -3.07258e-7 0.8920685 0.4518867 2.29642e-6 0.8920754 0.4518897 -2.66755e-7 0.8920738 0.4518837 -1.37335e-6 0.892077 0.4518882 1.36704e-6 0.8920747 0.4518902 0 0.8920737 0.4518854 0 0.892076 0.4518864 1.85131e-6 0.8920755 0.45189 -1.23307e-6 0.8920738 0.451887 6.15368e-7 0.8920752 0.4518856 -2.45454e-6 0.8920759 0.4518901 1.22262e-6 0.8920736 0.4518852 0 0.8920762 0.4518923 2.91118e-6 0.8920725 0.4518983 -2.72905e-6 0.8920695 0.4518776 6.80407e-7 0.89208 0.4518924 -1.23378e-6 0.8920725 0.4518882 0 0.8920746 0.4518933 1.36247e-6 0.892072 0.4518904 2.71909e-6 0.8920735 0.4518952 0 0.8920711 0.4518889 0 0.8920743 0.4518975 0 0.8920699 0.7888656 0.2924369 -0.5405292 0.8152035 0.1631261 -0.5557277 0.7790715 0.3219808 -0.5379368 0.8274155 0 -0.5615903 0.81807 0.1477439 -0.5558176 0.8277957 0 -0.5610296 0.6400569 0.6092626 -0.4681094 0.5410131 0.7298045 -0.4179598 0.5920988 0.6750494 -0.4401448 0.6745995 0.5590533 -0.482053 0.7406814 0.4305712 -0.5157516 0.7201339 0.4720728 -0.5084824 0.3856381 0.8593845 -0.33577 0.2971975 0.9084085 -0.294054 0.2663103 0.9236322 -0.2756491 0.4950531 0.7758915 -0.3910434 0.4256817 0.8304272 -0.3594245 -0.1306229 0.988492 -0.07629841 -0.1231143 0.9892175 -0.07931929 0.01513755 0.9885513 -0.1501245 0.1397761 0.9672325 -0.2119531 0.1590965 0.9615984 -0.2236446 -0.4134371 0.9081456 0.06588989 -0.542047 0.8301153 0.1307431 -0.4992657 0.8591192 0.1124637 -0.2537956 0.9671763 -0.01257377 -0.2750416 0.961425 -0.00375384 -0.3801191 0.9234865 0.05179136 -0.7055196 0.6746033 0.2171463 -0.756301 0.6089229 0.239211 -0.7880161 0.5586003 0.2588368 -0.6085561 0.7755275 0.1679785 -0.6573899 0.7294464 0.1890682 -0.9320866 0.1477434 0.3307365 -0.9025414 0.2922204 0.3162695 -0.9303229 0.1630957 0.3284803 -0.8946464 0.3218578 0.3098637 -0.8541939 0.4301335 0.292127 -0.8361321 0.4717644 0.2798603 -0.9303275 -0.1630659 0.3284819 -0.9024912 -0.2924375 0.3162122 -0.9320866 -0.1477434 0.3307365 -0.9420405 0 0.3354991 -0.9422704 0 0.3348532 -0.7877415 -0.5590581 0.2586842 -0.7561754 -0.6091032 0.2391488 -0.7051457 -0.6750538 0.2169609 -0.8540101 -0.4305605 0.2920352 -0.8946375 -0.3218852 0.3098606 -0.8360393 -0.4719468 0.2798293 -0.3797807 -0.9236326 0.05166894 -0.4988602 -0.8593788 0.1122786 -0.4131415 -0.9082888 0.06576937 -0.5417987 -0.830292 0.1306506 -0.6081327 -0.7758988 0.1677965 -0.6571947 -0.7296468 0.1889732 -0.1302877 -0.9885267 -0.07642084 0.008850514 -0.9892175 -0.1461867 -0.1230539 -0.9892226 -0.07935023 -0.2747352 -0.9615121 -0.003875911 -0.2535805 -0.9672314 -0.01266527 0.01544278 -0.9885233 -0.1502775 0.1399902 -0.9671747 -0.2120758 0.1593728 -0.9615166 -0.2237994 0.2974423 -0.9082887 -0.2941768 0.2666485 -0.9234883 -0.2758044 0.4258607 -0.8302972 -0.3595126 0.3860391 -0.8591195 -0.3359875 0.4954518 -0.7755283 -0.3912586 0.5411605 -0.729645 -0.4180474 0.6401701 -0.6091015 -0.468164 0.5924718 -0.6745993 -0.4403329 0.7202048 -0.4719572 -0.5084894 0.6748705 -0.5586229 -0.4821724 0.7408652 -0.4301444 -0.5158436 0.7790936 -0.3218858 -0.5379616 0.8152219 -0.1630626 -0.5557194 0.7889249 -0.2922226 -0.5405585 0.81807 -0.1477439 -0.5558176 0.008789539 0.9892224 -0.1461569 -0.06634771 -0.9972307 0.0336011 0.06695878 -0.9971795 -0.03390663 0.8821017 0.1491177 -0.4468342 -0.1982522 -0.9749945 0.1004079 -0.325793 -0.9309287 0.1650176 -0.4460077 -0.8660435 0.2259336 -0.5561529 -0.7818735 0.2817234 -0.6537835 -0.6803657 0.3311644 -0.73688 -0.563624 0.3732773 -0.8035997 -0.4341959 0.4070644 -0.8523712 -0.2949988 0.4317859 -0.8523826 -0.2950026 0.4317611 -0.8820936 -0.1491773 0.4468302 0.19874 -0.9748701 -0.1006518 0.3259795 -0.9308469 -0.1651108 0.4460439 -0.8660241 -0.2259365 0.5563018 -0.7817462 -0.2817826 0.6541123 -0.6799619 -0.3313441 0.7372504 -0.5630167 -0.3734624 0.8038805 -0.4335583 -0.4071896 0.8524855 -0.2946298 -0.4318125 0.8821017 -0.1491177 -0.4468342 0.8524026 0.2949075 -0.4317863 0.6537525 0.6803957 -0.3311641 0.736946 0.5635362 -0.3732798 0.803654 0.4340702 -0.4070915 0.4458261 0.8661685 -0.2258123 0.3257308 0.930956 -0.1649864 0.5559955 0.7820192 -0.2816295 0.5559743 0.7820324 -0.2816342 -0.06668359 0.9972021 0.03378427 0.06662285 0.9972072 -0.03375393 0.1984029 0.9749546 -0.1004985 -0.4462285 0.8659049 0.2260289 -0.3260673 0.9308056 0.16517 -0.1985888 0.9749072 0.1005914 -0.6541259 0.6799455 0.3313509 -0.7372195 0.5630775 0.3734318 -0.5563952 0.7816573 0.2818447 -0.8038378 0.4336433 0.4071834 -0.8524694 0.2946653 0.4318197 -0.8821057 0.1490878 0.4468362 -0.8820936 0.1491773 0.4468302 -0.8523712 0.2949988 0.4317859 -0.73688 0.563624 0.3732773 -0.653766 0.6803793 0.331171 -0.8038479 0.4336487 0.407158 -0.8035997 0.4341959 0.4070644 -0.4460077 0.8660435 0.2259336 -0.325793 0.9309287 0.1650176 -0.5561529 0.7818735 0.2817234 0.06698918 0.9971775 -0.03390657 -0.06631737 0.9972327 0.03360116 -0.1982516 0.9749916 0.1004381 0.3259795 0.9308469 -0.1651108 0.4460439 0.8660241 -0.2259365 0.445823 0.8661626 -0.2258413 0.19874 0.9748701 -0.1006518 0.7369235 0.5635424 -0.3733144 0.654119 0.6799688 -0.3313169 0.7372587 0.5630231 -0.3734362 0.5563018 0.7817462 -0.2817826 0.8524931 0.2946019 -0.4318163 0.8038805 0.4335583 -0.4071896 0.8036432 0.4340808 -0.4071015 0.8524026 -0.2949075 -0.4317863 0.8524694 -0.2946653 -0.4318197 0.8821057 -0.1490878 -0.4468362 0.6541259 -0.6799455 -0.3313509 0.736946 -0.5635362 -0.3732798 0.653759 -0.6804025 -0.331137 0.7372195 -0.5630775 -0.3734318 0.803827 -0.433654 -0.4071934 0.803654 -0.4340702 -0.4070915 0.3257308 -0.930956 -0.1649864 0.3260673 -0.9308056 -0.16517 0.4458261 -0.8661685 -0.2258123 0.5559955 -0.7820192 -0.2816295 0.4462285 -0.8659049 -0.2260289 0.5563952 -0.7816573 -0.2818447 0.06662285 -0.9972072 -0.03375393 -0.06668359 -0.9972021 0.03378427 -0.06662285 -0.9972072 0.03375393 0.1985888 -0.9749072 -0.1005914 0.1984035 -0.9749575 -0.1004683 0.06668359 -0.9972021 -0.03378427 -0.1984029 -0.9749546 0.1004985 -0.3257308 -0.930956 0.1649864 -0.1985888 -0.9749072 0.1005914 -0.3260673 -0.9308056 0.16517 -0.4458261 -0.8661685 0.2258123 -0.4462285 -0.8659049 0.2260289 -0.5559955 -0.7820192 0.2816295 -0.653759 -0.6804025 0.331137 -0.5563952 -0.7816573 0.2818447 -0.6541259 -0.6799455 0.3313509 -0.736946 -0.5635362 0.3732798 -0.7372195 -0.5630775 0.3734318 -0.803654 -0.4340702 0.4070915 -0.8524026 -0.2949075 0.4317863 -0.803827 -0.433654 0.4071934 -0.8524694 -0.2946653 0.4318197 -0.8821017 -0.1491177 0.4468342 -0.8821057 -0.1490878 0.4468362 -0.1393216 -0.967042 0.2131179 -0.02911549 -0.9873641 0.155771 -0.008240222 -0.9890732 0.1471951 0.942128 -1.83115e-4 -0.3352535 0.9421184 -1.52594e-4 -0.3352806 0.9334368 0.13749 -0.3313494 -0.2660373 -0.9233635 0.2768107 -0.1500007 -0.964491 0.2173866 -0.2670099 -0.9229832 0.2771422 -0.3848511 -0.8591855 0.3371796 -0.4808894 -0.787881 0.3846932 -0.3777948 -0.8639016 0.3330845 -0.4938917 -0.7755835 0.3931174 -0.5732673 -0.6967468 0.4311712 -0.6533886 -0.5922889 0.4714628 -0.5905822 -0.674877 0.4424407 -0.6729078 -0.5590424 0.4844241 -0.7198057 -0.476381 0.5049169 -0.7389937 -0.4306575 0.5180952 -0.7712739 -0.3511506 0.5308765 -0.8067482 -0.2190373 0.5487987 -0.7873273 -0.292585 0.5426876 -0.8167893 -0.1479272 0.5576496 -0.8240469 -0.09589105 0.5583474 -0.8266733 0 0.5626823 -0.8277957 0 0.5610296 0.09357172 -0.9912316 0.093297 0.1241508 -0.9889945 0.08047825 0.2549564 -0.9668444 0.01446604 0.2157717 -0.9759476 0.03112971 0.3349438 -0.9417797 -0.02938956 0.3812134 -0.9231707 -0.04931873 0.4486607 -0.8894475 -0.08710139 0.5003311 -0.8588702 -0.1095943 0.6097041 -0.7752684 -0.1649845 0.5547522 -0.8199968 -0.1409083 0.6512263 -0.7347888 -0.1897096 0.7066828 -0.6743319 -0.2141869 0.7363884 -0.6352795 -0.2327059 0.7891041 -0.558318 -0.256117 0.8550989 -0.4298995 -0.2898144 0.808501 -0.5233846 -0.2690629 0.866063 -0.4014445 -0.2979552 0.9031875 -0.2921 -0.3145316 0.9079394 -0.2720156 -0.3188317 0.9323503 -0.147589 -0.3300612 0.9335443 -0.1372132 -0.3311612 0.9031067 0.2923781 -0.3145049 0.9324218 0.1477433 -0.3297902 0.9078212 0.272444 -0.3188025 0.7063387 0.6747512 -0.2140013 0.7887795 0.5588447 -0.255968 0.7363089 0.6353815 -0.2326792 0.854862 0.4304371 -0.2897149 0.8658134 0.4020665 -0.2978418 0.808266 0.5237981 -0.2689642 0.5001137 0.8590164 -0.1094409 0.4481474 0.8897331 -0.08682775 0.3809748 0.9232756 -0.04919737 0.6511227 0.7348973 -0.189645 0.5544115 0.8202642 -0.1406934 0.6094009 0.7755456 -0.1648019 0.2155253 0.9759981 0.03125143 0.09351122 0.9912372 0.09329754 0.1237848 0.9890278 0.08063107 0.3344278 0.9419707 -0.02914565 0.2545908 0.9669384 0.01461863 -0.2675607 0.922805 0.2772047 -0.2661269 0.923265 0.2770528 -0.1505508 0.9643431 0.2176623 -0.1396237 0.9669592 0.2132962 -0.008606433 0.9890428 0.1473783 -0.02935886 0.9873383 0.155889 -0.4941691 0.7753438 0.3932417 -0.5733699 0.6966382 0.4312101 -0.5909232 0.6744557 0.4426277 -0.3783438 0.8636261 0.3331757 -0.4809832 0.7877932 0.384756 -0.3850601 0.8589616 0.3375113 -0.6732317 0.5585085 0.4845901 -0.6536232 0.5919139 0.4716085 -0.7200812 0.4758017 0.5050701 -0.7392324 0.430105 0.5182135 -0.7714141 0.3507316 0.53095 -0.7874264 0.292252 0.5427233 -0.8168104 0.147834 0.5576431 -0.806775 0.2189447 0.5487962 -0.8240469 0.09589105 0.5583474 -0.4518875 8.30093e-7 -0.8920751 -0.451887 8.25198e-7 -0.8920752 -0.4518868 -2.99923e-7 -0.8920754 -0.4518867 2.24724e-7 -0.8920754 -0.4518887 -3.00475e-7 -0.8920745 -0.451889 1.93425e-6 -0.8920742 -0.4518908 5.49962e-7 -0.8920734 -0.4518873 -5.48585e-7 -0.892075 -0.4518865 1.20147e-6 -0.8920755 -0.4518882 0 -0.8920747 -0.4518896 -1.80325e-6 -0.8920739 -0.4518867 1.21015e-6 -0.8920754 -0.4518874 1.52206e-6 -0.892075 -0.4518868 -1.20365e-6 -0.8920754 -0.451887 2.41264e-6 -0.8920753 -0.451885 0 -0.8920763 -0.451889 2.40382e-6 -0.8920742 -0.4518867 4.5142e-7 -0.8920754 -0.4518886 2.22137e-6 -0.8920744 -0.4518873 -2.50699e-6 -0.8920751 -0.4518879 -1.13698e-6 -0.8920748 -0.4518874 -1.50476e-7 -0.892075 -0.451887 0 -0.8920752 -0.4518889 6.00188e-7 -0.8920742 -0.451887 -5.50424e-7 -0.8920753 -0.4518874 -1.10551e-6 -0.892075 -0.4518871 2.87048e-7 -0.8920753 -0.4518883 5.48078e-7 -0.8920746 -0.4518882 0 -0.8920746 -0.4518915 6.076e-7 -0.892073 -0.4518882 -1.09281e-6 -0.8920746 -0.4518881 9.8044e-7 -0.8920748 -0.4518875 1.66522e-6 -0.892075 -0.4518883 1.20133e-6 -0.8920745 -0.451887 9.02369e-7 -0.8920752 -0.4518879 -3.00015e-7 -0.8920747 -0.4518878 -1.03777e-6 -0.8920748 -0.4518877 -1.42566e-6 -0.892075 -0.4518874 2.75673e-7 -0.8920751 -0.4518882 -9.66175e-7 -0.8920747 -0.4518868 -7.22718e-7 -0.8920754 -0.4518864 0 -0.8920756 -0.4518889 5.53089e-7 -0.8920742 -0.4518861 1.05553e-6 -0.8920757 -0.4518884 -4.53649e-7 -0.8920745 -0.451887 8.19649e-7 -0.8920753 -0.4518861 0 -0.8920758 -0.451889 0 -0.8920742 -0.4518861 -5.53204e-7 -0.8920758 -0.451889 0 -0.8920742 -0.4518861 1.1021e-6 -0.8920757 -0.4518874 0 -0.8920751 -0.451888 0 -0.8920747 -0.4518878 1.09374e-6 -0.8920748 -0.451888 6.07661e-7 -0.8920747 -0.4518868 -3.02575e-7 -0.8920753 -0.4518864 1.4324e-6 -0.8920755 -0.4518896 0 -0.892074 -0.4518857 9.57046e-7 -0.8920758 -0.451889 -2.76689e-7 -0.8920742 -0.4518867 2.76544e-7 -0.8920755 -0.4518879 2.76741e-7 -0.8920747 -0.4518872 -1.03736e-6 -0.8920752 -0.451887 -2.06953e-7 -0.8920753 -0.4518881 -5.15855e-7 -0.8920747 -0.4518865 2.03944e-6 -0.8920754 -0.451887 -8.83685e-7 -0.8920753 -0.4518876 3.03637e-7 -0.892075 -0.4518883 4.54818e-7 -0.8920747 -0.4518883 -1.50913e-7 -0.8920745 -0.4518884 -1.5052e-7 -0.8920745 -0.4518882 0 -0.8920747 -0.4518884 1.38566e-7 -0.8920746 -0.4518885 8.30783e-7 -0.8920745 -0.4518873 1.10639e-6 -0.8920751 -0.4518884 5.52329e-7 -0.8920745 -0.4518875 1.10257e-6 -0.8920751 -0.451889 1.10297e-6 -0.8920742 -0.451887 1.09888e-6 -0.8920753 -0.4518865 2.43196e-6 -0.8920755 -0.4518882 -6.05576e-7 -0.8920747 -0.4518886 -1.10431e-6 -0.8920745 -0.4518863 1.80281e-6 -0.8920755 -0.4518884 0 -0.8920746 -0.451888 0 -0.8920747 -0.4518878 1.67174e-6 -0.8920748 -0.4518863 0 -0.8920757 -0.4518867 0 -0.8920755 0.8834609 0.1386168 -0.4475291 0.8834551 0.1387122 -0.447511 0.8578556 0.2743038 -0.4345585 0.8157487 0.4047156 -0.4132305 0.857757 0.2747386 -0.4344788 0.7577981 0.5276203 -0.3838737 0.8155067 0.4053575 -0.413079 0.7575839 0.5280167 -0.3837513 0.6851837 0.6403511 -0.3470934 0.599405 0.7406191 -0.3036395 0.685096 0.6404769 -0.3470343 0.5021914 0.8264871 -0.254407 0.5993033 0.7407287 -0.3035733 0.5018536 0.8267583 -0.2541923 0.3952838 0.8964689 -0.200236 0.2806223 0.9492326 -0.1421575 0.3947619 0.8967672 -0.1999292 0.1604686 0.9836868 -0.08130246 0.2801345 0.9494177 -0.1418831 0.1602576 0.9837337 -0.08115124 0.03720259 0.9991304 -0.01883018 -0.0865516 0.9952831 0.04382514 0.03717213 0.9991316 -0.01883018 -0.2085695 0.9722869 0.1056276 -0.08679598 0.9952551 0.04397785 -0.2090837 0.9721435 0.1059305 -0.3267069 0.9305272 0.1654745 -0.4386466 0.8707621 0.2221767 -0.3272553 0.9302803 0.1657792 -0.5421676 0.7941312 0.2746087 -0.4390147 0.8705218 0.2223914 -0.5422711 0.7940268 0.2747063 -0.6351042 0.7022464 0.3217027 -0.7156971 0.5969484 0.3625332 -0.6352008 0.7021299 0.3217663 -0.7825366 0.4801242 0.3963802 -0.715954 0.5965622 0.3626617 -0.7828249 0.4795222 0.3965397 -0.8343445 0.3539051 0.4226352 -0.8700684 0.220775 0.4407261 -0.8344846 0.3534726 0.4227205 -0.8816645 0.1524121 0.4465851 -0.870086 0.2206879 0.4407349 0.8834609 -0.1386168 -0.4475291 0.8578671 -0.2743075 -0.4345338 0.8834551 -0.1387122 -0.447511 0.815759 -0.4047207 -0.4132052 0.8577455 -0.2747349 -0.4345036 0.8154964 -0.4053524 -0.4131042 0.7578111 -0.5276082 -0.3838648 0.6851837 -0.6403511 -0.3470934 0.757575 -0.5280106 -0.3837774 0.5994246 -0.7406057 -0.303634 0.685096 -0.6404769 -0.3470343 0.5993033 -0.7407287 -0.3035733 0.5022181 -0.8264809 -0.2543746 0.3952862 -0.8964743 -0.2002066 0.5018497 -0.826752 -0.2542209 0.2806515 -0.9492285 -0.1421264 0.3947337 -0.8967726 -0.199961 0.2801052 -0.9494217 -0.1419143 0.1604987 -0.9836845 -0.08127176 0.03720259 -0.9991304 -0.01883018 0.1602275 -0.9837361 -0.08118194 -0.08655148 -0.9952816 0.0438556 0.03717213 -0.9991316 -0.01883018 -0.0867961 -0.9952564 0.04394739 -0.2085688 -0.9722837 0.1056578 -0.3267053 -0.9305225 0.1655042 -0.2090844 -0.9721466 0.1059003 -0.4386436 -0.8707563 0.2222058 -0.3272842 -0.9302756 0.1657478 -0.4390177 -0.8705278 0.2223623 -0.5421415 -0.7941378 0.2746415 -0.6351042 -0.7022464 0.3217027 -0.5422757 -0.7940334 0.2746781 -0.7156971 -0.5969484 0.3625332 -0.6352008 -0.7021299 0.3217663 -0.715954 -0.5965622 0.3626617 -0.7825153 -0.4801299 0.3964154 -0.8343445 -0.3539051 0.4226352 -0.7828249 -0.4795222 0.3965397 -0.8700684 -0.220775 0.4407261 -0.8344954 -0.3534771 0.4226954 -0.870086 -0.2206879 0.4407349 -0.8816645 -0.1524121 0.4465851 0.4518879 0 0.8920747 0.4518877 0 0.8920748 0.8055503 0 -0.5925274 0.4262908 0 -0.9045862 0.5694512 0 -0.8220252 0.6970567 0 -0.7170161 0.1097146 0 -0.9939631 -0.05557477 0 -0.9984546 0.2718015 0 -0.9623534 -0.3766308 0 -0.9263635 -0.5240412 0 -0.8516929 -0.2190982 0 -0.9757028 -0.8662567 0 -0.4995992 -0.7721566 0 -0.6354323 -0.657045 0 -0.7538515 -0.9815452 0 -0.1912307 -0.9996286 0 -0.02725368 -0.936695 0 -0.3501467 -0.954311 0 0.2988154 -0.8920834 0 0.4518709 -0.9904653 0 0.137763 -0.5694306 0 0.8220395 -0.6969329 0 0.7171364 -0.8054998 0 0.5925961 -0.2718015 0 0.9623534 -0.1096845 0 0.9939665 -0.4266244 0 0.904429 0.2190691 0 0.9757093 0.3766308 0 0.9263635 0.05545306 0 0.9984613 0.5240412 0 0.8516929 0.6570125 0 0.7538797 0.772102 0 0.6354987 0.8662908 0 0.4995402 0.936685 0 0.3501734 0.9815384 0 0.1912658 0.9996319 0 0.02713173 0.9904778 0 -0.1376731 0.9542821 0 -0.2989075 -0.8920745 0 0.4518884 -0.8920747 0 0.4518883 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.8920742 0 -0.4518889 0.892074 0 -0.4518896 0 -1 0 0 -1 -3.82155e-7 0 -1 4.73332e-7 0 -1 0 0 -1 0 0 -1 -4.7333e-7 -0.8336713 -0.3558881 0.4222986 -0.8698384 -0.2219078 0.4406111 -0.881574 -0.1530226 0.4465551 -0.713264 -0.6005871 0.3613167 -0.63129 -0.7065505 0.3197804 -0.7811766 -0.4828792 0.3957156 -0.3186836 -0.9340158 0.1614171 -0.4319659 -0.8749492 0.2187907 -0.5368886 -0.7986187 0.2719539 0.04934966 -0.9984688 -0.02499526 -0.07565754 -0.9963968 0.03833234 -0.1991692 -0.9747571 0.1008969 0.2942321 -0.9440394 -0.149054 0.4091045 -0.8886463 -0.2072226 0.1734997 -0.9809066 -0.0878638 0.1734992 -0.9809041 -0.08789408 0.5158146 -0.815885 -0.2612798 0.6124573 -0.727087 -0.3102266 0.6971222 -0.6239674 -0.3531085 0.7681216 -0.5085204 -0.3890966 0.8240435 -0.383044 -0.4174084 0.8459933 -0.317278 -0.4285207 9.06667e-7 -1 0 0 -1 0 0 -1 0 0 -1 -1.44085e-7 -1.72124e-6 -1 -5.23419e-7 1.33265e-7 -1 0 0 -1 -4.34694e-7 0 -1 1.75221e-7 0 -1 -3.64173e-7 0 -1 3.14111e-7 0 -1 2.50394e-7 0 -1 0 0 -1 0 0 -1 -1.61124e-7 0 -1 -3.73179e-6 0 -1 6.99047e-7 0 -1 0 0 -1 1.10988e-6 0 -1 0 0 -1 2.41152e-6 0 -1 -1.64312e-6 0 -1 0 0 -1 0 0 -1 0 1.50139e-7 -1 0 0 -1 -4.65564e-7 0 -1 1.89973e-7 0 -1 0 0 -1 0 0 -1 1.27099e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.60374e-6 0 -1 0 0 -1 8.63807e-7 0 -1 0 0 -1 2.84617e-7 0 -1 0 0.8920747 0 -0.4518883 0.8920745 0 -0.4518884 -4.27938e-7 1 0 0 1 -6.94954e-7 0 1 0 0 1 1.66547e-7 0 1 0 0 1 -1.30851e-6 -2.36085e-7 1 1.67526e-6 0 1 0 0 1 -1.82085e-7 0 1 0 0 1 0 0 1 0 0 1 2.31635e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 6.55698e-7 1 1.51347e-7 9.18024e-7 1 0 0 1 4.92878e-7 0 1 -6.78006e-7 0 1 1.45965e-7 0 1 0 0 1 -8.61428e-7 0 1 0 0 1 8.678e-7 0 1 2.52353e-7 0 1 0 0 1 1.02262e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.50394e-7 0 1 0 0 1 0 0 1 0 0 1 2.09407e-7 0 1 0 0 1 0 0 1 0 -0.09088557 0.9947974 0.04602265 0.04464983 0.9987468 -0.02261483 0.8814319 -0.1540011 -0.4464994 0.892071 -6.1038e-4 -0.4518951 -0.2243474 0.967859 0.1136539 -0.3526165 0.9185608 0.1786277 -0.4727088 0.848062 0.2394521 -0.5818822 0.7579789 0.294756 -0.6776047 0.6504126 0.3432428 -0.7576628 0.5278858 0.3837755 -0.8201835 0.393306 0.4154632 -0.8638381 0.2496142 0.4375804 -0.8782584 0.1753342 0.4448821 0.1790531 0.9796496 -0.09070152 0.3092545 0.9379874 -0.1566568 0.4323942 0.8746765 -0.2190353 0.5455688 0.7911907 -0.2763552 0.6461825 0.6894282 -0.3273181 0.7319089 0.5717142 -0.3707459 0.8007418 0.4407635 -0.4056355 0.8510913 0.2996383 -0.4311154 0.8817754 0.1515609 -0.4466559 0.7270948 -0.5793808 -0.3683084 0.7979846 -0.4470142 -0.4042263 0.8498117 -0.304156 -0.4304757 0.8814277 -0.1540308 -0.4464972 0.5353457 -0.7999209 -0.2711673 0.4190595 -0.8827992 -0.2122612 0.6388335 -0.6979802 -0.3235979 0.159431 -0.9839008 -0.08075314 0.02230954 -0.9996874 -0.01129209 0.2927381 -0.9446238 -0.1482918 -0.3786888 -0.9054288 0.1918165 -0.249894 -0.9599618 0.126595 -0.1152095 -0.9916259 0.05835247 -0.606468 -0.7333648 0.3072015 -0.6999792 -0.6199284 0.3545674 -0.6064487 -0.7333784 0.3072071 -0.4984999 -0.8292972 0.2525156 -0.7768092 -0.4916668 0.3934861 -0.8350918 -0.3516706 0.4230241 -0.8734614 -0.2032583 0.4424378 -0.8848446 -0.1270211 0.4482362 -0.4518877 0 -0.892075 -0.4518862 -5.13523e-7 -0.8920756 -0.451888 1.03759e-6 -0.8920747 -0.4518899 -2.90905e-7 -0.8920738 -0.4518855 1.27347e-6 -0.8920759 -0.4518892 -1.04661e-6 -0.8920741 -0.451888 -1.36945e-6 -0.8920747 -0.4518889 -1.58135e-6 -0.8920743 -0.4518871 -1.25905e-6 -0.8920753 -0.4518895 2.12249e-6 -0.892074 -0.4518877 -1.24607e-6 -0.8920749 -0.4518874 3.08627e-6 -0.892075 -0.4518887 -1.22425e-6 -0.8920744 -0.4518879 -1.06761e-6 -0.8920748 -0.451888 2.73446e-6 -0.8920747 -0.4518887 1.61014e-6 -0.8920744 -0.4518885 0 -0.8920745 -0.4518889 0 -0.8920744 -0.4518897 0 -0.8920739 -0.4518893 -1.20034e-6 -0.8920741 -0.451887 1.65048e-6 -0.8920752 -0.4518872 -1.09654e-6 -0.8920751 -0.4518872 -8.20546e-7 -0.8920751 -0.4518886 2.51057e-6 -0.8920744 -0.4518877 -1.16007e-6 -0.8920749 -0.451888 2.35959e-6 -0.8920747 -0.4518879 8.80051e-7 -0.8920748 -0.4518867 2.73546e-6 -0.8920753 -0.4518875 0 -0.892075 -0.4518864 -1.99559e-6 -0.8920755 -0.4518862 -1.77419e-6 -0.8920756 -0.451888 -2.73643e-6 -0.8920748 -0.4518891 1.39323e-6 -0.8920742 -0.4518876 -5.29937e-6 -0.892075 -0.4518882 1.07459e-6 -0.8920747 -0.4518867 5.38233e-6 -0.8920754 -0.4518863 1.068e-6 -0.8920757 -0.4518901 -2.06972e-6 -0.8920736 -0.4518863 0 -0.8920755 -0.4518864 0 -0.8920755 -0.4518882 1.93195e-6 -0.8920747 -0.4518871 -1.95281e-6 -0.8920753 -0.4518886 0 -0.8920744 -0.4518883 4.7429e-6 -0.8920747 -0.4518873 1.18083e-6 -0.892075 -0.4518877 0 -0.892075 -0.4518902 -3.38696e-6 -0.8920736 -0.4518907 2.32873e-6 -0.8920733 -0.4518901 -2.37521e-6 -0.8920737 -0.4518879 2.9429e-6 -0.8920748 -0.4518895 -2.47364e-6 -0.892074 -0.4518859 2.19084e-6 -0.8920758 -0.4518894 -5.65203e-7 -0.8920741 -0.451887 1.05492e-6 -0.8920753 -0.4518881 -1.06578e-6 -0.8920747 -0.4518873 -1.65954e-6 -0.8920751 -0.4518883 -2.58615e-6 -0.8920746 -0.4518865 -5.30241e-6 -0.8920754 -0.4518882 -2.48202e-6 -0.8920747 -0.4518896 -2.78534e-6 -0.8920739 -0.4518888 3.32796e-6 -0.8920743 -0.4518879 0 -0.8920747 -0.4518879 1.76331e-6 -0.8920748 -0.4518885 2.44153e-6 -0.8920745 -0.4518887 0 -0.8920743 -0.4518882 5.89048e-7 -0.8920746 -0.4518889 2.29351e-6 -0.8920742 -0.4518878 -2.40737e-6 -0.8920749 -0.4518897 0 -0.8920738 -0.4518887 0 -0.8920744 -0.4518884 -3.10487e-6 -0.8920745 -0.4518887 -2.10458e-6 -0.8920743 -0.4518882 1.01601e-6 -0.8920747 -0.4518904 2.37796e-6 -0.8920735 -0.4518857 5.0406e-6 -0.8920758 -0.4518892 -1.08334e-6 -0.8920741 -0.4518873 2.13971e-6 -0.8920751 -0.4518892 -2.43432e-6 -0.8920741 -0.4518899 -1.10694e-6 -0.8920738 -0.4518852 3.60253e-6 -0.8920762 -0.4518882 0 -0.8920746 -0.4518881 6.74668e-6 -0.8920748 -0.4518899 1.13175e-6 -0.8920738 -0.451888 -1.16947e-6 -0.8920748 -0.4518885 2.26579e-6 -0.8920745 0.1248829 0.9901524 -0.0632655 0.004181087 0.9999892 -0.002105772 0.2432362 0.9621106 -0.1232051 0.3570113 0.9164246 -0.1808556 0.4641361 0.8539885 -0.2351199 0.5628746 0.7758105 -0.2851149 0.6513971 0.6832283 -0.3299711 0.7278889 0.5781299 -0.3687055 0.7908539 0.4626768 -0.4006 0.8393419 0.3387337 -0.4251644 0.8578852 0.274212 -0.4345581 -0.1164908 0.9914383 0.0589931 -0.2348771 0.9647177 0.1189645 -0.3490116 0.9202906 0.1767947 -0.3489847 0.9203004 0.1767965 -0.4568475 0.8589124 0.2314299 -0.5563656 0.7816891 0.2818146 -0.6456099 0.6901073 0.3270166 -0.7228534 0.5860041 0.3661724 -0.7868424 0.4711837 0.3985789 -0.8364542 0.3475892 0.4237054 -0.8707236 0.2174825 0.441069 -0.8818843 0.1507651 0.4467103 0.4518871 -1.89089e-6 0.8920751 0.4518882 0 0.8920747 0.4518879 -2.13972e-6 0.8920748 0.4518869 1.23682e-6 0.8920753 0.451887 0 0.8920753 0.4518882 -5.41667e-7 0.8920747 0.4518867 0 0.8920754 0.451889 5.4771e-7 0.8920742 0.4518883 1.10693e-6 0.8920746 0.4518872 6.00422e-7 0.8920751 0.4518888 -1.11801e-6 0.8920744 0.4518878 0 0.8920748 0.4518882 -8.47629e-7 0.8920747 0.4518885 1.76574e-6 0.8920745 0.4518876 0 0.892075 0.4518883 -2.25797e-6 0.8920746 0.4518888 0 0.8920743 0.451886 5.82183e-7 0.8920757 0.4518898 1.6656e-6 0.8920738 0.4518884 1.09841e-6 0.8920745 0.4518868 0 0.8920753 0.4518847 -5.69113e-7 0.8920764 0.45189 -2.46471e-6 0.8920737 0.4518896 1.09654e-6 0.8920739 0.4518876 2.5662e-6 0.892075 0.4518879 0 0.8920748 0.451889 -2.43063e-6 0.8920742 0.4518883 -7.78194e-7 0.8920747 0.4518866 0 0.8920754 0.4518867 -5.23302e-7 0.8920754 0.4518891 6.29525e-7 0.8920742 0.4518899 -7.74868e-7 0.8920738 0.4518877 6.17255e-7 0.8920748 0.451889 6.23036e-7 0.8920743 0.4518872 5.30621e-7 0.8920752 0.451887 6.12125e-7 0.8920753 0.4518868 1.13434e-6 0.8920754 0.4518882 -2.33087e-6 0.8920747 0.4518878 -1.87849e-6 0.8920748 0.4518874 -2.18232e-6 0.892075 0.4518896 7.50212e-7 0.892074 0.451888 0 0.8920747 0.4518897 5.4709e-7 0.8920739 0.4518879 -4.07024e-7 0.8920747 0.4518879 9.02762e-7 0.8920747 0.4518864 -1.08757e-6 0.8920755 0.4518872 1.92144e-6 0.8920751 0.4518885 -2.7508e-7 0.8920745 0.4518873 -1.08423e-6 0.8920751 0.4518873 -1.35081e-6 0.892075 0.4518871 0 0.8920752 0.4518854 -8.87028e-7 0.8920761 0.4518877 -5.48244e-7 0.8920748 0.4518882 -1.09556e-6 0.8920747 0.4518896 0 0.892074 0.4518874 1.82507e-6 0.892075 0.4518901 -1.51038e-6 0.8920736 0.4518861 6.0043e-7 0.8920757 0.4518896 -5.97333e-7 0.8920739 0.4518879 -1.78452e-6 0.8920748 0.4518876 1.77859e-6 0.892075 0.451889 -1.18083e-6 0.8920742 0.4518899 -5.91395e-7 0.8920738 0.4518905 -1.11771e-6 0.8920734 0.4518879 2.35942e-6 0.8920748 0.4518891 0 0.8920741 0.4518885 2.7733e-7 0.8920745 0.4518873 -9.15574e-7 0.8920751 0.4518875 -1.24101e-6 0.8920751 0.4518876 1.26481e-6 0.892075 0.4518873 -5.4703e-7 0.8920751 0.4518862 5.61908e-7 0.8920757 0.4518885 0 0.8920745 0.4518883 5.57905e-7 0.8920747 0.4518879 5.81422e-7 0.8920748 0.451889 0 0.8920742 0.4518884 0 0.8920745 0.4518864 7.43113e-7 0.8920755 0.4518898 0 0.8920738 0.4518884 -8.77449e-7 0.8920745 0.4518883 0 0.8920746 0.451888 5.32889e-7 0.8920747 0.4518886 1.39267e-7 0.8920744 0.4518882 1.04052e-6 0.8920746 0.4518883 0 0.8920745 0.4518883 -4.25409e-7 0.8920746 0.4518879 0 0.8920747 0.451888 1.76331e-7 0.8920748 0.8920747 0 -0.4518883 0.8920745 0 -0.4518883 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.54217e-7 0 -1 0 0 -1 -1.46098e-7 0 -1 0 0 -1 -2.09404e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 5.89088e-7 0 -1 0 0 -1 -2.87173e-7 0 -1 0 0 -1 0 0 -1 -5.58485e-7 0 -1 0 0 -1 0 0 -1 0 -7.83843e-7 -1 -4.94492e-7 1.24581e-7 -1 -3.24316e-7 0 -1 0 0 -1 0 0 -1 -2.02223e-7 0 -1 0 0 -1 -3.41062e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -6.88581e-7 0 -1 8.3239e-7 0 -1 -1.60374e-7 0 -1 -8.69735e-7 2.19047e-7 -1 1.57056e-7 0 -1 1.04681e-6 0 -1 0 0 -1 -1.23378e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 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.26997e-7 1 0 0 1 0 -4.15299e-7 1 8.16558e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 8.10124e-7 1 2.28715e-7 0 1 0 -1.33265e-7 1 0 0.8920897 0 -0.4518586 -0.5698621 1.22078e-4 0.8217404 -0.6970567 6.10382e-5 0.7170161 -0.6970876 6.10383e-5 0.7169861 -0.8055251 3.05193e-5 0.5925618 -0.8054094 0 0.592719 -0.2715877 -3.05189e-5 0.9624137 -0.1098688 3.05191e-5 0.9939461 -0.2720437 0 0.962285 -0.5692148 0 0.8221889 -0.4262291 -3.05191e-5 0.9046153 -0.4268094 3.05191e-5 0.9043416 0.2188237 3.05193e-5 0.9757645 0.2194308 -3.05189e-5 0.9756281 0.3763001 3.05191e-5 0.9264979 0.05517756 3.05186e-5 0.9984766 -0.109259 -3.05193e-5 0.9940133 0.05588072 -3.05193e-5 0.9984375 0.5238318 3.05192e-5 0.8518218 0.5243222 -3.05193e-5 0.85152 0.6567505 3.05196e-5 0.7541079 0.3769353 -3.05186e-5 0.9262396 0.6572073 -3.05195e-5 0.75371 0.7718809 3.05188e-5 0.6357672 0.8660789 0 0.4999074 0.7723503 -6.10385e-5 0.6351969 0.8663664 -3.05188e-5 0.4994089 0.9366173 0 0.3503541 0.9367862 -3.05192e-5 0.3499024 0.9814971 0 0.1914774 0.9996252 0 0.02737569 0.9815864 -3.05191e-5 0.1910191 0.9996386 -6.10373e-5 0.02688694 0.9904611 0 -0.1377929 0.9542936 0 -0.298871 -2.96689e-7 -1 0 -2.96689e-7 -1 0 -4.54951e-7 -1 0 -4.54951e-7 -1 -7.00126e-7 -0.7327501 2.62548e-7 -0.680498 -0.7327503 0 -0.6804977 -0.9557021 0 0.2943361 -0.9557022 5.25098e-7 0.2943357 -0.2229585 0 0.974828 -0.2229584 0 0.974828 0.7327505 -2.62548e-7 0.6804975 0.7327505 -1.31274e-7 0.6804975 0.9557021 -5.25097e-7 -0.2943357 0.955702 0 -0.2943359 0.2229584 -1.47684e-7 -0.974828 0.2229583 -1.58428e-7 -0.974828 0 -1 -2.38934e-6 -3.4275e-7 -1 -1.05492e-6 0 -1 1.33857e-6 0 -1 5.93095e-7 0 -1 -2.66381e-6 0 -1 2.85785e-6 0 -1 0 0 -1 -3.42559e-6 -2.65986e-7 -1 6.79772e-6 -5.26808e-7 -1 -6.88744e-7 0 -1 -2.2844e-6 -5.62182e-7 -1 4.99386e-7 7.7428e-7 -1 1.44438e-6 -4.45046e-7 -1 2.62556e-7 -4.68076e-7 -1 0 -2.91005e-7 -1 -2.67798e-6 -5.88421e-7 -1 0 -6.00448e-7 -1 0 -3.06596e-7 -1 7.90151e-7 0 -1 3.88351e-6 -4.33197e-7 -1 6.23218e-7 -6.81416e-7 -1 2.80815e-6 -1.13253e-6 -1 -1.41073e-6 1.83279e-7 -1 -9.06407e-7 0 -1 -4.53406e-6 0 -1 1.28733e-6 -3.06589e-7 -1 5.26771e-7 0 -1 0 0 -1 -3.42753e-7 0 -1 -2.57336e-6 -4.89273e-7 -1 2.37202e-6 -1.44073e-6 -1 9.28251e-7 -2.8969e-7 -1 -3.42817e-7 0 -1 1.05495e-6 -0.9814616 0 -0.1916595 -0.9996219 0 -0.02749764 0.1095941 0 -0.9939764 0.2717088 0 -0.9623795 -0.9905121 0 0.1374253 -0.9543774 0 0.2986034 -0.8921944 0 0.4516516 -0.8056661 0 0.5923701 -0.6971495 0 0.7169259 -0.5695908 0 0.8219284 -0.4265009 0 0.9044872 -0.271745 0 0.9623693 -0.1095941 0 0.9939764 -0.936536 0 -0.3505715 -0.8660657 0 -0.4999303 -0.7719779 0 -0.6356495 -0.6568328 0 -0.7540363 -0.5238097 0 -0.8518354 -0.3765155 0 -0.9264104 -0.2190045 0 -0.9757239 -0.05551391 0 -0.998458 0.4264143 0 -0.9045281 0.8055251 0 -0.5925618 0.6969948 0 -0.7170763 0.5694862 0 -0.822001 0.9904694 0 -0.1377331 0.9366512 0 0.3502638 0.9815326 0 0.1912952 0.657045 0 0.7538515 0.7721716 0 0.6354141 0.866236 0 0.4996353 0.3766677 0 0.9263485 0.5240191 0 0.8517066 0.2190626 0 0.9757108 0.05548352 0 0.9984596 0 1 1.38141e-6 0 1 -2.59016e-7 4.49423e-7 1 -6.90722e-7 7.03421e-7 1 -1.10513e-6 0 1 -2.21025e-6 0 1 -1.10513e-6 -3.1941e-7 1 -3.453e-7 6.80674e-7 1 0 4.6443e-7 1 0 4.49648e-7 1 1.38147e-6 4.22589e-7 1 -1.38152e-6 0 1 1.10534e-6 7.37655e-7 1 0 4.66555e-7 1 0 4.55953e-7 1 0 5.6242e-7 1 2.76284e-7 5.64796e-7 1 1.10484e-6 2.96959e-7 1 0 0 1 -1.38102e-6 0 1 1.38141e-6 0 1 -1.10513e-6 0 1 6.90715e-7 6.63812e-7 1 0 8.16939e-7 1 -1.38116e-6 0 1 -1.38168e-6 0 1 1.38145e-6 0 1 -1.10513e-6 0 1 5.52578e-7 0 1 7.59782e-7 0 1 -1.38143e-7 0 1 8.28849e-7 0 1 -1.10514e-6 3.3505e-7 1 1.10514e-6 0 1 1.38143e-6 8.66328e-7 1 0 0 1 6.90711e-7 0 1 5.18032e-7 0 1 6.90526e-7 2.33515e-7 1 1.38104e-6 5.11657e-7 1 0 5.06953e-7 1 0 6.87428e-7 1 0 0 1 5.52457e-7 4.32904e-7 1 -5.5249e-7 4.55944e-7 1 -2.7625e-7 4.66551e-7 1 2.76261e-7 4.64439e-7 1 1.51954e-6 4.49642e-7 1 -2.76289e-7 4.22592e-7 1 1.10523e-6 7.19436e-7 1 -5.52649e-7 0 1 5.52775e-7 7.02828e-7 1 0 0.9366611 0 0.350237 0.8662227 0 0.4996582 0.9542849 0 -0.2988988 0.69701 0 -0.7170615 0.6970257 0 -0.7170462 0.5694655 0 -0.8220152 -0.523796 -6.10378e-5 -0.8518438 -0.3766677 0 -0.9263485 -0.3764892 -6.10391e-5 -0.9264211 -0.2190626 0 -0.9757108 -0.05548352 0 -0.9984596 -0.7721716 0 -0.6354141 -0.7719506 -9.15573e-5 -0.6356827 -0.8660657 -9.15567e-5 -0.4999303 -0.5240191 0 -0.8517066 -0.6568328 -9.15574e-5 -0.7540363 -0.9814616 -9.15571e-5 -0.1916595 -0.9996227 -6.10382e-5 -0.02746719 -0.9815326 0 -0.1912952 -0.936536 -9.15569e-5 -0.3505715 -0.9366611 0 -0.350237 -0.8662227 0 -0.4996582 -0.8921944 -3.05191e-5 0.4516516 -0.9542849 0 0.2988988 -0.9543774 -6.10391e-5 0.2986034 -0.9904694 0 0.1377331 -0.9996319 0 -0.02713173 -0.9905121 -6.10372e-5 0.1374253 -0.69701 0 0.7170615 -0.8055251 0 0.5925618 -0.6971495 -3.05192e-5 0.7169259 -0.8056661 -3.05188e-5 0.5923701 -0.5696115 -3.05193e-5 0.8219142 -0.5694655 0 0.8220152 -0.4264143 0 0.9045281 -0.2717088 0 0.9623795 1.38439e-7 1 0 2.33268e-7 1 1.38142e-6 2.51425e-7 1 0 2.1642e-7 1 -2.76283e-6 0 1 -2.76282e-6 1.39625e-6 1 0 1.23388e-6 1 0 0 1 3.45356e-7 6.55178e-7 1 0 7.25379e-7 1 -3.45353e-7 0 1 1.38136e-6 2.16431e-7 1 0 1.23368e-6 1 0 2.27954e-7 1 -6.04251e-7 2.33255e-7 1 0 5.18757e-7 1 1.72676e-7 1.38379e-7 1 0 0 1 -3.45347e-7 0 1 0 0 1 3.45354e-7 0 1 -6.91559e-7 0 1 -3.45354e-7 0 1 -3.45354e-7 7.25373e-7 1 3.45355e-7 0 1 6.90513e-7 0 1 6.90715e-7 0 1 1.38186e-6 6.55109e-7 1 -6.90666e-7 1.3844e-7 1 -6.90706e-7 2.51198e-7 1 0 2.3327e-7 1 0 2.27956e-7 1 0 2.16421e-7 1 0 0 1 -1.38114e-6 1.39602e-6 1 0 0 1 0 0 1 3.45259e-7 0 1 -6.90708e-7 0 1 -1.38141e-6 0 1 0 1.3844e-7 1 0 2.33268e-7 1 0 2.27953e-7 1 1.72677e-7 2.16419e-7 1 1.38139e-6 2.27953e-7 1 -1.38142e-6 5.18611e-7 1 -6.90726e-7 0 1 1.38141e-6 0 1 3.45355e-7 0 1 -3.45357e-7 0 1 -3.45353e-7 0 1 -6.90714e-7 0 1 1.26537e-5 0 1 -3.41861e-6 0 1 8.63129e-6 0 1 -5.27423e-6 0 1 2.4806e-6 0 1 -2.30428e-6 0 1 5.5241e-6 0 1 2.76374e-6 0 1 3.73858e-6 0 1 1.29508e-7 0 1 2.53208e-5 0 1 -6.47687e-6 0 1 5.27744e-6 0 1 -4.09802e-6 0 1 -5.20969e-7 0 1 -1.44038e-6 0 1 -2.76283e-6 0 1 -1.87707e-7 0 1 2.10124e-6 0 1 -3.27158e-6 -0.6968401 0 0.7172267 -0.5696115 0 0.8219142 -0.5693258 0 0.822112 -0.4263526 0 0.9045572 -0.8919292 0 0.4521753 -0.9541868 0 0.2992115 -0.8053696 0 0.5927732 -0.999641 0 -0.02679544 -0.9815977 0 -0.1909603 -0.9996227 0 -0.02746719 -0.9904189 0 0.1380965 -0.7723503 0 -0.6351969 -0.8663796 0 -0.499386 -0.9367662 0 -0.3499559 -0.523796 0 -0.8518438 -0.5241706 0 -0.8516133 -0.6572245 0 -0.7536948 -0.3768199 0 -0.9262866 -0.2191563 0 -0.9756898 -0.4518916 -1.65769e-5 -0.8920729 -0.4518957 -5.12673e-6 -0.8920708 -0.4518836 -1.30769e-5 -0.8920769 -0.4518879 8.70571e-6 -0.8920747 -0.4518875 2.37692e-6 -0.892075 -0.4518846 -4.61917e-6 -0.8920764 -0.4518888 -1.63364e-5 -0.8920744 -0.4518989 4.10998e-6 -0.8920693 -0.4518923 1.71289e-5 -0.8920725 -0.4518981 0 -0.8920695 -0.4518964 -2.4452e-6 -0.8920705 -0.451889 6.8862e-7 -0.8920742 -0.4518903 -1.49526e-5 -0.8920736 -0.4518978 2.60776e-6 -0.8920697 -0.4518862 -9.42392e-6 -0.8920756 -0.451883 5.83165e-6 -0.8920773 -0.4518974 3.6269e-6 -0.8920699 -0.4518942 1.19858e-6 -0.8920717 -0.4518948 4.32316e-6 -0.8920712 -0.4518909 -3.30423e-6 -0.8920732 -0.4518886 0 -0.8920744 -0.4519004 1.43859e-5 -0.8920685 -0.4518879 1.59469e-5 -0.8920748 -0.4518787 -1.29012e-5 -0.8920794 -0.4518853 -7.98415e-6 -0.8920761 -0.451883 3.68079e-6 -0.8920773 -0.4518847 9.12622e-6 -0.8920764 -0.4518828 -2.30788e-6 -0.8920773 -0.4518824 4.11009e-6 -0.8920776 -0.4518771 -3.19669e-6 -0.8920802 -0.4518769 -1.53581e-7 -0.8920803 -0.4518902 -1.32438e-5 -0.8920736 -0.4518831 -1.4946e-5 -0.8920773 -0.4518875 4.71232e-6 -0.892075 -0.4518892 -1.98369e-5 -0.8920741 -0.4518864 5.731e-6 -0.8920755 -0.4518918 1.12257e-5 -0.8920727 -0.4518958 -2.39569e-6 -0.8920708 -0.4518852 -3.64058e-6 -0.8920761 -0.4518823 8.34758e-6 -0.8920777 -0.4518517 -2.05973e-5 -0.8920931 -0.4519934 1.17486e-4 -0.8920213 -0.4517469 -3.37057e-5 -0.8921462 -0.4517257 -9.3828e-5 -0.8921569 -0.4519904 -4.61843e-5 -0.8920229 -0.4519183 3.28975e-5 -0.8920593 -0.451986 1.27911e-5 -0.8920251 -0.4518745 -1.2858e-6 -0.8920816 -0.4518557 -3.19056e-5 -0.892091 -0.4518852 -2.52996e-5 -0.8920762 -0.451909 1.47285e-5 -0.892064 -0.4518936 -1.27948e-5 -0.8920719 -0.4518786 -3.0378e-6 -0.8920795 -0.4518647 -1.9648e-5 -0.8920865 -0.4519011 2.2605e-5 -0.8920681 -0.4519176 1.06776e-5 -0.8920597 -0.4518355 2.35253e-6 -0.8921014 -0.4519407 1.59617e-5 -0.892048 -0.4517413 -2.94456e-4 -0.8921489 -0.4519102 9.9668e-5 -0.8920634 -0.4519023 3.74463e-5 -0.8920675 -0.4517779 -1.52134e-4 -0.8921306 -0.4519044 -4.79797e-5 -0.8920665 -0.4518647 1.47475e-5 -0.8920866 -0.4519007 2.55303e-5 -0.8920683 -0.4518771 -3.33308e-5 -0.8920803 -0.4518379 -2.44529e-5 -0.8921 -0.4518959 -9.31118e-6 -0.8920708 -0.4518929 9.11466e-6 -0.8920722 -0.4518637 -2.24238e-5 -0.8920871 -0.4518848 -2.55985e-6 -0.8920763 -0.4519048 3.23871e-5 -0.8920662 -0.4519261 3.49518e-5 -0.8920554 -0.4518573 -7.95105e-7 -0.8920904 -0.4518944 1.0676e-5 -0.8920715 -0.4519239 2.32608e-5 -0.8920566 -0.4518871 0 -0.8920751 -0.451766 9.44746e-4 -0.892136 -0.4518824 8.03418e-5 -0.8920775 -0.4518747 -3.17495e-4 -0.8920814 -0.451951 6.67185e-5 -0.8920428 -0.4518502 -1.22512e-4 -0.8920939 -0.4518552 7.55106e-5 -0.8920913 -0.4519693 0 -0.8920335 -0.4518854 2.91838e-5 -0.8920761 -0.4518647 0 -0.8920866 -0.451888 -2.23875e-6 -0.8920747 -0.4518358 7.54695e-5 -0.8921012 -0.451932 0 -0.8920524 -0.451824 0 -0.8921072 -0.4519535 0 -0.8920416 -0.4518631 0 -0.8920873 -0.4519394 -7.33073e-5 -0.8920488 -0.451898 0 -0.8920696 -0.4519117 0 -0.8920628 -0.451883 -1.71179e-5 -0.8920773 -0.4518885 0 -0.8920744 -0.4518774 0 -0.8920801 -0.4518274 -1.18001e-4 -0.8921055 -0.4519675 0 -0.8920344 -0.4519045 -2.46969e-5 -0.8920664 -0.4518994 0 -0.8920689 -0.4518759 4.10051e-5 -0.8920809 -0.451849 0 -0.8920946 -0.4519462 0 -0.8920452 -0.4518861 8.95502e-6 -0.8920757 -0.4518603 -9.44759e-4 -0.8920883 -0.4518891 -5.82076e-6 -0.8920742 -0.4518454 -8.03423e-5 -0.8920963 -0.4519538 3.17495e-4 -0.8920413 -0.4519215 -3.33595e-5 -0.8920577 -0.4519068 9.80063e-5 -0.8920652 -0.451846 -5.19125e-5 -0.8920961 -0.4519526 0 -0.8920419 -0.4518818 -5.04783e-5 -0.8920779 -0.4518883 -5.82076e-6 -0.8920746 -0.4521017 -1.77133e-4 -0.8919665 -0.4518616 -6.02589e-5 -0.8920881 -0.4517795 1.58742e-4 -0.8921296 -0.4518414 6.6722e-5 -0.8920983 -0.4519508 -8.57545e-5 -0.8920429 -0.4518762 -1.88785e-5 -0.8920807 -0.4519367 -4.88686e-5 -0.8920502 -0.4517289 1.77492e-6 -0.8921553 -0.4519383 1.51779e-5 -0.8920492 -0.4518883 -1.67907e-6 -0.8920746 -0.4518465 2.44347e-5 -0.8920958 -0.4520725 2.36193e-4 -0.8919811 -0.4518514 8.03434e-5 -0.8920933 -0.4518586 -7.93709e-5 -0.8920896 -0.4518362 -4.90061e-5 -0.8921009 -0.4518876 -5.6637e-5 -0.8920749 -0.4519544 0 -0.8920412 -0.4518256 0 -0.8921063 -0.4519414 1.5178e-5 -0.8920477 -0.4518725 -2.90295e-5 -0.8920825 -0.4518642 0 -0.8920869 -0.4518808 -3.60869e-5 -0.8920784 -0.4517852 -4.42118e-5 -0.8921268 -0.4517464 3.63959e-5 -0.8921464 -0.4520127 -4.93895e-5 -0.8920115 -0.4519196 0 -0.8920587 -0.451889 2.3677e-5 -0.8920742 -0.451888 4.47751e-6 -0.8920747 -0.4520606 1.7714e-4 -0.8919872 -0.4518882 3.39545e-6 -0.8920746 -0.4518555 6.02581e-5 -0.8920912 -0.4518115 -1.58753e-4 -0.8921135 -0.4518398 -7.08919e-5 -0.8920992 -0.4519897 7.35022e-5 -0.8920232 -0.4519542 1.65174e-5 -0.8920413 -0.4518797 4.8873e-5 -0.8920789 -0.4518167 0 -0.8921108 -0.4518647 -1.51795e-5 -0.8920866 -0.4518851 -4.35637e-4 -0.8920761 -0.4518915 -4.04815e-4 -0.8920729 -0.4518879 2.95762e-4 -0.8920747 -0.4518526 -5.86132e-4 -0.8920925 -0.4518886 0 -0.8920745 -0.4518865 0 -0.8920755 -0.4518598 0 -0.8920891 -0.4518709 0 -0.8920835 -0.4518958 -9.4096e-5 -0.8920708 -0.4518797 0 -0.8920789 -0.451888 0 -0.8920748 -0.451888 0 -0.8920748 -0.4518932 0 -0.892072 -0.4518712 0 -0.8920832 -0.4518929 2.27797e-4 -0.8920722 -0.4518926 -1.66918e-4 -0.8920724 -0.4519109 -4.86492e-5 -0.892063 -0.4518733 1.67609e-4 -0.8920821 -0.4518968 0 -0.8920703 -0.4518901 -2.61197e-5 -0.8920737 -0.4518879 1.1746e-5 -0.8920748 -0.4519088 7.5268e-5 -0.8920642 -0.4518881 -7.22126e-6 -0.8920747 -0.4519035 -5.22696e-4 -0.8920668 -0.4518026 0 -0.8921179 -0.451887 2.03787e-5 -0.8920753 -0.4519338 2.68928e-4 -0.8920515 -0.4518734 -9.74971e-5 -0.892082 -0.4518842 0 -0.8920767 -0.4518749 0 -0.8920814 -0.4518895 0 -0.892074 -0.4518826 -1.2704e-4 -0.8920775 -0.4519072 5.11699e-5 -0.892065 -0.4519035 0 -0.8920668 -0.451876 1.02982e-4 -0.8920809 -0.4518772 0 -0.8920802 -0.4518808 4.0909e-5 -0.8920783 -0.4518352 -7.77769e-4 -0.8921012 -0.4518702 0 -0.8920838 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.8920747 0 0.4518883 -0.8920747 0 0.4518883 -0.8437612 -0.324662 0.4273893 -0.8799148 -0.1645568 0.4457254 -0.8890235 -0.08264589 0.4503409 -0.8890257 -0.08261555 0.450342 -0.703961 -0.6142339 0.3565889 -0.6041552 -0.7357534 0.3060451 -0.784569 -0.4759236 0.397427 -0.4879351 -0.8371621 0.2471415 0.07367187 -0.996585 -0.03729373 -0.07367187 -0.996585 0.03729373 0.4879351 -0.8371621 -0.2471415 0.6041687 -0.7357394 -0.3060519 0.703961 -0.6142339 -0.3565889 0.8437612 -0.324662 -0.4273893 0.8799148 -0.1645568 -0.4457254 0.8890212 -0.08267623 -0.4503397 0.8890257 -0.08261555 -0.450342 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1.79083e-7 -1 0 0 -1 0 1.56636e-7 -1 0 -0.8524103 -0.2948796 0.4317902 -0.8820976 -0.1491475 0.4468321 -0.8895816 -0.07474219 0.45062 -0.6537525 -0.6803957 0.3311641 -0.8036646 -0.4340454 0.4070969 -0.4457898 -0.866188 0.2258095 -0.5559611 -0.7820444 0.2816275 0.4462529 -0.865893 -0.2260258 0.7372322 -0.5630567 -0.3734382 0.5563609 -0.7816824 -0.2818427 0.8038164 -0.4336787 -0.407188 0.8524618 -0.2946932 -0.4318159 0.8821097 -0.149058 -0.4468383 0.8895816 -0.07474219 -0.45062 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.8439309 0.3240887 -0.4274895 0.8799916 0.1640409 -0.4457639 0.8439453 0.3240215 -0.4275119 0.8799872 0.1640706 -0.4457617 0.703786 0.6144852 -0.3565015 0.604462 0.7354502 -0.306168 0.6039744 0.7359393 -0.3059547 0.7038014 0.614472 -0.3564938 0.784569 0.4759236 -0.397427 0.7842597 0.476562 -0.3972724 0.2190946 0.9693696 -0.110997 0.3579915 0.9159454 -0.1813457 0.2185814 0.9695165 -0.1107251 0.3584201 0.9157353 -0.18156 0.4878208 0.8372365 -0.2471149 0.4877567 0.8372924 -0.2470523 -0.2190946 0.9693696 0.110997 -0.2188239 0.9694479 0.1108464 -0.07391655 0.9965611 0.03744655 0.07330584 0.9966177 -0.0371412 -0.07361119 0.9965896 0.03729385 0.07361119 0.9965896 -0.03729385 -0.4883042 0.8368924 0.2473261 -0.6040074 0.7359118 0.3059559 -0.6044699 0.7354293 0.3062025 -0.3581405 0.9158753 0.181405 -0.3587527 0.915575 0.1817111 -0.4878208 0.8372365 0.2471149 -0.8436451 0.3250001 0.4273618 -0.784901 0.47525 0.3975778 -0.8435883 0.3251848 0.4273334 -0.784569 0.4759236 0.397427 -0.7041987 0.6138924 0.3567077 -0.7042614 0.6138024 0.3567391 -0.8798516 -0.1650198 0.4456788 -0.8798472 -0.1650496 0.4456766 -0.8798295 0.1651683 0.4456676 -0.8798472 0.1650496 0.4456766 -0.7845807 -0.4759122 0.3974175 -0.7042118 -0.6138734 0.3567144 -0.8436451 -0.3250001 0.4273618 -0.3581405 -0.9158753 0.181405 -0.4878208 -0.8372365 0.2471149 -0.6044699 -0.7354293 0.3062025 0.07361125 -0.9965906 -0.03726339 0.07361119 -0.9965896 -0.03729385 -0.07361119 -0.9965896 0.03729385 -0.2188239 -0.9694479 0.1108464 -0.07361125 -0.9965906 0.03726339 0.2190946 -0.9693696 -0.110997 0.2191237 -0.9693631 -0.1109962 0.3584201 -0.9157353 -0.18156 0.4878208 -0.8372365 -0.2471149 0.6039744 -0.7359393 -0.3059547 0.7038146 -0.614453 -0.3565005 0.784569 -0.4759236 -0.397427 0.8439309 -0.3240887 -0.4274895 0.7845807 -0.4759122 -0.3974175 0.8799872 -0.1640706 -0.4457617 0.8857944 -0.1125555 -0.4502218 0.8893385 -0.07828253 -0.4504985 0.8801951 -0.1654428 -0.4448432 0.6868625 -0.6389476 -0.3463611 0.790915 -0.461273 -0.4020955 0.8240211 -0.3853366 -0.4153372 0.2298111 -0.9663664 -0.1154243 0.2102488 -0.9717714 -0.1070318 0.4550134 -0.859853 -0.2315505 0.0875597 -0.9951718 -0.04434442 0.1010788 -0.9936063 -0.05029523 0.4771091 -0.8452641 -0.2406146 0.6635588 -0.667862 -0.3371203 0.8650903 -0.240886 -0.4399918 1.48469e-7 -1 2.79844e-7 0 -1 -1.39922e-7 -0.3051308 -0.939686 0.1545491 -0.3053466 -0.9396007 0.1546418 -0.1550657 -0.9847784 0.0785247 -0.07758015 -0.9962121 0.03927838 -0.07751721 -0.9962183 0.03924685 -0.1549472 -0.9848018 0.07846552 -0.573576 -0.7659073 0.2905113 -0.6835753 -0.6425266 0.3462435 -0.6836704 -0.6424078 0.3462758 -0.5733674 -0.7660972 0.2904223 -0.4457929 -0.866194 0.2257805 -0.4455506 -0.8663501 0.2256593 -0.8381428 -0.3424535 0.4245496 -0.8786691 -0.1727368 0.4450874 -0.8381271 -0.3425206 0.4245265 -0.7721691 -0.5007913 0.3911049 -0.8786737 -0.1727072 0.4450897 -0.8887648 -0.08606261 0.4502115 -0.8887718 -0.08597177 0.450215 -0.8920746 0 0.4518882 -0.8920742 0 0.451889 -0.822658 0.3861655 0.4172651 -0.8207253 0.3915628 0.4160392 -0.8787177 0.1735644 0.4446692 -0.8894614 0.07651245 0.4505599 -0.8894594 0.07654279 0.4505589 -0.8796549 0.1663296 0.4455803 -0.7181233 0.5934818 0.3634259 -0.6922105 0.6298899 0.3522549 -0.5624146 0.7768146 0.2832826 -0.3478263 0.920914 0.1758816 -0.5291973 0.8049354 0.268383 -0.3430027 0.9232294 0.1731951 -0.1543651 0.9848788 0.07864743 -0.1480187 0.9861401 0.0749554 -0.07016313 0.9969028 0.03552407 0 1 0 0 1 1.39922e-7 0.1003465 0.9936069 -0.05172967 0.0875597 0.9951718 -0.04434442 0.2014886 0.9742074 -0.1015988 0.5813233 0.7587293 -0.2939271 0.4106341 0.8876472 -0.2084758 0.3992523 0.8943655 -0.2017625 0.8624486 0.2572788 -0.4358785 0.866656 0.2360361 -0.4395387 0.7665551 0.5106502 -0.3893967 0.8877789 0.09805881 -0.4497033 0.8867571 0.1127978 -0.4482616 0.7544018 0.5344811 -0.3810616 0.5953973 0.7442696 -0.302597 0.2149129 0.9704958 -0.1093181 0.8920747 0 -0.4518882 0.8920746 0 -0.4518882 0.8860015 -0.1128903 -0.4497302 0.887771 -0.09814947 -0.4496994 0.867075 -0.2360949 -0.4386799 0.7535277 -0.5344889 -0.3827762 0.5962142 -0.7442607 -0.3010064 0.5808941 -0.7587269 -0.2947807 0.2153148 -0.9704886 -0.1085882 0.2011221 -0.9742065 -0.1023312 0.3988596 -0.8943747 -0.202497 0.4110265 -0.8876378 -0.2077411 0.101109 -0.9936032 -0.05029511 0.7674379 -0.5106487 -0.3876559 0.861626 -0.2573403 -0.4374662 0 -1 0 0 -1 -1.39922e-7 -0.3050405 -0.9397203 0.1545193 -0.3050683 -0.9397116 0.1545178 -0.154883 -0.9848121 0.07846391 -0.07776188 -0.9961944 0.03936922 -0.07770127 -0.9962003 0.03933894 -0.1548536 -0.9848191 0.07843393 -0.5734794 -0.7659921 0.2904782 -0.6832448 -0.6429587 0.3460935 -0.6834146 -0.6427326 0.3461783 -0.573208 -0.7662408 0.2903578 -0.4460107 -0.8660494 0.2259047 -0.4459169 -0.866106 0.225873 -0.8382006 -0.3422385 0.424609 -0.8785005 -0.1738079 0.4450031 -0.8382712 -0.3420593 0.4246138 -0.7724995 -0.5001165 0.3913159 -0.7725113 -0.5000936 0.3913218 -0.8785353 -0.1736256 0.4450054 -0.8886877 -0.08713221 0.4501578 -0.8886831 -0.08719277 0.4501554 -0.892075 0 0.4518874 -0.892074 0 0.4518894 -0.8867415 0.1128913 0.4482691 -0.887771 0.09814947 0.4496994 -0.8666359 0.2361 0.439544 -0.7543764 0.5345153 0.3810641 -0.5953973 0.7442696 0.302597 -0.5813233 0.7587293 0.2939271 -0.2149484 0.9704877 0.1093206 -0.2014886 0.9742074 0.1015988 -0.3992523 0.8943655 0.2017625 -0.4106595 0.8876361 0.2084732 -0.0875597 0.9951718 0.04434442 -0.1003463 0.9936053 0.05176013 -0.7665523 0.5106788 0.3893647 -0.8624204 0.2573711 0.4358797 0 1 0 0 1 1.39922e-7 0.1003463 0.9936053 -0.05176013 0.4106595 0.8876361 -0.2084732 0.8624204 0.2573711 -0.4358797 0.8666436 0.2360938 -0.4395324 0.7665523 0.5106788 -0.3893647 0.8877736 0.09811925 -0.4497007 0.8867384 0.1129214 -0.4482676 0.2149484 0.9704877 -0.1093206 0.8920739 0 -0.4518898 0.8920757 0 -0.4518858 -0.3292676 -0.92939 0.1667854 -0.3293025 -0.9293717 0.1668181 -0.1871101 -0.9777579 0.09476053 -0.11283 -0.9919704 0.05713218 -0.1128298 -0.9919687 0.05716264 -0.5830134 -0.7568828 0.2953369 -0.6876285 -0.6370581 0.3483158 -0.687664 -0.6370018 0.3483489 -0.4622693 -0.8552608 0.2341713 -0.4622486 -0.855279 0.2341457 -0.8764677 -0.1862623 0.4439715 -0.8764378 -0.1864391 0.4439564 -0.8352941 -0.3510683 0.4231253 -0.8353033 -0.3510593 0.4231145 -0.7718701 -0.5013448 0.390986 -0.7717956 -0.5014886 0.3909487 -0.8491168 0.3066 0.4301129 -0.8827731 0.1440514 0.4471699 -0.849138 0.3065052 0.4301387 -0.8918754 -0.02124166 0.4517822 -0.8918874 -0.02093601 0.4517728 -0.8827391 0.1442645 0.4471682 -0.7115021 0.6032188 0.3604053 -0.7115224 0.6031796 0.3604306 -0.6124573 0.727087 0.3102266 -0.7921225 0.4599224 0.4012647 -0.7920986 0.4599872 0.4012376 -0.4959051 0.8312492 0.2512028 -0.6125169 0.7270242 0.3102564 -0.3650965 0.9124208 0.1849134 -0.4959726 0.8311989 0.2512366 -0.3650701 0.9124309 0.1849155 -0.2973444 0.9428166 0.1506101 -0.2251725 0.9676192 0.1140632 -0.2251729 0.9676191 0.1140633 0.06875932 0.9970254 -0.03482216 0.06872892 0.9970275 -0.03482222 -0.07962334 0.9960095 0.04031521 -0.1531444 0.9851539 0.07757931 -0.1531742 0.9851493 0.07757896 0.3540799 0.917855 -0.1793594 0.4854643 0.8389649 -0.2458909 0.4854089 0.8390051 -0.2458631 0.3540285 0.9178798 -0.1793337 0.2140036 0.970799 -0.1084057 0.2140612 0.9707832 -0.1084344 0.7846881 0.4756776 -0.3974866 0.7847707 0.4755196 -0.3975126 0.702157 0.6168251 -0.3556717 0.7021439 0.6168441 -0.355665 0.6017801 0.7382014 -0.304827 0.6018679 0.7381054 -0.3048862 0.8796721 0.1661745 -0.4456041 0.8439225 0.3241161 -0.4274852 0.8796302 0.1664528 -0.4455832 0.8889 0.08429378 -0.4502791 0.8888909 0.08441501 -0.4502745 0.8920744 0 -0.4518888 0.8920744 0 -0.4518888 0.8459601 -0.3173686 -0.4285193 0.8803609 -0.1615388 -0.4459486 0.8891881 -0.08048015 -0.4504081 0.8891816 -0.08057111 -0.4504047 0.8803322 -0.1616918 -0.4459496 0.713121 -0.6008089 -0.36123 0.6158714 -0.7234506 -0.3119642 0.6159709 -0.7233378 -0.3120293 0.7130799 -0.600861 -0.3612246 0.7902297 -0.4640116 -0.4002878 0.7902651 -0.4639229 -0.4003208 0.2459841 -0.9612306 -0.1246096 0.2459564 -0.9612414 -0.1245805 0.3814897 -0.9039475 -0.1932474 0.3816366 -0.9038731 -0.1933056 0.5048736 -0.8244367 -0.2557481 0.504976 -0.8243627 -0.255784 0.1050449 -0.9930439 -0.05319386 0.03323489 -0.9993062 -0.01681584 0.03323489 -0.9993056 -0.01684629 -0.03874802 -0.9990562 0.01962804 -0.03874772 -0.9990563 0.01962816 0.8920744 0 -0.4518886 0.8920746 -2.56403e-6 -0.4518882 0.8920746 6.51404e-7 -0.4518883 0.8920746 5.54535e-7 -0.4518883 0.4518875 0 0.892075 0.4518875 0 0.892075 0.8920746 3.16113e-7 -0.4518884 0.8920745 0 -0.4518885 0.8920747 -2.37225e-7 -0.4518882 0.8920744 0 -0.4518887 -0.451888 0 -0.8920747 -0.4518884 0 -0.8920745 0.8920747 0 -0.4518882 0.8920747 6.58623e-7 -0.4518879 0.8920744 -1.23668e-6 -0.4518888 0.8920746 2.99605e-7 -0.4518883 0.8920739 1.91e-6 -0.4518895 0.8920747 -2.54965e-6 -0.451888 0.8920746 2.54846e-6 -0.4518881 0.8920742 0 -0.4518889 0.892075 0 -0.4518874 0.4518871 -1.32502e-6 0.8920752 0.4518832 1.69247e-6 0.8920772 0.4518904 0 0.8920736 0.4518919 0 0.8920727 0.4518868 -4.31634e-7 0.8920753 0.8920753 0 -0.4518868 0.892073 0 -0.4518914 0.8920754 -6.38306e-7 -0.4518867 0.4518961 0 0.8920706 0.4518885 0 0.8920745 0.8920734 0 -0.4518905 0.8920759 0 -0.4518856 -0.4518851 0 -0.8920763 -0.4518897 0 -0.8920739 0.892074 0 -0.4518895 0.8920746 0 -0.4518883 -0.4518852 -1.30455e-6 -0.8920762 -0.4518884 1.81344e-6 -0.8920746 -0.4518883 0 -0.8920747 -0.4518883 0 -0.8920747 -0.4518894 4.43253e-7 -0.8920741 0.8920739 -1.9563e-6 -0.4518896 0.892075 3.95044e-6 -0.4518876 0.8920748 0 -0.4518879 0.892075 -4.4953e-6 -0.4518874 0.892075 -8.01656e-6 -0.4518873 0.8920738 0 -0.4518899 0.892075 0 -0.4518874 -0.4518849 2.33091e-6 -0.8920764 -0.4518872 -2.86034e-7 -0.8920751 -0.45189 -1.65472e-5 -0.8920737 -0.4518764 6.8146e-5 -0.8920806 -0.4518555 0 -0.8920912 -0.451888 4.22193e-5 -0.8920748 -0.4518899 -2.07265e-4 -0.8920737 -0.4518825 5.8175e-5 -0.8920775 -0.4518989 1.44018e-4 -0.8920693 -0.4518884 4.42053e-5 -0.8920745 -0.4518874 -9.83522e-5 -0.892075 -0.4518885 -1.04193e-4 -0.8920745 -0.4518855 6.63924e-5 -0.8920761 -0.4518878 -2.99174e-5 -0.8920749 -0.4518867 -2.54308e-5 -0.8920753 -0.4518935 2.73494e-5 -0.8920719 -0.4518915 0 -0.8920729 -0.4518879 1.64043e-5 -0.8920748 -0.4518934 9.54108e-6 -0.892072 -0.4518797 0 -0.8920789 -0.4518882 0 -0.8920746 -0.4518945 -1.72624e-6 -0.8920713 -0.4518783 0 -0.8920797 -0.4518974 3.43596e-7 -0.89207 -0.8920742 3.74672e-6 0.4518888 -0.8920749 -3.70521e-6 0.4518877 -0.8920748 -1.89148e-6 0.4518878 -0.8920744 7.3179e-6 0.4518888 -0.8920748 -3.81376e-6 0.4518877 -0.8920746 -3.60855e-6 0.4518882 -0.8920746 0 0.4518884 -0.8920744 0 0.4518886 -0.8920742 1.68775e-6 0.4518889 -0.8920744 6.99101e-6 0.4518886 -0.892075 -1.37363e-5 0.4518876 -0.8920746 0 0.4518883 -0.8920745 1.34794e-5 0.4518886 -0.8920747 -6.46991e-6 0.4518882 -0.8920744 0 0.4518887 -0.8920746 -1.98268e-6 0.4518883 -0.8920746 1.26611e-5 0.4518883 -0.8920755 0 0.4518863 -0.892074 2.24282e-6 0.4518894 -0.8920753 0 0.451887 -0.8920737 0 0.4518902 -0.8920745 -4.64608e-6 0.4518885 -0.8920741 0 0.4518893 -0.8920752 0 0.4518871 -0.4518877 0 -0.892075 -0.4518878 0 -0.8920748 -0.8920745 -1.28753e-7 0.4518883 -0.8920746 0 0.4518883 -0.8920744 0 0.4518885 0.4518877 0 0.8920748 0.4518877 0 0.892075 -0.8920747 0 0.4518882 -0.8920745 0 0.4518884 -0.8920745 4.69975e-7 0.4518885 -0.8920747 -5.40494e-7 0.4518883 -0.8920747 0 0.4518882 -0.4518927 5.36069e-5 -0.8920723 -0.4518876 8.18988e-5 -0.8920749 -0.4518822 0 -0.8920777 -0.4518856 -1.23565e-5 -0.892076 -0.4518843 0 -0.8920766 -0.4518907 -5.41368e-5 -0.8920734 -0.4518877 0 -0.8920749 -0.4518862 1.07259e-5 -0.8920757 -0.4518866 0 -0.8920754 -0.4518887 -5.20183e-6 -0.8920743 -0.4518796 -1.7059e-4 -0.8920791 -0.4518896 0 -0.892074 -0.4518903 0 -0.8920736 -0.451887 -1.61412e-4 -0.8920753 -0.4518871 1.94521e-5 -0.8920751 -0.4518876 2.90509e-6 -0.892075 -0.4518873 0 -0.892075 -0.4518896 0 -0.8920738 -0.4518875 0 -0.892075 -0.4518885 -9.33538e-6 -0.8920745 -0.4518879 6.90117e-7 -0.8920748 -0.4518874 -2.55199e-6 -0.892075 -0.4518885 -1.93979e-5 -0.8920745 -0.4518883 1.31228e-5 -0.8920746 -0.4518873 3.17169e-6 -0.8920751 -0.4518879 0 -0.8920748 -0.4518864 0 -0.8920756 -0.4518868 5.15487e-5 -0.8920754 -0.4518923 3.53976e-5 -0.8920725 -0.4518908 -3.21987e-5 -0.8920733 -0.4518923 -4.66457e-5 -0.8920726 -0.4518339 8.0843e-5 -0.8921022 -0.451896 -1.9137e-4 -0.8920707 -0.4518896 6.06877e-6 -0.892074 -0.4518832 0 -0.8920772 -0.4518897 -5.88405e-5 -0.8920738 -0.4518883 1.40262e-5 -0.8920747 -0.4518867 4.67684e-6 -0.8920754 -0.4518869 1.08688e-5 -0.8920754 -0.4518808 0 -0.8920783 -0.4518878 -1.31703e-5 -0.8920748 -0.451892 -3.90361e-6 -0.8920728 -0.4518843 1.27349e-6 -0.8920766 -0.4518945 1.56449e-6 -0.8920714 -0.451875 4.98033e-6 -0.8920813 -0.4518896 7.73762e-6 -0.892074 -0.4518928 -4.70036e-6 -0.8920723 -0.451884 7.30882e-6 -0.8920767 -0.4518876 0 -0.892075 -0.4518882 -6.6688e-7 -0.8920746 -0.4518901 8.10696e-6 -0.8920737 -0.4518873 3.80601e-6 -0.8920751 -0.4518812 -8.32516e-6 -0.8920782 -0.4518882 -1.62544e-5 -0.8920747 -0.4518922 -1.25935e-5 -0.8920725 -0.4518875 1.13351e-5 -0.892075 -0.4518928 -4.4605e-6 -0.8920723 -0.4518869 1.15426e-5 -0.8920754 -0.4518887 9.3176e-6 -0.8920745 -0.451878 -1.06435e-5 -0.8920798 -0.4518935 -2.47503e-6 -0.892072 -0.4518929 -1.79829e-5 -0.8920723 -0.4518803 2.92947e-5 -0.8920786 -0.4518889 -1.55681e-6 -0.8920743 -0.4518932 -3.4063e-6 -0.8920721 -0.4518843 -2.26021e-6 -0.8920766 -0.4518854 4.13828e-6 -0.892076 -0.4519343 -3.38604e-5 -0.8920513 -0.4518861 8.70025e-6 -0.8920757 -0.4518908 -6.3638e-7 -0.8920733 -0.4518868 1.27712e-6 -0.8920753 -0.4518893 1.8867e-6 -0.892074 -0.4518854 1.27378e-6 -0.8920761 -0.4518796 7.75733e-5 -0.892079 -0.4518978 7.54891e-6 -0.8920697 -0.4518802 -6.31536e-7 -0.8920786 -0.4518868 8.98076e-6 -0.8920753 -0.4518992 -6.68985e-5 -0.892069 -0.4518882 -8.69616e-6 -0.8920747 -0.451888 -2.61367e-5 -0.8920747 -0.4518878 3.72577e-6 -0.8920748 -0.451888 -3.54825e-5 -0.8920747 -0.4518867 2.87504e-5 -0.8920755 -0.4518869 0 -0.8920753 -0.4518893 -4.03189e-6 -0.8920741 -0.4518871 -2.29933e-6 -0.8920752 -0.4518892 -1.07692e-6 -0.8920742 -0.4518898 7.77271e-7 -0.8920738 -0.4518866 -5.35739e-7 -0.8920754 -0.4518883 3.82287e-6 -0.8920746 -0.4518872 2.73924e-6 -0.8920752 -0.4518907 -7.28965e-6 -0.8920734 -0.4518879 5.09497e-6 -0.8920748 -0.4518877 0 -0.8920749 -0.4518873 -8.8448e-6 -0.8920751 -0.4518886 0 -0.8920744 -0.4518642 5.85735e-5 -0.8920869 -0.4518896 9.04571e-6 -0.892074 -0.4518864 -2.34498e-6 -0.8920755 -0.451888 1.16632e-5 -0.8920747 -0.4518871 -2.34403e-6 -0.8920753 -0.4518885 -4.1448e-5 -0.8920744 -0.45189 2.36269e-5 -0.8920736 -0.4518872 3.05203e-5 -0.8920752 -0.4518871 -6.04215e-6 -0.8920752 -0.4518882 1.28431e-6 -0.8920747 -0.451897 0 -0.8920702 -0.4518883 -1.87436e-5 -0.8920745 -0.4518864 0 -0.8920755 -0.4518861 -1.32052e-5 -0.8920757 -0.451887 1.28822e-5 -0.8920753 -0.4518858 -6.93289e-6 -0.8920759 -0.4518911 1.35621e-5 -0.8920732 -0.4518889 4.58478e-6 -0.8920742 -0.4518911 -5.1023e-5 -0.8920731 -0.451886 -2.72458e-6 -0.8920757 -0.4518872 -7.12936e-6 -0.8920751 -0.451893 7.64107e-6 -0.8920722 -0.4518861 -2.82027e-6 -0.8920756 -0.4518834 0 -0.892077 -0.451887 3.8738e-6 -0.8920752 -0.4518905 -9.8987e-6 -0.8920734 -0.4518874 1.02867e-5 -0.892075 -0.451888 3.32659e-5 -0.8920747 -0.4518898 1.58731e-6 -0.8920739 -0.4518835 -5.78538e-5 -0.892077 -0.4518854 0 -0.892076 -0.4518844 -3.16938e-6 -0.8920766 -0.451889 4.21951e-5 -0.8920742 -0.4518741 8.77419e-5 -0.8920817 -0.4518852 -2.02212e-4 -0.8920761 -0.4518892 0 -0.8920742 -0.4519078 0 -0.8920648 -0.4519126 4.1522e-4 -0.8920623 -0.4517588 0 -0.8921402 -0.4520118 0.001525402 -0.8920106 -0.4518212 2.34488e-4 -0.8921085 -0.4519007 -6.5337e-4 -0.892068 -0.4518921 1.21519e-4 -0.8920727 -0.4518949 -1.74745e-4 -0.8920711 -0.451889 -4.56161e-5 -0.8920742 -0.451891 0 -0.8920732 -0.4518884 1.00143e-5 -0.8920745 -0.4518932 0 -0.8920721 -0.4519023 -5.36856e-5 -0.8920676 -0.4518803 6.56519e-5 -0.8920787 -0.4518923 8.67965e-5 -0.8920725 -0.4518831 -9.23996e-5 -0.8920772 -0.451884 0 -0.8920767 -0.4518855 0 -0.892076 -0.4518868 -8.32376e-6 -0.8920754 -0.4518858 3.07524e-5 -0.8920758 -0.4518882 -4.16342e-5 -0.8920747 -0.451887 0 -0.8920753 -0.4518835 4.99724e-6 -0.892077 -0.4518849 0 -0.8920763 -0.4518901 -7.26977e-5 -0.8920737 -0.4518915 3.19127e-5 -0.892073 -0.4518812 -6.11138e-5 -0.8920782 -0.4518879 -1.97014e-5 -0.8920748 -0.4518893 0 -0.8920741 -0.4518874 -4.72597e-5 -0.892075 -0.4518856 4.23548e-5 -0.892076 -0.4518875 8.28584e-6 -0.892075 -0.4518813 1.29546e-5 -0.8920781 -0.4518867 3.09778e-5 -0.8920754 -0.4518942 -3.33928e-5 -0.8920717 -0.4518891 2.8876e-6 -0.8920742 -0.4518859 8.50353e-6 -0.8920757 -0.4518893 0 -0.8920741 -0.4518884 1.01275e-5 -0.8920745 -0.451888 0 -0.8920747 -0.451888 -2.44426e-6 -0.8920747 -0.4518882 -1.33524e-5 -0.8920747 -0.4518864 0 -0.8920755 -0.4518873 5.18999e-5 -0.8920751 -0.4518878 0 -0.8920749 -0.4518883 -1.14313e-5 -0.8920746 -0.4518878 -1.03046e-4 -0.8920748 -0.4518886 -1.57933e-6 -0.8920744 -0.4518871 0 -0.8920753 -0.4518882 -3.42687e-5 -0.8920747 -0.451885 7.08269e-6 -0.8920762 -0.4518871 -5.29462e-5 -0.8920753 -0.4518888 0 -0.8920744 -0.4518859 -6.29554e-6 -0.8920757 -0.4518856 2.81286e-4 -0.8920759 -0.4518613 0.001031339 -0.8920876 -0.4518995 -6.33743e-4 -0.8920688 -0.4518876 0 -0.8920749 -0.4518868 0 -0.8920753 -0.4518896 7.47265e-5 -0.8920739 -0.4518933 0 -0.892072 -0.4518888 -3.36278e-5 -0.8920742 -0.4518987 2.05531e-4 -0.8920693 -0.4518885 0 -0.8920745 -0.4518939 -3.73868e-5 -0.8920717 -0.4518886 0 -0.8920745 -0.4518887 -1.79326e-6 -0.8920744 -0.4518869 -1.82345e-5 -0.8920753 -0.4518857 0 -0.8920758 -0.4518877 0 -0.8920748 -0.4518881 0 -0.8920747 -0.4518859 5.12569e-5 -0.8920758 -0.451893 0 -0.8920722 -0.4518856 4.15972e-5 -0.892076 -0.4518857 0 -0.8920759 -0.451881 -3.67271e-4 -0.8920782 -0.4518892 0 -0.8920741 -0.4518877 -3.09572e-6 -0.892075 -0.4518876 8.41634e-6 -0.892075 -0.4518893 9.89931e-6 -0.8920741 -0.4518865 3.11152e-5 -0.8920755 -0.4518893 -2.72658e-5 -0.8920741 -0.4518887 0 -0.8920744 -0.4518881 -1.28333e-5 -0.8920748 -0.4518874 5.1029e-6 -0.892075 -0.4518892 0 -0.8920742 -0.4518873 -8.01451e-5 -0.892075 -0.4518874 2.63049e-5 -0.892075 -0.4518876 2.36809e-5 -0.8920749 -0.4518839 7.72955e-5 -0.8920768 -0.4518893 -2.35969e-5 -0.8920741 -0.4518885 -3.33645e-6 -0.8920745 -0.4518863 0 -0.8920755 -0.4518883 0 -0.8920746 -0.4518886 -3.37491e-6 -0.8920744 -0.451887 -1.14448e-5 -0.8920753 -0.4518879 1.2914e-5 -0.8920748 -0.4518884 1.04125e-5 -0.8920745 -0.4518878 0 -0.8920749 -0.4518879 0 -0.8920748 -0.4518775 -5.53322e-5 -0.89208 -0.4518877 0 -0.8920749 -0.4518879 4.07258e-6 -0.8920747 -0.451893 0 -0.8920723 -0.4518879 -5.26453e-6 -0.8920748 -0.451889 4.16085e-5 -0.8920743 -0.4518921 0 -0.8920726 -0.4518888 9.61492e-6 -0.8920744 -0.4518879 4.55803e-6 -0.8920748 -0.4518876 1.9946e-5 -0.8920749 -0.4518866 -1.0624e-4 -0.8920754 -0.4518876 0 -0.892075 -0.4518888 -8.9429e-5 -0.8920743 -0.4518881 0 -0.8920747 -0.4518826 2.66494e-5 -0.8920774 -0.4519059 1.27937e-4 -0.8920656 -0.4518787 6.01182e-5 -0.8920794 -0.451906 -4.53972e-5 -0.8920656 -0.451888 -6.09857e-6 -0.8920747 -0.4519214 5.8486e-5 -0.8920578 -0.4518876 -2.45536e-6 -0.892075 -0.4518874 1.86465e-6 -0.892075 -0.4519316 0 -0.8920527 -0.4518876 2.62067e-6 -0.8920749 -0.4518868 -2.65402e-5 -0.8920754 -0.4518841 0 -0.8920767 -0.4518889 8.41991e-5 -0.8920742 -0.4518876 0 -0.892075 -0.4518869 0 -0.8920753 -0.4518896 0 -0.8920739 -0.451888 0 -0.8920747 -0.4518873 3.97048e-6 -0.8920751 -0.4518874 -1.00701e-5 -0.892075 -0.4518879 2.3485e-6 -0.8920748 -0.4519196 3.6458e-4 -0.8920587 -0.4518861 6.8325e-6 -0.8920757 -0.4518884 0 -0.8920745 -0.4518876 8.7874e-7 -0.892075 -0.4518882 3.06388e-6 -0.8920747 -0.4518871 0 -0.8920753 -0.4518873 0 -0.8920751 -0.4518878 -8.57758e-7 -0.8920749 -0.4518896 -5.98424e-5 -0.892074 -0.4518843 1.07266e-4 -0.8920766 -0.4518882 0 -0.8920747 -0.4518873 0 -0.8920751 -0.4518879 0 -0.8920748 -0.4518892 4.51692e-5 -0.8920741 -0.4518878 0 -0.8920748 -0.4518871 -1.22341e-5 -0.8920751 -0.4518864 -2.34686e-6 -0.8920755 -0.4518871 -3.28046e-5 -0.8920753 -0.4518833 1.81114e-5 -0.8920771 -0.4518894 3.23205e-5 -0.8920741 -0.4518423 0 -0.8920979 -0.4518861 3.01424e-6 -0.8920757 -0.4518848 -9.09628e-6 -0.8920763 -0.4518854 0 -0.8920761 -0.4518865 1.38843e-5 -0.8920755 -0.4518929 -6.45043e-6 -0.8920722 -0.4519017 2.51436e-6 -0.8920677 -0.4518819 0 -0.8920778 -0.4519113 1.83316e-5 -0.892063 -0.4518979 6.99123e-6 -0.8920697 -0.4518908 2.65226e-6 -0.8920733 -0.4519019 -2.75013e-5 -0.8920677 -0.4518874 0 -0.892075 -0.4518892 1.75409e-5 -0.8920741 -0.4518911 6.57924e-7 -0.8920732 -0.4519121 0 -0.8920626 -0.4518792 -2.99887e-5 -0.8920791 -0.4518882 -2.37197e-5 -0.8920747 -0.4518883 5.00282e-6 -0.8920747 -0.4518885 2.42337e-6 -0.8920745 -0.4518867 1.62879e-5 -0.8920754 -0.4518868 -4.97706e-5 -0.8920753 -0.4518881 5.67163e-5 -0.8920746 -0.4518868 0 -0.8920754 -0.4518892 7.2981e-5 -0.8920741 -0.4518876 0 -0.892075 -0.451887 -3.81852e-5 -0.8920753 -0.451887 9.15155e-6 -0.8920753 -0.4518854 9.75924e-5 -0.8920761 -0.4518878 1.19759e-6 -0.8920748 -0.4518771 -6.47655e-5 -0.8920803 -0.4518921 -9.93866e-6 -0.8920726 -0.4518935 6.19839e-5 -0.892072 -0.4518875 2.43367e-5 -0.8920751 -0.4518867 2.09798e-6 -0.8920755 -0.4518883 -2.78126e-5 -0.8920746 -0.4518887 -1.89762e-5 -0.8920744 -0.4518878 -5.58483e-6 -0.8920749 -0.4518877 4.32018e-5 -0.892075 -0.4518872 -7.33152e-6 -0.8920751 -0.4518876 -4.78267e-6 -0.892075 -0.4518849 4.34589e-5 -0.8920763 -0.4518839 0 -0.8920768 -0.4518874 0 -0.892075 -0.4518872 0 -0.8920751 -0.4518888 -6.95233e-6 -0.8920743 -0.4518874 2.08779e-5 -0.8920751 -0.4518798 -3.07372e-5 -0.8920788 -0.4518878 -2.45668e-5 -0.8920748 -0.4518886 0 -0.8920745 -0.4518877 0 -0.8920748 -0.4518846 7.81617e-6 -0.8920765 -0.4518881 2.67081e-4 -0.8920747 -0.4518879 -3.7924e-6 -0.8920747 -0.451887 5.85642e-5 -0.8920753 -0.4518876 6.66039e-6 -0.892075 -0.451888 -5.68144e-6 -0.8920748 -0.4518872 0 -0.8920752 -0.4518879 0 -0.8920747 -0.451886 -3.9381e-5 -0.8920758 -0.4518904 0 -0.8920735 -0.451887 0 -0.8920753 -0.4518864 0 -0.8920755 -0.4518879 -1.92422e-5 -0.8920748 -0.4518876 -1.95998e-5 -0.892075 -0.4518871 -6.00032e-5 -0.8920751 -0.4518883 6.33204e-6 -0.8920747 -0.4518887 2.19143e-5 -0.8920744 -0.451888 -4.98909e-5 -0.8920748 -0.4518874 8.90026e-6 -0.892075 -0.4518879 1.83852e-6 -0.8920748 -0.451887 0 -0.8920752 -0.4518901 -1.44637e-4 -0.8920737 -0.451887 4.69246e-6 -0.8920753 -0.4518616 -8.65209e-6 -0.8920881 -0.4518959 -5.25428e-6 -0.8920707 -0.4518924 -1.29847e-5 -0.8920725 -0.4518916 3.63577e-6 -0.8920729 -0.4518835 -3.72492e-6 -0.892077 -0.4518837 4.86918e-6 -0.8920769 -0.4518981 0 -0.8920696 -0.4518902 -1.39683e-6 -0.8920736 -0.451889 -6.69248e-6 -0.8920742 -0.4518825 -1.19937e-6 -0.8920775 -0.4518953 5.21528e-6 -0.8920711 -0.4518873 -4.5849e-6 -0.8920751 -0.4518854 6.49424e-6 -0.8920761 -0.4518924 3.12031e-6 -0.8920725 -0.4518842 1.97143e-6 -0.8920766 -0.4518814 4.68074e-6 -0.8920781 -0.4518839 2.54729e-5 -0.8920769 -0.4518885 0 -0.8920745 -0.4518968 1.34686e-5 -0.8920702 -0.8920741 1.25243e-6 0.4518894 -0.8920744 -1.25457e-6 0.4518886 -0.8920747 -1.26845e-6 0.4518881 -0.8920742 0 0.4518891 -0.8920744 0 0.4518887 -0.8920747 -1.01057e-6 0.4518882 -0.892076 0 0.4518854 -0.892075 0 0.4518875 -0.8920744 0 0.4518886 -0.8920741 0 0.4518892 -0.8920745 1.00519e-6 0.4518883 -0.8920739 -1.26683e-6 0.4518896 -0.8920746 -5.03148e-7 0.4518882 -0.8920748 0 0.451888 -0.8920749 -6.33547e-7 0.4518877 -0.8920747 3.77021e-7 0.451888 -0.8920732 1.26171e-6 0.4518913 -0.8920744 -9.59829e-7 0.4518887 -0.892075 -8.7475e-7 0.4518875 -0.8920738 3.18329e-7 0.4518899 -0.8920754 -3.54977e-6 0.4518869 -0.8920745 -9.14727e-7 0.4518885 -0.892074 -1.67269e-6 0.4518895 -0.8920758 -1.8905e-6 0.4518858 -0.8920744 1.93523e-6 0.4518887 -0.892073 -1.54953e-6 0.4518915 -0.8920745 -1.07873e-6 0.4518885 -0.8920744 -7.23596e-7 0.4518886 -0.8920755 1.07654e-6 0.4518865 -0.8920746 -1.58831e-6 0.4518884 -0.8920745 -3.41566e-6 0.4518883 -0.8920758 -2.95702e-6 0.4518859 -0.8920746 -4.75065e-7 0.4518883 -0.8920724 -1.03241e-6 0.4518927 -0.8920755 -9.07555e-7 0.4518865 -0.8920744 0 0.4518888 0.1797591 -0.8817659 0.4360914 0.200877 -0.92589 0.3199627 0.1689244 -0.9065459 0.3868324 0.1512864 -0.9116249 0.3821682 0.1510394 -0.9146296 0.3750198 0.1517696 -0.9249309 0.3485238 0.1704166 -0.9444329 0.2810776 0.1584868 -0.9347153 0.3181029 0.1403254 -0.9350349 0.325605 0.1933664 -0.9160186 0.3514533 0.1854056 -0.9000797 0.3943113 0.1189655 -0.9407368 0.3175871 0.1183842 -0.9399629 0.3200861 0.117195 -0.9471737 0.2985421 0.1230213 -0.9544147 0.2719531 0.1343455 -0.9611409 0.2411627 0.1113033 -0.9571418 0.2673783 0.0858801 -0.9621384 0.2586781 0.08936083 -0.961392 0.2602695 0.08502608 -0.9662332 0.2432368 0.08862721 -0.9713591 0.2204693 0.09827065 -0.976023 0.1942219 0.08182239 -0.9749107 0.2070128 0.05856692 -0.9781199 0.1996281 0.05221885 -0.9795237 0.1944398 0.05139392 -0.9816734 0.1835106 0.05264574 -0.985376 0.1620573 0.07443672 -0.9912694 0.1088321 0.03851455 -0.9897206 0.1377307 0.0606417 -0.9886707 0.137306 0.01818937 -0.9910183 0.1324837 0.01785391 -0.9922204 0.1232073 0.01699918 -0.994071 0.107397 -0.01123112 -0.9969773 0.07687836 0.00903362 -0.9965684 0.08227926 -0.008575916 -0.9973461 0.07230061 0.02240091 -0.9959876 0.08664339 0.03296077 -0.99746 0.06314426 -0.002349913 -0.999576 0.02902317 -0.008392632 -0.9990026 0.04385548 -0.009216666 -0.9970519 0.07617509 0.01937955 -0.9910447 0.1321169 -0.01782339 -0.9964926 0.08176177 -0.01086455 -0.9982317 0.058443 -0.01556485 -0.999174 0.03753882 -0.05172902 -0.9986603 0.001403808 -0.03518837 -0.9993752 0.003326535 -0.04550313 -0.9989638 -9.46075e-4 -0.03448647 -0.9988565 0.03311312 -0.029787 -0.9991161 0.02966493 -0.03293043 -0.9992365 0.02102786 -0.03195381 -0.9994201 0.0117805 -0.0272842 -0.9996274 -8.54539e-4 -0.04785424 -0.9988363 -0.00601226 -0.04587006 -0.998735 -0.02060031 -0.04754865 -0.998766 -0.01434391 -0.0581085 -0.9979162 -0.02804708 -0.0630216 -0.9978476 -0.01812821 -0.05764955 -0.9980179 -0.02523881 -0.04300105 -0.9987303 -0.02624619 -0.05188274 -0.9984382 -0.02072256 -0.05511748 -0.9978532 -0.03537166 -0.05755889 -0.9978812 -0.0303359 -0.05932873 -0.9977241 -0.03204482 -0.06851607 -0.9972828 -0.0270707 -0.06186228 -0.9975493 -0.03268599 -0.06186163 -0.9975384 -0.03302133 -0.06192338 -0.9975495 -0.03256392 -0.06793618 -0.9974355 -0.02252328 -0.06164848 -0.9975157 -0.03408974 -0.06967407 -0.9973191 -0.02237015 -0.06689786 -0.9976394 -0.0155037 -0.06405913 -0.9976934 -0.02246189 -0.06021338 -0.997718 -0.03054922 -0.06027531 -0.9978541 -0.02557504 -0.06454813 -0.9977651 -0.01727384 0.1867484 -0.8779525 0.4408227 0.1821104 -0.8843055 0.4299297 0.2052423 -0.8517635 0.4820526 0.205697 -0.8811708 0.4257075 0.208231 -0.8752236 0.4366047 0.2129316 -0.8947889 0.3924449 0.2198588 -0.8553866 0.469016 0.2114334 -0.8519594 0.4790211 0.207589 -0.8685659 0.4500001 -0.01952904 -0.9997345 0.01223921 -0.02707076 -0.9995628 0.01189154 -0.02801609 -0.9995188 0.01331919 -0.02735728 -0.9995103 0.01519119 -0.03506636 -0.9992848 0.01416081 -0.03387641 -0.9993253 0.01419144 -0.04382526 -0.9988566 0.01910489 -0.03372389 -0.9993266 0.01446616 -0.04574847 -0.9988369 0.0152291 -0.0479148 -0.9987649 0.01315367 -0.04950165 -0.9985482 0.02124112 -0.04028522 -0.9991045 0.0129401 -0.03378468 -0.9993196 0.01480174 -0.03335684 -0.9993321 0.01492357 -0.04318463 -0.9988628 0.0202037 -0.0332967 -0.9993286 0.0152902 -0.03357076 -0.9993113 0.01580876 -0.03390681 -0.9992907 0.01638877 -0.04287928 -0.9988584 0.02105814 -0.03466933 -0.9992474 0.01739573 -0.04355096 -0.9988036 0.0222485 -0.03515774 -0.9992185 0.01806712 -0.03628695 -0.9991583 0.01913535 -0.04416149 -0.9987458 0.02359145 -0.03659272 -0.9991436 0.01931875 -0.03674459 -0.9991248 0.01998978 -0.0444355 -0.9987012 0.02493393 -0.03796607 -0.9990514 0.02133303 -0.05113905 -0.9983003 0.02795583 -0.03772193 -0.9990527 0.02169924 -0.04361194 -0.9987419 0.02475106 -0.03671401 -0.9990916 0.02163773 -0.03796744 -0.999236 0.009268283 -0.03619569 -0.9991058 0.02185171 -0.03506678 -0.9991746 0.020509 -0.03274697 -0.999257 0.02032572 -0.03790438 -0.9991268 0.01757884 -0.03753864 -0.9990784 0.02081412 -0.05027157 -0.9983566 0.02750974 -0.02225655 -0.9996543 0.01399892 -0.02758425 -0.9994878 0.01622873 -0.02684295 -0.999528 0.01494526 -0.02662968 -0.9995775 0.01165771 -0.02033591 -0.9997513 0.00916475 -0.02754408 -0.9995254 0.01379418 -0.0238744 -0.9996732 0.009142696 -0.02387493 -0.9996731 0.009143531 0.001159727 -0.9999962 0.00250256 0.006622552 -0.9999762 -0.001983702 0.002075314 -0.9999977 6.10387e-4 -0.01965039 -0.9997308 0.01234233 0.5842597 -0.7595621 -0.2858429 0.8161556 -0.381953 -0.4335922 0.5808364 -0.7540009 -0.3067764 -0.02345901 -0.9996895 0.008397817 0.1683439 -0.9821385 -0.08404988 0.09497445 -0.9944545 -0.04516774 0.110997 -0.9925334 -0.05056965 0.1267157 -0.9898902 -0.06372404 -0.01378899 -0.9998136 0.01351511 -0.04194438 -0.9990032 0.01528054 -0.02731341 -0.9994971 0.01611691 -0.04324316 -0.9988525 0.02058464 -0.02991974 -0.9994603 0.01356613 0.8167652 -0.3813422 -0.4329814 0.8170319 -0.3821931 -0.4317259 -0.1053691 -0.9930393 0.05263406 -0.02078467 -0.9994729 0.02493762 0.00274074 -0.999833 0.01806932 0.007640957 -0.9999676 -0.00251019 0.05916285 -0.9982165 -0.007989168 0.03060197 -0.9995098 0.006615757 0.08483296 -0.9961091 -0.02387291 -0.01977604 -0.9995459 0.02273637 -0.01770079 -0.9995757 0.02313309 -0.01638871 -0.9995315 0.02584964 -0.06087702 -0.9977008 0.02978658 -0.08201986 -0.9957967 0.0407651 -0.02115088 -0.9995877 0.01942449 -0.01602113 -0.9994412 0.02933907 -0.02002292 -0.9993196 0.03097593 -0.01389449 -0.9994877 0.0288335 0.1091033 -0.9926244 -0.0528512 -0.01388734 -0.9994874 0.02884763 0.002227842 -0.999272 -0.03808724 -0.002838253 -0.9988342 -0.04818987 -0.009644091 -0.9993556 -0.03457838 0.08972513 -0.9947897 -0.04840272 0.05020326 -0.9980539 -0.03698867 0.06280827 -0.9977299 -0.02429318 0.09509867 -0.9947517 -0.03775256 0.07898437 -0.996613 -0.02288955 0.1705386 -0.9818482 -0.08301091 0.1760653 -0.9817423 -0.07199484 0.6327827 -0.7502506 -0.1915988 0.08069247 -0.9964791 -0.02276724 0.07742792 -0.9968276 -0.01843374 0.06613528 -0.9977977 -0.005096673 0.1027563 -0.9944509 -0.02255326 0.2135705 -0.9727563 -0.09018301 0.1907758 -0.9777454 -0.08728504 0.8388472 -0.3569511 -0.4110004 0.2402439 -0.9638444 -0.1152694 0.2727199 -0.9517732 -0.1405411 0.3043974 -0.5880419 -0.7493658 0.8777951 -0.1316296 -0.4605967 0.03518861 -0.9992591 -0.01559525 0.05517822 -0.9981219 -0.02661252 0.03289949 -0.9993464 -0.01498484 0.818037 -0.3817648 -0.4301989 0.8187784 -0.3816469 -0.4288912 0.5819802 -0.7540807 -0.3044035 0.828683 -0.3832274 -0.4079478 0.8292992 -0.382345 -0.4075233 0.5884128 -0.7539193 -0.2921921 0.8246878 -0.3826183 -0.416525 0.825356 -0.3819758 -0.4157909 0.585815 -0.7539144 -0.2973785 0.004486322 -0.9999696 -0.006378531 0.01040691 -0.9999182 -0.007446587 0.01391667 -0.9998038 -0.01409977 0.008209586 -0.9999578 -0.004120051 0.01916569 -0.99979 -0.007263422 0.02536141 -0.9996264 -0.0101934 0.005974173 -0.9999812 -0.001468122 0.8191214 -0.3818497 -0.428055 0.8199775 -0.3818036 -0.4264542 0.5826708 -0.7540661 -0.3031157 0.002807736 -0.9999952 0.001342833 0.007019281 -0.9999744 -0.001464843 0.0294575 -0.9994719 -0.01372098 0.04972267 -0.9984617 -0.02453553 0.09106743 -0.9948145 -0.04528957 0.1683412 -0.9818786 -0.08703935 0.3088212 -0.9371757 -0.1622692 -0.5742418 0.8061847 -0.1425228 -0.4181115 0.8702213 -0.260572 0.7199885 -0.6939858 5.49353e-4 0.7981292 -0.596552 -0.0843541 0.8645253 -0.4739674 -0.1671857 0.9390691 -0.2728702 -0.2090245 0.8387946 0.3397417 -0.4254401 0.9775488 -0.1245474 -0.1699594 0.9522306 0.1089231 -0.2852938 0.8765392 0.3231363 -0.3567378 0.7952746 0.4707007 -0.3820723 0.7306276 0.5665263 -0.3810921 0.1522006 -0.98523 -0.07846558 0.6993482 0.608462 -0.3750814 0.8175372 -0.3816373 -0.4312609 0.05768162 -0.9979844 -0.02646028 0.07071286 -0.9969691 -0.03244185 0.01797586 -0.9998132 -0.007110953 0.0441609 -0.9988238 -0.02002042 0.01062071 -0.9999372 -0.003601253 0.03265529 -0.9993446 -0.01562571 0.05493384 -0.9981181 -0.02725327 0.05478119 -0.9981164 -0.02761948 0.008057057 -0.9999628 -0.003082394 0.01748746 -0.9998099 -0.008636891 0.1692256 -0.9819057 -0.08499431 0.09116071 -0.9947723 -0.04602289 0.09094583 -0.994789 -0.04608327 0.05450677 -0.9981212 -0.02798581 0.03238058 -0.9993438 -0.01623606 0.03201442 -0.9993454 -0.01684647 0.01654154 -0.9998173 -0.009583055 0.05429279 -0.9981156 -0.02859604 0.03183114 -0.9993398 -0.0175178 0.02154642 -0.999681 -0.01318418 0.02539175 -0.9994968 -0.01901328 0.01644986 -0.9998102 -0.01043754 0.02487266 -0.9995766 -0.01510667 0.03466987 -0.9991396 -0.02276736 0.05444651 -0.9981054 -0.02865767 0.03112947 -0.9993488 -0.0182504 0.04681551 -0.9985384 -0.02700895 0.02938997 -0.9994124 -0.01764005 0.04968482 -0.9983973 -0.0271008 0.01608359 -0.9998107 -0.0109564 0.03164803 -0.9993408 -0.01779246 0.0285356 -0.9994483 -0.01699924 0.02758884 -0.9994855 -0.01635795 0.01605314 -0.9998138 -0.01071226 0.04709082 -0.9985824 -0.02481192 0.02624654 -0.9995363 -0.01544272 0.8603907 -0.3827994 -0.3364411 0.8618654 -0.3809726 -0.3347358 0.6116359 -0.7531537 -0.2422006 0.04159748 -0.9989197 -0.02072244 0.02240079 -0.9996739 -0.01226854 0.61459 -0.7529933 -0.2351177 0.8636869 -0.382189 -0.3285977 0.8650018 -0.3807558 -0.3267982 0.03326612 -0.9993283 -0.01538175 0.03347921 -0.9993413 -0.01400816 0.05676609 -0.9981066 -0.02368301 0.05804693 -0.9980905 -0.02111905 0.01715141 -0.9998205 -0.008056879 0.8681284 -0.3806703 -0.318502 0.617706 -0.7527223 -0.2277027 0.8669779 -0.381607 -0.3205084 0.02047789 -0.9997569 -0.008178949 0.05960333 -0.9980592 -0.01803666 0.03469955 -0.9993305 -0.01159703 0.008819997 -0.999961 -6.10384e-4 0.01577842 -0.9998713 -0.002929806 0.004333674 -0.9999825 0.004058957 0.03616476 -0.9993081 -0.008697807 0.01776224 -0.9998145 -0.007446706 0.005821049 -0.999976 0.003768444 0.01413035 -0.9998998 9.46094e-4 -3.6623e-4 -0.9999597 0.008972585 0.01348942 -0.9998971 0.00488305 0.06140458 -0.9980081 -0.01446604 0.1015971 -0.994517 -0.02478128 0.06347876 -0.9979296 -0.01034581 0.03790509 -0.9992675 -0.005279839 0.03988873 -0.9992033 -0.001342833 0.8808361 -0.378953 -0.2837646 0.6299503 -0.750929 -0.1981622 0.8794692 -0.3819772 -0.2839498 0.04196423 -0.9991154 0.002746701 0.01480156 -0.9998566 0.008240044 -2.74673e-4 -0.9999024 0.01397776 0.0202338 -0.99976 0.008392572 0.03671437 -0.9993156 0.00451678 0.8832796 -0.3786792 -0.2764407 0.6321467 -0.750348 -0.1933094 0.8821274 -0.3811545 -0.2767177 0.06744652 -0.9977203 -0.002288877 0.04498487 -0.9989757 0.004913508 0.06732487 -0.9977273 -0.002777218 0.05230885 -0.9986299 0.001495361 0.1059321 -0.9942539 -0.01541215 0.1892776 -0.9808744 -0.04538142 0.105046 -0.9943055 -0.01794511 0.05667406 -0.9983732 -0.006256401 0.08270734 -0.9964252 -0.01721286 0.06418067 -0.9979287 -0.00439465 0.08133339 -0.9965097 -0.01879972 0.1130736 -0.9928808 -0.03744703 0.8894446 -0.3777332 -0.2573053 0.8906764 -0.3761509 -0.2553553 0.6343069 -0.750096 -0.187112 0.8905907 -0.3793578 -0.2508706 0.8917745 -0.3766694 -0.2507162 0.08487445 -0.9960618 -0.02563625 0.09943121 -0.9946175 -0.02914571 0.8935705 -0.3756909 -0.2457402 0.6335451 -0.7502499 -0.1890655 0.8925088 -0.3781656 -0.2458031 0.08355998 -0.9946634 -0.06051844 0.04355031 -0.997812 -0.04974561 0.02526998 -0.9992333 -0.02990889 0.9024724 -0.3694305 -0.2215057 0.9072456 -0.3649492 -0.2090873 0.6423011 -0.7473777 -0.1699293 0.9063216 -0.3845694 -0.1751788 0.9157978 -0.361259 -0.1755174 0.9232596 -0.3657087 -0.1176811 0.6545449 -0.7439356 -0.1346506 0.9140266 -0.3872612 -0.1207654 0.9221721 -0.3566489 -0.1496668 0.1789332 -0.9815236 -0.06778281 0.08752787 -0.9947294 -0.05340784 0.08011162 -0.9944828 -0.067721 0.01886045 -0.9989036 -0.04284805 0.01388603 -0.9985135 -0.05270588 0.03906393 -0.9975047 -0.05880957 0.04556542 -0.9978922 -0.04620629 0.0388205 -0.9974924 -0.05917686 -0.01834201 -0.9993221 -0.03192311 -0.02359116 -0.9988251 -0.04232978 -0.02496421 -0.9992418 -0.02987772 -0.01483219 -0.9988845 -0.04483228 -0.01535105 -0.9988267 -0.0459311 0.01379466 -0.9984987 -0.05301195 0.01968467 -0.9989457 -0.04147517 -0.003204464 -0.9987961 -0.04895246 -0.02423179 -0.9987534 -0.04364162 -0.03024405 -0.9987268 -0.0403763 0.002319395 -0.9992718 -0.03808724 -0.01007127 -0.9993181 -0.03552424 0.01388633 -0.9997853 -0.01538175 -0.03543275 -0.998619 -0.03878986 -0.03009134 -0.9991485 -0.02822965 0.001098632 -0.9999089 -0.01345866 -0.01910489 -0.9992538 -0.03357088 -0.03097683 -0.9986441 -0.04184156 -0.02600187 -0.9991492 -0.03201401 -0.03134286 -0.9990361 -0.03073251 -0.03622627 -0.9985277 -0.0403769 0.01840293 -0.9996178 0.02063077 -0.00814855 -0.9998957 -0.0119329 -0.04324758 -0.9982302 -0.04081839 -0.03994941 -0.9987969 -0.02844375 -0.04358154 -0.9983167 -0.03827118 -0.03567695 -0.9989249 -0.0296036 -0.04610836 -0.9981629 -0.03930604 -0.04394668 -0.9986588 -0.0273751 -0.04712194 -0.9981984 -0.03714209 -0.04977726 -0.9980381 -0.03797852 0.3855848 -0.8257694 0.4116181 0.6516814 -0.4705181 0.5949153 0.4164725 -0.7553943 0.5058954 -0.04651147 -0.9985632 -0.02661287 -0.05020332 -0.9980852 -0.03613418 0.06131231 -0.9902445 0.1251271 0.07150709 -0.9895021 0.1255876 0.1053513 -0.9755986 0.1926355 0.009308397 -0.9975857 0.06882107 -0.01318407 -0.9996128 0.02450656 0.01397752 -0.9975627 0.06836169 -0.03619593 -0.9993258 -0.006164908 -0.04822033 -0.9984967 -0.02606338 -0.01995939 -0.9994667 0.02584958 -0.03784406 -0.9992676 -0.005676567 -0.04855543 -0.9984844 -0.02591043 -0.02163827 -0.9994205 0.02627724 0.002349972 -0.9975584 0.06979793 -0.05276799 -0.9979835 -0.03528034 -0.05334669 -0.9979624 -0.03500497 6.10375e-4 -0.9975354 0.07016253 -0.02206528 -0.999408 0.02639895 0.222091 -0.8607745 0.4579769 -0.03994965 -0.999169 0.008087575 -0.03967499 -0.9991089 0.01440507 -0.04654163 -0.9986767 0.02188217 -0.05079925 -0.9983083 0.02828717 -0.05191761 -0.9982653 0.02776873 -0.0531305 -0.9982635 0.02543842 -0.05237835 -0.9982653 0.02689123 -0.05158036 -0.9983301 0.02600896 -0.05183106 -0.9983363 0.02526628 -0.05287551 -0.9983408 0.02280104 -0.05396449 -0.9982545 0.02399736 -0.04958516 -0.9987139 0.01057678 -0.06192314 -0.9976685 -0.02868789 -0.05972659 -0.9978649 -0.02642983 -0.07181072 -0.9971105 -0.02478122 -0.06714099 -0.997624 -0.01544243 -0.07723617 -0.9967212 -0.02411961 -0.05670481 -0.9983776 0.005188226 -0.04034572 -0.9984816 0.03750753 0.0109564 -0.9903833 0.1379169 0.1455775 -0.9072805 0.3945242 0.04425299 -0.978327 0.202282 0.07809942 -0.96048 0.2671679 0.2243155 -0.8697338 0.4395974 0.2253201 -0.8762551 0.42592 0.1114853 -0.9372025 0.3304883 0.2347885 -0.8282148 0.5088561 0.2084431 -0.8397544 0.5013623 -0.0342428 -0.9993591 0.0104376 -0.03875863 -0.9992408 0.003967404 -0.05114209 -0.9982838 0.02853012 -0.03741669 -0.9990811 0.02090573 -0.05120277 -0.998328 0.02682805 -0.03769052 -0.9990896 0.01998972 -0.04617512 -0.9986107 0.02539175 -0.03906482 -0.9990838 0.01748758 -0.047365 -0.9986027 0.02343833 -0.03854578 -0.9990777 0.01892191 -0.04684597 -0.9985985 0.02462846 -0.03201454 -0.9993788 0.0147407 -0.03949111 -0.9990895 0.01614433 -0.04907423 -0.9986066 0.01940995 -0.04806691 -0.9986025 0.02197343 -0.05220252 -0.9983469 0.02405315 -0.05556565 -0.9982663 0.01941531 -0.03845369 -0.9991566 0.01440489 -0.04727345 -0.9987859 0.01385545 -0.05496436 -0.9980875 -0.02829092 -0.05578947 -0.9979243 -0.03216743 -0.07723528 -0.9967211 -0.02412277 -0.06286931 -0.9975772 -0.02978658 -0.05823016 -0.998092 -0.02053922 -0.0478841 -0.9988529 0 -0.03161782 -0.9989843 0.03210616 0.1187503 -0.9389244 0.3229851 0.1518015 -0.9100767 0.3856381 0.05240058 -0.9791619 0.1962047 0.1800964 -0.8753948 0.4486082 0.08585166 -0.9616121 0.2606375 -0.03841519 -0.9992485 0.005194664 -0.036071 -0.9993475 0.001852393 -0.03048855 -0.9993774 0.01776206 -0.03079372 -0.9993781 0.01718223 -0.03112941 -0.999377 0.01663285 -0.0315566 -0.9993755 0.01590037 -0.03299081 -0.9993688 0.01318407 -0.03271609 -0.9993683 0.01388603 -0.05154663 -0.9982172 -0.03009176 -0.05264592 -0.9980447 -0.03369337 -0.05633836 -0.9978544 -0.03335744 -0.05169922 -0.9983695 -0.02420157 -0.04138398 -0.9991363 -0.00375384 -0.002838253 -0.99739 0.07214677 -0.02514767 -0.9992851 0.02823007 0.1571419 -0.9118748 0.3791975 0.1247922 -0.9401074 0.3172146 0.02563613 -0.991447 0.127967 0.05847531 -0.9796756 0.191876 0.09152597 -0.9623201 0.256053 0.2122913 -0.84828 0.4851325 -0.03688025 -0.9992938 0.007213532 -0.03380376 -0.9994246 0.002795815 -0.02845418 -0.9994522 0.01690304 -0.02862256 -0.9994536 0.01653271 -0.02862513 -0.9994536 0.01653504 -0.02890539 -0.9994544 0.01598143 -0.02928751 -0.9994551 0.01522833 -0.02976965 -0.9994549 0.0142734 -0.03057193 -0.999459 0.01213204 -0.03135561 -0.999435 0.01211631 -0.03241074 -0.9993827 0.0135644 -0.05334681 -0.9979646 -0.03494399 -0.04873824 -0.9984779 -0.0258187 -0.05516111 -0.9978173 -0.03630328 -0.03845363 -0.9992458 -0.00540179 -0.02218723 -0.9994021 0.0265209 0.09430253 -0.9626185 0.253915 9.15574e-5 -0.9975183 0.07040762 0.02847421 -0.9915928 0.1262266 0.1864722 -0.8803568 0.4361193 0.06128174 -0.9798678 0.1900101 -0.03536981 -0.9993319 0.009205758 -0.03232985 -0.9994657 0.004823923 -0.02844059 -0.9994528 0.01689201 -0.02696168 -0.999504 0.01627212 -0.02890592 -0.9994544 0.01598173 -0.02701455 -0.9995123 0.01566916 -0.02707844 -0.9995094 0.01574176 -0.02928584 -0.9994551 0.01522666 -0.02976906 -0.9994549 0.01427268 -0.02773779 -0.999511 0.01444101 -0.03035444 -0.9994532 0.01311874 -0.02821958 -0.9995108 0.01349133 -0.03106093 -0.9994232 0.01373982 -0.02932709 -0.9995059 0.01130533 -0.05014312 -0.998254 -0.03122115 -0.05511367 -0.9978172 -0.03637689 -0.03388661 -0.9993637 0.01113337 -0.03097689 -0.9994964 0.006887257 -0.02677047 -0.999513 0.01603555 -0.02665007 -0.9995166 0.0160135 -0.02735769 -0.9995104 0.01519167 -0.02773857 -0.9995109 0.01444202 -0.02821987 -0.9995107 0.01349174 -0.02880191 -0.999509 0.01234167 -0.02880209 -0.999509 0.01234197 -0.02898806 -0.9995223 0.01072335 -0.03094297 -0.9994702 0.01008993 -0.03250598 -0.9993891 0.01284337 -0.02983933 -0.9995145 0.008970916 -0.02634054 -0.9995273 0.015854 -0.02677232 -0.9995234 0.01537561 -0.02719068 -0.9995298 0.01417928 -0.02648741 -0.9995294 0.0154761 -0.02683711 -0.9995284 0.01492559 -0.02718502 -0.9995302 0.01416039 -0.02763909 -0.9995307 0.01321345 -0.02870821 -0.9995218 0.01149773 -0.02879703 -0.9995254 0.01095008 -0.04022425 -0.9989236 -0.02310299 -0.05200374 -0.9980815 -0.03360098 -0.05334764 -0.9978823 -0.03721415 -0.04800695 -0.998503 -0.02621614 -0.03784406 -0.9992671 -0.00576812 0.02914583 -0.9916313 0.1257698 0.2134825 -0.850634 0.4804654 -0.03128093 -0.999409 0.01425772 -0.02903515 -0.999518 0.01098507 -0.02679997 -0.9995222 0.01540476 -0.02711468 -0.9995251 0.01464247 -0.0276339 -0.999531 0.01319628 -0.0281893 -0.99953 0.01205122 -0.02807623 -0.9995246 0.01274502 -0.02818375 -0.9995304 0.01203292 -0.02896487 -0.9995417 0.008803844 -0.05335199 -0.9978795 -0.03728514 -0.02908474 -0.9993801 -0.01983743 0.0356763 -0.9987839 -0.03402829 0.008942067 -0.9996251 -0.02588021 -0.02151566 -0.9994272 0.026124 7.32456e-4 -0.9975438 0.07004106 0.1588508 -0.9125149 0.3769389 0.188274 -0.881613 0.4327952 0.06161755 -0.9798999 0.1897358 0.09460878 -0.96266 0.2536432 0.1266552 -0.9404834 0.3153561 -0.02989166 -0.9994263 0.01592946 -0.02846747 -0.9995135 0.01274394 -0.02646464 -0.9995237 0.01587611 -0.02662861 -0.9995214 0.01574277 -0.02663028 -0.9995211 0.01576417 -0.0290392 -0.9995375 0.009033203 -0.05862063 -0.9980161 0.02296686 -0.02943009 -0.9995133 0.01034945 -0.07852536 -0.9963737 0.03276103 -0.1005183 -0.9939541 0.04417616 -0.0518499 -0.9977705 0.04202139 -0.05337101 -0.998207 0.02710288 -0.04751718 -0.9985653 0.02469164 -0.03628212 -0.9991572 0.01920223 -0.01791059 -0.9997879 0.01016515 0.0371651 -0.9991612 -0.01719784 0.06664305 -0.997268 -0.03186684 0.08148473 -0.9961894 -0.03109848 0.03579866 -0.9993421 -0.005829095 0.101629 -0.9938592 -0.04376459 0.1116387 -0.9923583 -0.05255383 0.0413227 -0.9989175 -0.02136325 0.1074271 -0.9926636 -0.05548363 0.1037762 -0.993839 -0.03891807 0.03122061 -0.9991822 -0.02569669 0.08417046 -0.9951829 -0.05026417 0.0420857 -0.9990103 -0.01440495 -0.02651864 -0.9995211 0.01595276 -0.02646946 -0.9995234 0.01588803 -0.02924287 -0.9995149 0.01071941 -0.0523892 -0.9983196 0.02476513 -0.05563795 -0.9980254 0.02915364 -0.04807662 -0.9984214 0.0290445 -0.03765946 -0.9988908 0.02826774 -0.02675193 -0.999512 0.0161302 -0.028418 -0.9994533 0.01690107 -0.02783447 -0.9995049 0.01466923 -0.02688592 -0.9995081 0.01614904 -0.02698719 -0.9995086 0.01594817 -0.02698749 -0.9995086 0.01594853 -0.02721565 -0.9995095 0.01549732 -0.0279622 -0.9995148 0.01372069 -0.02812242 -0.999511 0.01367187 -0.02752453 -0.9995108 0.01485693 -0.02849423 -0.9995137 0.01266855 -0.02752465 -0.9995108 0.01485151 -0.02761954 -0.9995149 0.01439696 -0.02795505 -0.9995111 0.01400208 -0.02810055 -0.9995148 0.01344585 -0.02879071 -0.9995092 0.01235204 -0.02912008 -0.9995074 0.01170057 -0.03022491 -0.9994976 0.009546041 -0.02938443 -0.9995058 0.01117962 -0.03019905 -0.9994995 0.009426414 -0.02923101 -0.9995041 0.01171422 -0.0301671 -0.9995009 0.009372651 -0.02989417 -0.999503 0.01001733 -0.02924239 -0.9995059 0.01152414 -0.0284115 -0.9995074 0.01333516 -0.02410739 -0.9994728 0.0217483 -0.02719539 -0.9995062 0.01574665 -0.02410793 -0.9994719 0.02178937 -0.02792453 -0.9993324 0.02356034 -0.02340823 -0.9994433 0.02377444 -0.02145451 -0.9993909 0.02752768 -0.02073913 -0.9993794 0.02847611 -0.01730406 -0.9996082 0.02200394 -0.02031952 -0.9993641 0.02930265 -0.01962327 -0.9993369 0.03067409 -0.0249952 -0.9994741 0.02066147 -0.02893203 -0.9994997 0.01278746 -0.03390604 -0.9994207 0.002960264 -0.03994935 -0.9991623 -0.008881032 -0.03839266 -0.9992476 -0.00552386 -0.04678606 -0.9986531 -0.02243167 -0.05224788 -0.998081 -0.03323477 -0.05374377 -0.997873 -0.03689396 1.83112e-4 -0.9975314 0.07022333 -0.02718806 -0.9995108 0.01545804 -0.02723896 -0.9995142 0.01514792 -0.02764099 -0.999511 0.01462203 -0.02879077 -0.9995092 0.01235079 -0.02848744 -0.9995103 0.01295089 -0.02912008 -0.9995074 0.0117017 -0.02980542 -0.999504 0.01017135 -0.03028988 -0.9994985 0.009236991 -0.03017061 -0.9995 0.009469509 -0.02987909 -0.9995008 0.01027089 -0.02841109 -0.9995076 0.01332873 -0.0258665 -0.9994983 0.01827901 -0.02031964 -0.999364 0.02930617 -0.01933377 -0.9993247 0.03124737 0.02853506 -0.9916182 0.1260123 -0.0270155 -0.9995024 0.01628601 -0.02738183 -0.99949 0.01643306 -0.02723848 -0.9994958 0.01631754 -0.02729815 -0.9994978 0.01609402 -0.02754676 -0.999498 0.01565617 -0.02821671 -0.9994951 0.01461362 -0.02781581 -0.9994981 0.01516264 -0.02870011 -0.9994948 0.0136615 -0.02837496 -0.9994951 0.01430118 -0.02890962 -0.9994943 0.01324802 -0.03021824 -0.999489 0.01042753 -0.03067624 -0.9994818 0.00976032 -0.03069275 -0.9994843 0.009444773 -0.0302844 -0.9994859 0.0105344 -0.02587288 -0.9994866 0.01889878 -0.01974594 -0.9993251 0.03097534 -0.02114242 -0.9993783 0.02821552 -0.05425864 -0.997835 -0.03716474 -0.02735424 -0.9994917 0.01637542 -0.02738636 -0.9994891 0.01648122 -0.02755737 -0.9994974 0.01567298 -0.02993869 -0.9994915 0.01097923 -0.03019732 -0.9994867 0.01070588 -0.03060358 -0.9994853 0.009620487 -0.03073567 -0.9994811 0.009643077 -0.02760094 -0.9994994 0.01546621 -0.01965349 -0.9993213 0.03115695 -0.02233988 -0.9994052 0.02627682 0.0290538 -0.9916149 0.1259203 -0.02851194 -0.9994922 0.01423072 -0.02916717 -0.9994886 0.01311492 -0.02824068 -0.9994922 0.0147649 -0.02943825 -0.9994863 0.01267325 -0.02872419 -0.9994919 0.01381176 -0.02965903 -0.9994885 0.01196587 -0.02941149 -0.9994924 0.01225161 -0.02965861 -0.9994894 0.01189386 -0.02999305 -0.9994862 0.01130634 -0.03038823 -0.9994832 0.01048052 -0.02884119 -0.9994924 0.01353591 -0.02974158 -0.9994886 0.01175731 -0.02884125 -0.9994924 0.01353555 -0.02767115 -0.9994916 0.01584553 -0.0213325 -0.9993926 0.02755826 -0.02073568 -0.9993457 0.02963733 -0.019818 -0.9993125 0.03133475 -0.02122521 -0.9993654 0.02860605 -0.02862715 -0.9995099 0.01266551 -0.03384506 -0.9994227 0.002990782 0.03082424 -0.9915961 0.1256471 0.06360286 -0.9798017 0.1895878 0.1883037 -0.8814874 0.4330376 0.1596171 -0.9122897 0.3771603 -0.02776706 -0.99949 0.01577895 -0.02763831 -0.999484 0.01637065 -0.0280326 -0.9994918 0.01517546 -0.02778422 -0.9994886 0.01583397 -0.02805024 -0.9994907 0.0152198 -0.03087872 -0.9994755 0.009753823 -0.02974152 -0.9994886 0.01175796 -0.02074551 -0.9993493 0.0295062 -0.02493435 -0.99948 0.02044796 -0.05212622 -0.9980894 -0.03317397 0.1273579 -0.940306 0.3156022 0.2191897 -0.8470638 0.484189 -0.0272215 -0.999528 0.01423919 -0.03089743 -0.9994754 0.009716808 -0.05439233 -0.9978416 -0.03679144 -0.03955322 -0.9991768 -0.009033739 0.005096673 -0.997578 0.06936991 -0.04638862 -0.9986683 -0.0225839 0.03366279 -0.9915422 0.1253429 0.06183189 -0.97988 0.1897684 0.09479159 -0.9626262 0.2537034 -0.02665925 -0.9995554 0.01335543 -0.02737021 -0.9994912 0.016384 -0.0272808 -0.999499 0.01604765 -0.02795362 -0.9994935 0.01521408 -0.02887767 -0.9994878 0.01380121 -0.02836298 -0.9994888 0.01475709 -0.02905809 -0.9994947 0.01288235 -0.02888983 -0.999487 0.01382726 -0.02995526 -0.9994873 0.0113092 -0.03036504 -0.9994838 0.01049804 -0.03005725 -0.9994794 0.01172286 -0.03036516 -0.9994838 0.01049971 -0.03074312 -0.9994813 0.009597241 -0.03076314 -0.9994795 0.009712219 -0.02613961 -0.9994856 0.01858574 -0.02748906 -0.9994953 0.01592361 -0.02322524 -0.9994497 0.02368301 -0.02612459 -0.999482 0.01879304 -0.02459037 -0.9994552 0.02201372 -0.01985812 -0.9993298 0.03074991 -0.02118623 -0.9993662 0.02860873 -0.02111506 -0.9993743 0.0283764 -0.02194344 -0.9994187 0.02609407 -0.01727378 -0.9995315 0.0252698 -0.05404567 -0.997867 -0.03661477 -0.02741348 -0.9994887 0.0164591 -0.02738654 -0.9994924 0.0162844 -0.02754098 -0.9994983 0.01564085 -0.0281161 -0.9995035 0.01422274 -0.02847731 -0.9994939 0.01417636 -0.02853941 -0.9995087 0.01296246 -0.02771949 -0.999557 0.01084566 -0.03076916 -0.9994795 0.009700059 -0.03072315 -0.9994816 0.009636759 -0.03038346 -0.9994836 0.01046216 -0.02462714 -0.9994605 0.0217325 -0.01981788 -0.9993125 0.03133481 -0.0202198 -0.9993889 0.0285117 -0.05234003 -0.9980017 -0.03540199 0.04260444 -0.9912564 0.1248836 0.03805702 -0.9914067 0.125158 0.2806229 -0.8267009 0.4876644 0.2240713 -0.8867328 0.4043477 0.2462902 -0.8754749 0.4157941 0.07129216 -0.9792907 0.1894919 0.06650114 -0.9796334 0.1894627 -0.02657431 -0.9995185 0.01602107 -0.02748799 -0.9995113 0.01488572 -0.02699178 -0.9995141 0.01558935 -0.02736252 -0.999521 0.014463 -0.02773898 -0.9995274 0.01324963 -0.02902948 -0.9995075 0.01192778 -0.02927786 -0.9995118 0.01091432 -0.02852666 -0.9995096 0.01292061 -0.02943062 -0.9995214 0.009534358 -0.0290746 -0.9995042 0.01208621 -0.03002542 -0.9995054 0.009349644 -0.0292561 -0.9995131 0.01084822 -0.02962279 -0.9995098 0.01014494 -0.03002566 -0.9995054 0.00935018 -0.03004074 -0.9995052 0.009320259 -0.02734696 -0.9995097 0.01524907 -0.02974319 -0.9995023 0.01051855 -0.02923351 -0.9995062 0.01152551 -0.02833199 -0.9995101 0.01330411 -0.02163797 -0.9994997 0.02307242 -0.0202949 -0.9994259 0.02713108 -0.02355742 -0.999482 0.02192842 -0.02009075 -0.999361 0.02956503 -0.02331656 -0.9995314 0.01983737 -0.01923871 -0.9993509 0.03045856 -0.02041721 -0.9994668 0.02548336 -0.03274667 -0.9994607 0.002471983 -0.03357112 -0.9994128 -0.006866812 -0.05044782 -0.9981532 -0.03384548 0.1340995 -0.9390935 0.3164187 0.1044057 -0.9615338 0.2540712 0.1406935 -0.9376108 0.317949 -0.0269376 -0.9995883 0.009878039 -0.02696633 -0.999509 0.01596307 -0.02631598 -0.999529 0.01579177 -0.02802908 -0.9995061 0.01421469 -0.02748554 -0.9995583 0.01130765 -0.0300408 -0.9995053 0.009320318 -0.02962136 -0.9995098 0.01014876 -0.02923351 -0.9995062 0.01152497 -0.02833211 -0.9995101 0.01330518 -0.02000004 -0.9993742 0.02917742 -0.01931565 -0.9993298 0.03109329 -0.0269789 -0.9995644 0.01196348 -0.05359619 -0.9978608 -0.03743618 -0.03796601 -0.9992329 -0.009613573 -0.04477101 -0.9987274 -0.02322477 0.5845333 -0.3150187 0.7477193 0.5436365 -0.3370223 0.7686842 0.4824807 -0.4879131 0.7274291 0.1118827 -0.9604338 0.2550475 0.09662431 -0.9624589 0.2536465 0.1910176 -0.8805305 0.4337953 -0.02514839 -0.9995717 0.01496601 -0.02659124 -0.9995327 0.01508069 -0.02586716 -0.9995676 0.01398688 -0.02568942 -0.9995598 0.01484447 -0.02797907 -0.9995082 0.0141645 -0.02615672 -0.9995553 0.01432442 -0.0262047 -0.9995686 0.0132659 -0.02718478 -0.9995771 0.01033008 -0.02800786 -0.9995594 0.009835958 -0.02702796 -0.9995601 0.01221114 -0.02953439 -0.9995186 0.009512186 -0.02797591 -0.9995436 0.01141268 -0.02800637 -0.9995595 0.009833276 -0.02898472 -0.9995386 0.009089291 -0.02836185 -0.9995519 0.009576857 -0.02907752 -0.9995375 0.008905947 -0.02878481 -0.9995474 0.008741676 -0.02836203 -0.9995518 0.009576976 -0.02569109 -0.9995568 0.01504606 -0.02681529 -0.9995607 0.01262897 -0.02565079 -0.9995596 0.01492923 -0.02430593 -0.9995465 0.0177825 -0.02282738 -0.999525 0.02070379 -0.02181774 -0.9995447 0.02084589 -0.01858627 -0.9994804 0.02633821 -0.01871013 -0.9994153 0.02862203 -0.01950895 -0.9994337 0.02741974 -0.01805192 -0.9993702 0.03055292 -0.01798248 -0.9993782 0.03033089 -0.03088498 -0.9995214 0.001770079 -0.05211192 -0.9979477 -0.0372129 0.1298871 -0.9399119 0.3157454 0.1647411 -0.9108373 0.3784652 -0.02539712 -0.9995611 0.01525366 -0.02348101 -0.9996234 0.01420557 -0.02581977 -0.9995546 0.01496243 -0.02618509 -0.9995695 0.01323825 -0.02686691 -0.9995616 0.01244151 -0.02591061 -0.9995912 0.01208364 -0.02844399 -0.9995552 0.008968889 -0.02786904 -0.9995769 0.008322954 -0.02788096 -0.9995769 0.008299231 -0.02658975 -0.9996079 0.008779406 -0.02681559 -0.9995607 0.01262986 -0.02771914 -0.999557 0.01084446 -0.02231425 -0.9996078 0.01692324 -0.02430647 -0.9995464 0.01778471 -0.02232563 -0.9995174 0.02160269 -0.01785677 -0.9993813 0.03030437 -0.01870989 -0.9994153 0.02862143 -0.02066117 -0.9996104 0.01876896 -0.01773124 -0.9995439 0.02444535 -0.024598 -0.9996375 0.01095616 -0.0180906 -0.9994543 0.02763658 -0.03546309 -0.9993156 -0.01052904 -0.04229879 -0.9988142 -0.02410972 -0.02957302 -0.9995321 -0.007812857 -0.04782336 -0.9982487 -0.03482222 -0.05134344 -0.9979538 -0.03810715 0.07852596 -0.9786599 0.1898906 0.2348459 -0.8572869 0.4581556 0.1954746 -0.8996409 0.3904303 0.2079241 -0.89426 0.3963163 0.09952384 -0.9621554 0.2536774 -0.02392596 -0.9996077 0.01456075 -0.0217688 -0.9996828 0.01267379 -0.02346897 -0.9996327 0.01355546 -0.0243467 -0.9996164 0.01320755 -0.02434682 -0.9996163 0.01320761 -0.02478128 -0.9996162 0.01239013 -0.02476823 -0.9996166 0.01237553 -0.02543085 -0.9996154 0.01106524 -0.02491104 -0.9996275 0.01115989 -0.0265913 -0.9995874 0.01087033 -0.02607524 -0.9996121 0.009794235 -0.02590769 -0.9996131 0.01012432 -0.02667123 -0.999602 0.009198129 -0.02657324 -0.9996167 0.007776498 -0.02649623 -0.9996088 0.008963108 -0.02651309 -0.9996188 0.0077129 -0.02694451 -0.9996044 0.008078575 -0.02082777 -0.999733 0.01001828 -0.02659189 -0.9996165 0.007739901 -0.02594327 -0.9996128 0.01005619 -0.02658975 -0.9996079 0.008779287 -0.02370488 -0.9996142 0.01447552 -0.02503627 -0.9996165 0.01184558 -0.02327215 -0.9996327 0.01389312 -0.02324479 -0.9995545 0.01872766 -0.01598995 -0.9994313 0.02969092 -0.01691532 -0.9994686 0.02786642 -0.01714909 -0.9994982 0.02663528 -0.01581531 -0.9994432 0.02938097 -0.02792459 -0.9996098 6.40893e-4 -0.02514749 -0.9996455 -0.008758902 0.04763972 -0.9910349 0.1248216 0.1507646 -0.9351068 0.3206952 -0.02577304 -0.9996204 0.009743034 -0.02509462 -0.9996337 0.01014101 -0.02190846 -0.9996689 0.01349347 -0.02150374 -0.9996822 0.01315611 -0.02210336 -0.9996691 0.01315307 -0.02394992 -0.9996154 0.01399123 -0.02199447 -0.9996861 0.01200115 -0.02246308 -0.9996675 0.01266795 -0.02292275 -0.9996653 0.01198947 -0.02231878 -0.9996889 0.01113766 -0.02190631 -0.9996979 0.01114499 -0.02282291 -0.9996899 0.009957015 -0.02324217 -0.9996909 0.008831501 -0.02376443 -0.9996738 0.009359955 -0.022421 -0.9997304 0.006048321 -0.02456682 -0.9996634 0.00834614 -0.02422326 -0.9996756 0.007884263 -0.02496242 -0.999664 0.006993949 -0.02542322 -0.9996491 0.007442772 -0.02496039 -0.999664 0.006997287 -0.02496057 -0.999664 0.006997823 -0.02452564 -0.9996684 0.007856607 -0.02452528 -0.9996684 0.007856726 -0.02166485 -0.9996742 0.01350045 -0.02503669 -0.9996164 0.0118463 -0.02594304 -0.9996129 0.01005542 -0.02296322 -0.9996765 0.01094323 -0.02187949 -0.9996669 0.01369255 -0.02004498 -0.9996106 0.01941913 -0.01666754 -0.9994851 0.02741926 -0.01407033 -0.9995536 0.02635937 -0.01173394 -0.9995402 0.02796083 -0.01483279 -0.9995259 0.02698355 -0.01484322 -0.9995536 0.02593255 -0.01389461 -0.9994877 0.02883368 -0.01400804 -0.9996393 0.02291947 -0.01687693 -0.9997078 0.01730418 -0.01362824 -0.9995046 0.02837294 -0.02072232 -0.9997397 0.009552419 -0.01500582 -0.9995435 0.02622538 -0.03161746 -0.9994292 -0.01190227 -0.02066129 -0.9997398 -0.009674489 -0.03851443 -0.9989347 -0.02542197 0.1398689 -0.9702011 0.1978551 0.1695932 -0.964365 0.2030724 0.2057012 -0.9383517 0.2778187 -0.04388689 -0.9983817 -0.03616547 -0.008636832 -0.9996802 0.02377426 -0.04821813 -0.9980579 -0.03943932 0.3270148 -0.8261588 0.4588279 0.2904788 -0.8810196 0.3733987 0.08664268 -0.9778507 0.1905284 0.1203079 -0.9590149 0.2565471 0.1962723 -0.8782354 0.4360963 -0.02434372 -0.9996687 0.008374094 -0.02397018 -0.9996452 0.01162219 -0.01963537 -0.9997369 0.01186597 -0.01998901 -0.9997236 0.01237386 -0.02051162 -0.9997193 0.01186048 -0.01982533 -0.9997397 0.01130574 -0.02059656 -0.9997265 0.01108688 -0.01991492 -0.999747 0.01045691 -0.02141201 -0.9997147 0.01058822 -0.01926755 -0.9997771 0.008628606 -0.02326601 -0.9996758 0.01034408 -0.01868999 -0.9997926 0.008090972 -0.02176833 -0.9997257 0.008645534 -0.02147793 -0.9997354 0.008247733 -0.02177876 -0.9997382 0.007019579 -0.02243131 -0.9997172 0.007900536 -0.02247583 -0.9997246 0.006762564 -0.02217108 -0.9997375 0.005803644 -0.0228427 -0.9997209 0.00603795 -0.02293318 -0.9997199 0.005857586 -0.02239918 -0.9997253 0.006910562 -0.0230599 -0.9997147 0.006245315 -0.02174395 -0.9997299 0.008207499 -0.02240002 -0.9997252 0.006912112 -0.01886063 -0.9997661 0.01059001 -0.005798518 -0.9999774 0.003418087 -0.01263463 -0.99988 0.008972406 -0.02174288 -0.9997299 0.008206367 -0.02296143 -0.9996766 0.01094126 -0.02082723 -0.9997329 0.01001709 -0.02011567 -0.9997143 0.01291549 -0.01258015 -0.9995753 0.02628797 -0.01173263 -0.9995403 0.0279594 -0.01202255 -0.9995525 0.02739155 -0.02453696 -0.9996988 -5.79854e-4 -0.04037725 -0.9984146 -0.03921753 0.04190254 -0.9968714 0.06701964 0.05548286 -0.9962202 0.06683582 0.0855152 -0.9882774 0.1264721 -0.004028558 -0.9997243 0.02313369 0.01870805 -0.9975102 0.06799608 0.615495 -0.4072576 0.6747646 0.6086221 -0.3233247 0.7245966 0.575477 -0.3952589 0.7159586 0.09488511 -0.9769294 0.1913267 0.1288517 -0.957446 0.2582528 0.1618116 -0.9321413 0.3239285 0.1731334 -0.9081189 0.3812415 0.2034416 -0.8749884 0.4393253 -0.02174741 -0.9997299 0.008209049 -0.0181905 -0.9997996 0.008365988 -0.01716965 -0.9997943 0.0107966 -0.01773375 -0.9997803 0.01117604 -0.01760435 -0.9997887 0.01060825 -0.01846593 -0.9997711 0.01080435 -0.02474826 -0.9996322 0.0110929 -0.02619826 -0.9995984 0.01080667 -0.0284686 -0.9995294 0.0114215 -0.02683472 -0.9995898 0.01001185 -0.02299273 -0.9996944 0.009082615 -0.02694696 -0.9995976 0.008865654 -0.01831668 -0.9998093 0.006777644 -0.02246057 -0.9997302 0.005937635 -0.01787215 -0.999834 0.003548979 -0.01257628 -0.9999197 0.001534819 -0.01146686 -0.9999321 0.002070128 -0.01904374 -0.999794 0.007027626 -0.01812064 -0.9997967 0.008851706 -0.01812022 -0.9997966 0.00885123 -0.01813691 -0.999736 0.01411437 -0.01809746 -0.9997568 0.01260411 -0.009574115 -0.9996552 0.02445381 -0.009906113 -0.9996411 0.02489066 -0.008814871 -0.9996021 0.02679586 -0.009403586 -0.9995937 0.02690899 -0.009281158 -0.9995985 0.02677124 -0.01071476 -0.9996466 0.0243299 -0.01214641 -0.9995786 0.02636814 -0.008118093 -0.9996585 0.02484267 -0.009918749 -0.9997233 0.02133303 -0.0127263 -0.9997946 0.01577818 -0.01660227 -0.9998293 0.008117973 -0.02142423 -0.9997691 -0.001678526 -0.02746719 -0.9995329 -0.01339787 -0.03954148 -0.9983475 -0.04169839 -0.03430372 -0.9990514 -0.0268265 -0.01519834 -0.9998275 -0.01068156 -0.03967428 -0.9985108 -0.03744643 0.001556456 -0.9997479 0.02240109 -0.0435304 -0.9982321 -0.04046958 0.02450644 -0.9974095 0.06762921 0.05359196 -0.990719 0.1249157 0.6387953 -0.11347 0.7609633 0.6064499 -0.3212466 0.7273371 0.419518 -0.6096531 0.6725533 0.365925 -0.6946471 0.6193258 0.1734701 -0.9286938 0.3277743 0.2382032 -0.8336655 0.4982582 -0.01354789 -0.9998977 0.004604279 -0.008061707 -0.9999658 0.001904606 -0.01605296 -0.9998624 0.004181087 -0.005218684 -0.9999759 -0.004577755 2.13635e-4 -0.9999969 -0.002472043 0.02015078 -0.9997235 -0.01212722 0.005848109 -0.9999718 -0.004737734 0.01551562 -0.9998643 -0.005545318 -0.01626217 -0.9997894 0.01252192 0.001512229 -0.9999931 0.003404259 -0.009736657 -0.9999472 0.00330156 0.002807676 -0.9997981 0.01989829 -0.004211544 -0.9997292 0.02288895 -0.004882931 -0.9996673 0.02533042 -0.00560981 -0.9996632 0.02533614 -0.005298495 -0.9996705 0.02511751 -0.01214635 -0.9997895 0.01654106 -0.002410948 -0.9997664 0.0214852 -0.008850574 -0.9997518 0.0204479 -0.0124213 -0.9999009 0.006622612 -0.01736551 -0.9998446 -0.003051877 -0.02331644 -0.9996182 -0.01483219 0.008850336 -0.9997281 0.02157664 -0.03954213 -0.9983475 -0.04169774 0.03201478 -0.9972195 0.06729513 0.441858 -0.6711494 0.5952479 0.3609494 -0.7588574 0.5420803 0.4615774 -0.5652827 0.683668 0.1839976 -0.9041186 0.3856352 0.2159226 -0.8683905 0.4464029 -0.003448545 -0.9995746 0.02896207 0.01932877 -0.9997248 0.01329976 0.005798637 -0.9998127 0.01846414 0.01716727 -0.9998 0.01025974 0.004608273 -0.9997618 0.0213353 7.30692e-4 -0.9998953 0.01444941 -0.008270561 -0.999792 0.01864689 -0.01516795 -0.9997134 0.01852506 -0.01806712 -0.9997653 0.01196336 -0.01242107 -0.9999131 -0.004425168 -0.01818907 -0.9996983 -0.01651054 0.03155654 -0.9993118 0.01950156 0.241716 -0.9035661 0.3537538 0.1752128 -0.9469303 0.2694877 0.1396561 -0.9552832 0.2606344 0.3467922 -0.7298719 0.5890859 0.3133091 -0.8012181 0.5097911 -0.02786403 -0.999444 0.0183115 -0.009888112 -0.9999228 -0.007538139 -0.01156681 -0.9997553 -0.01886099 -0.003143429 -0.9997668 -0.02136313 -0.002197325 -0.9999008 -0.01391673 0.07742571 -0.9968599 0.01660209 0.03173947 -0.9993367 -0.01785343 0.05832237 -0.9980731 -0.02118039 0.04999023 -0.9985841 0.01818937 0.07452678 -0.9949727 0.06689709 0.1051073 -0.9861894 0.1279965 0.6801295 -0.5437679 0.4916709 0.3517324 -0.8798651 0.3195653 0.1197569 -0.9735284 0.1946812 0.1545188 -0.9520167 0.2641744 0.1889477 -0.9236804 0.3333367 0.2565406 -0.8435992 0.4717283 0.002044796 -0.999998 2.13636e-4 0.04184168 -0.9987993 -0.02548342 0.008301079 -0.9997957 -0.01843333 0.1028485 -0.9924119 0.06738561 0.1342231 -0.9822883 0.1307439 0.2103985 -0.9160606 0.3414169 0.3941208 -0.6700724 0.6290246 0.2663061 -0.8111561 0.5206793 0.0151177 -0.9998672 -0.006114065 0.01757913 -0.9998157 -0.007721364 0.8416563 -0.3842052 -0.3794748 0.8427155 -0.3821396 -0.3792097 0.5967487 -0.7538633 -0.2749201 0.8446254 -0.3838735 -0.3731611 0.8455921 -0.3821904 -0.372699 0.5990394 -0.7537129 -0.2703124 0.6011378 -0.7537035 -0.2656396 0.1717927 -0.9818952 -0.07980775 0.1713351 -0.9818348 -0.08151692 0.09201437 -0.9947928 -0.04382508 0.09118998 -0.9947891 -0.04559499 0.0549646 -0.9981222 -0.02703976 0.05566632 -0.998118 -0.02572733 0.03250271 -0.9993442 -0.0159614 0.01684665 -0.9998151 -0.00927788 0.09744596 -0.9946939 -0.03299063 0.1815899 -0.981501 -0.06067234 0.09940099 -0.9946205 -0.02914583 0.01925754 -0.9995636 -0.02240103 0.00891149 -0.9996456 -0.02508646 0.1218914 -0.9924354 0.01464891 0.101446 -0.9945005 -0.02603292 0.2181788 -0.9758384 0.01171916 0.1486281 -0.9864999 0.06875956 0.1810365 -0.974063 0.1357468 0.2171462 -0.9528492 0.2119579 0.2539193 -0.922258 0.2914883 0.6922584 -0.2738759 0.6676603 0.7045693 -0.1409077 0.695505 0.2783627 -0.8574585 0.4327577 0.3039407 -0.7758897 0.5528249 0.8228927 -0.3830786 -0.4196408 0.8237122 -0.3818863 -0.4191196 0.5846244 -0.7539445 -0.2996368 0.5869035 -0.753993 -0.2950235 0.8266311 -0.3832546 -0.4120643 0.827264 -0.3821052 -0.4118618 0.8328515 -0.3816181 -0.4009065 0.5914611 -0.7539451 -0.2859034 0.8314737 -0.3824706 -0.4029492 0.8352568 -0.3814628 -0.3960206 0.5930514 -0.7539493 -0.2825784 0.8338827 -0.3825307 -0.3978819 0.8358839 -0.3852714 -0.3909784 0.8373128 -0.3820338 -0.3910979 0.8386958 -0.3846629 -0.3855175 0.8399598 -0.3821356 -0.3852791 0.5951048 -0.7537161 -0.2788591 0.8538389 -0.3819493 -0.3536579 0.6060752 -0.7535426 -0.2546498 0.8516158 -0.382043 -0.3588786 0.8570849 -0.3834801 -0.3440181 0.8588032 -0.381029 -0.3424531 0.6087965 -0.7533963 -0.2485176 0.8736429 -0.3800557 -0.3038188 0.624296 -0.7519873 -0.211588 0.8712617 -0.3805437 -0.3099834 0.876365 -0.3835679 -0.2913078 0.8782212 -0.3793234 -0.2912755 0.6273866 -0.7514479 -0.2042356 0.103888 -0.9943826 -0.02026486 0.0656467 -0.9978243 -0.006103813 0.8854761 -0.3784347 -0.2696652 0.6335116 -0.7501244 -0.189675 0.8847504 -0.3796278 -0.2703692 0.04141366 -0.9989341 -0.02038639 0.9073566 -0.4192987 -0.02987796 0.9353225 -0.3525275 -0.02993935 0.6691419 -0.7391538 -0.07681775 0.6843074 -0.729171 -0.00576812 0.924085 -0.379687 0.04364216 0.935067 -0.3512719 0.04751783 0.2469335 -0.9662787 0.07300269 0.7046036 -0.6869633 0.1778066 0.2802554 -0.9485591 0.1472843 0.709114 -0.6475567 0.2789762 0.3160536 -0.9201751 0.2310585 0.7045578 -0.5961549 0.3849645 0.8264032 -0.3818277 -0.4138425 0.8283855 -0.3815829 -0.4100879 0.8306079 -0.3815498 -0.4055988 0.5897341 -0.7539916 -0.2893277 0.8415274 -0.3818216 -0.3821573 0.8443779 -0.381583 -0.376059 0.8473505 -0.3811917 -0.3697163 0.8485019 -0.3822256 -0.3659893 0.8503524 -0.3809388 -0.3630242 0.6035236 -0.7536491 -0.2603315 0.8703427 -0.3804506 -0.3126678 0.6209378 -0.7524132 -0.2197971 0.8823414 -0.3782858 -0.2799529 0.8848069 -0.377459 -0.2732061 0.8869821 -0.3770658 -0.2666165 0.6343106 -0.7500087 -0.1874487 0.8888723 -0.3766072 -0.2609088 0.6345543 -0.7500082 -0.1866246 0.8875396 -0.3780459 -0.2633534 0.934647 -0.344713 -0.08722352 0.9421017 -0.322681 0.09122228 0.6956509 -0.7135961 0.0827676 0.9023603 -0.4014797 0.1567159 0.9321806 -0.3281737 0.1527794 0.8731934 -0.4082593 0.2661911 0.9188508 -0.299488 0.2569438 0.8432135 -0.3894243 0.370594 0.8918259 -0.2761358 0.3583234 0.8155042 -0.3388244 0.4692025 0.8352093 -0.2912413 0.4664806 0.7327188 -0.3586074 0.5783804 0.7628563 -0.2920681 0.5768421 0.6429162 -0.3846327 0.6623569 0.697231 -0.2770186 0.6611579 0.09088504 -0.9947918 -0.04614442 0.8213866 -0.3822191 -0.4233587 0.5836568 -0.7539867 -0.3014115 0.8205487 -0.3817386 -0.4254121 0.8219733 -0.3817645 -0.4226297 0.8334114 -0.3827381 -0.398669 0.8359342 -0.3825643 -0.3935208 0.838688 -0.3820042 -0.388169 0.8551942 -0.381558 -0.3507941 0.09317588 -0.9947816 -0.04156744 0.09433454 -0.9947702 -0.03915596 0.09576892 -0.9947397 -0.03634822 0.8768687 -0.3798381 -0.2946599 0.8752977 -0.3796619 -0.2995178 0.8797236 -0.3791433 -0.286944 0.105749 -0.9942543 -0.01660239 0.8891268 -0.3778324 -0.2582566 0.8910313 -0.3768175 -0.2531242 0.892832 -0.376024 -0.2479054 0.8948901 -0.3744121 -0.2428734 0.8972704 -0.3719399 -0.2378377 0.9022585 -0.3652188 -0.2292268 0.6362411 -0.7480952 -0.1885498 0.9106698 -0.3678814 -0.1879998 0.07922607 -0.9944466 -0.06927704 0.9388585 -0.34395 0.01559519 0.9306684 -0.3043937 0.20298 0.9108539 -0.2731189 0.309437 0.8842331 -0.2256895 0.4088963 0.8406874 -0.2065553 0.5005792 0.774735 -0.1646216 0.6104796 0.1684938 -0.981909 -0.08639842 0.1689858 -0.9818697 -0.08588153 0.8309795 -0.3827426 -0.4037093 0.169959 -0.9818499 -0.08417075 0.1702681 -0.9819027 -0.08292138 0.8508335 -0.3826446 -0.3600912 0.1730117 -0.9818549 -0.07764011 0.1741713 -0.9818235 -0.07541215 0.1756694 -0.9817772 -0.07248347 0.177408 -0.981711 -0.06906491 0.1793623 -0.981625 -0.06512832 0.1840593 -0.9813341 -0.05572742 0.1866242 -0.9811275 -0.05060058 0.188699 -0.9809417 -0.04632782 0.1897959 -0.9808409 -0.0439164 0.8871261 -0.378466 -0.2641419 0.1874204 -0.9810501 -0.0491364 0.1846401 -0.9812784 -0.05478161 0.1808271 -0.9815327 -0.06241202 0.9023394 -0.3682788 -0.2239521 0.1671236 -0.9818055 -0.09015393 0.1695328 -0.9817648 -0.08600246 0.9308553 -0.3597561 -0.06390643 0.1952899 -0.980112 -0.03524923 0.9294142 -0.3466916 0.1264691 0.8189722 -0.2096337 0.5341707 0.7623019 -0.1423403 0.6313756 0.6843584 -0.1447517 0.7146333 0.6222788 -0.07455748 0.7792371 0.5815085 -0.7538796 -0.3058 0.8476962 -0.3832272 -0.3668081 0.8942831 -0.3787778 -0.2382964 0.9099584 -0.3408682 0.2361875 0.8849966 -0.315874 0.3420595 0.8573158 -0.2642965 0.4417659 0.7836846 -0.2679323 0.5604025 0.7369748 -0.1907747 0.648439 0.6533916 -0.216139 0.7255091 0.5921095 -0.1811334 0.785237 0.5935708 0.7727193 -0.224897 0.5938112 0.7732943 -0.222271 0.6582294 0.7114542 -0.2461035 -0.08005172 0.9959924 0.0398885 -0.08646005 0.995344 0.04260438 -0.07965379 0.9960083 0.04028463 -0.09247314 0.994651 0.04602289 -0.08584946 0.9953411 0.04388606 -0.03991889 0.9989798 0.02111917 -0.03015285 0.99941 0.0164498 -0.04022443 0.9989883 0.02011221 -0.02063059 0.9997311 0.01058995 -0.02008128 0.9997305 0.01165813 -0.01034593 0.9999286 0.005981743 0.5739499 0.7745547 -0.2657944 0.5723613 0.7746136 -0.2690287 0.4680056 0.8565404 -0.2175074 0.466672 0.8565571 -0.2202889 0.3996457 0.8971657 -0.1880883 0.6346154 0.7125309 -0.2992709 0.6333467 0.7131559 -0.3004673 0.6349888 0.7131797 -0.2969242 0.5707352 0.774663 -0.2723208 0.2521172 0.9604321 -0.1183525 0.2801083 0.9512026 -0.1294333 0.2791591 0.9512225 -0.1313241 0.6288429 0.7131362 -0.3098284 0.5665352 0.7747703 -0.2806581 0.5679349 0.7747036 -0.2780009 0.633213 0.7125935 -0.3020793 0.6320658 0.7129738 -0.3035808 0.5692803 0.7747072 -0.2752249 0.6316875 0.7129603 -0.304399 0.6307418 0.7129607 -0.3063524 0.6301004 0.7132654 -0.3069626 0.346518 0.9223593 -0.1708174 0.3475258 0.922239 -0.1694139 0.3963221 0.8972334 -0.1946818 0.6299828 0.7125379 -0.3088875 0.4640778 0.8566487 -0.2253551 0.4629477 0.856647 -0.2276741 0.5653402 0.7747334 -0.2831584 0.6275843 0.713128 -0.3123883 0.6272922 0.7130207 -0.3132188 0.4618186 0.8566778 -0.2298411 0.6286361 0.7128388 -0.3109304 0.3073545 0.9392759 -0.1526243 0.3454183 0.9223567 -0.1730449 0.3057985 0.9393081 -0.1555238 0.3495938 0.9221892 -0.1653819 0.3984845 0.897193 -0.190407 0.4607238 0.8567156 -0.2318879 0.3942787 0.8972977 -0.1984974 0.3930246 0.8972911 -0.2009986 0.6258555 0.712774 -0.3166359 0.5642099 0.7747625 -0.2853248 0.6260077 0.7133839 -0.3149571 0.4597458 0.8568352 -0.2333827 0.6266193 0.7129274 -0.3147745 0.5630798 0.7747612 -0.2875522 0.6249149 0.7131769 -0.3175847 0.6243978 0.7129347 -0.3191421 0.6236873 0.7132303 -0.3198702 0.5619575 0.7748929 -0.2893869 0.4585787 0.8568518 -0.2356067 0.6232938 0.7129287 -0.3213062 0.6227157 0.7131443 -0.321948 0.561334 0.7745696 -0.2914555 0.4578182 0.8566428 -0.2378359 0.6219418 0.7131318 -0.3234683 0.560002 0.7748287 -0.2933228 0.6214973 0.7132387 -0.3240857 0.6209437 0.712776 -0.3261587 0.5587431 0.7747877 -0.2958213 0.6197569 0.7136956 -0.3264047 0.4565981 0.8565526 -0.2404915 0.4554957 0.8566066 -0.2423816 0.6200919 0.7129012 -0.327503 0.6189925 0.7132666 -0.3287844 0.0964697 0.9938424 -0.05450642 0.08356118 0.9953486 -0.04794543 0.08371329 0.9953432 -0.04779255 0.557856 0.7747847 -0.2974988 0.6189204 0.7127961 -0.3299383 0.6183739 0.7130435 -0.3304281 0.5570978 0.774883 -0.2986611 0.4547991 0.8565862 -0.2437579 0.1830839 0.9779532 -0.1004382 0.1832079 0.9779331 -0.1004088 0.2015191 0.9732616 -0.1102358 0.4558354 0.8562783 -0.2429026 0.3024139 0.9392257 -0.1624838 0.3022307 0.9391949 -0.1630025 0.3405891 0.9221542 -0.1833871 0.6182269 0.7127447 -0.3313466 0.3409624 0.9221427 -0.1827499 0.3892729 0.8974183 -0.2076224 0.3458146 0.920158 -0.1836348 0.4056597 0.8886854 -0.2137252 0.3190476 0.9319034 -0.1725249 0.625611 0.7083178 -0.3269511 0.6352291 0.7018528 -0.3223145 0.6564103 0.6669699 -0.3525291 0.462852 0.8538316 -0.2382012 0.4254041 0.8772377 -0.2224529 0.5589378 0.7750173 -0.2948508 0.5293944 0.8007144 -0.2803538 0.4883643 0.8397597 -0.2372848 0.5937753 0.7440809 -0.3062264 0.3795647 0.902355 -0.204172 0.3616231 0.9131983 -0.1878767 -0.1033569 0.9932996 0.05170542 -0.1148034 0.9917455 0.05710661 -0.125594 0.9901323 0.06216442 -0.1267949 0.9899277 0.06297868 -0.1294078 0.9895241 0.06399923 -0.1273715 0.9896283 0.06642603 -0.04818958 0.9984925 0.02627688 -0.04867851 0.9985048 0.02487331 -0.05664324 0.9979409 0.0300917 -0.1399036 0.9877573 0.06901156 -0.115177 0.9917926 0.05551326 -0.1149329 0.9918227 0.05548274 -0.1272948 0.9899148 0.06216722 0.5794637 0.7740526 -0.2550776 0.5810847 0.7739656 -0.2516304 0.6430109 0.7123508 -0.2812353 0.6444944 0.7116966 -0.2794905 0.6448761 0.7119578 -0.2779407 0.6457489 0.7118222 -0.2762569 0.5822818 0.7739138 -0.2490087 0.5834604 0.7738678 -0.2463791 0.5849403 0.7737046 -0.243364 0.6475011 0.711897 -0.2719284 0.6498759 0.7113415 -0.2676839 0.6488217 0.7118757 -0.2688189 0.5863078 0.7736053 -0.2403706 0.5876141 0.7734447 -0.2376825 0.6507883 0.7114906 -0.2650579 0.6517948 0.7112153 -0.2633181 0.6518979 0.7115025 -0.2622851 0.5886849 0.7734786 -0.2349063 0.6529633 0.7110419 -0.2608801 -0.1377635 0.988577 0.06112986 -0.1303481 0.9895593 0.06149643 -0.1241203 0.9905211 0.05884039 0.5904021 0.7730622 -0.2319492 0.6529953 0.7115927 -0.2592937 -0.1367251 0.9879916 0.07196378 0.654916 0.7104918 -0.2574617 0.6538067 0.7110602 -0.2587088 0.6545822 0.7114706 -0.2556008 0.6549391 0.7113078 -0.2551394 0.6561672 0.7106443 -0.2538298 0.5911042 0.7732453 -0.2295381 0.6561912 0.7110036 -0.2527592 0.5921924 0.7731706 -0.2269704 0.6571086 0.7109444 -0.250532 0.6569338 0.7105872 -0.2520001 0.6569261 0.7114029 -0.2497082 0.6581422 0.7104822 -0.2491266 0.6589341 0.7101754 -0.2479052 0.6585065 0.7110601 -0.2465012 0.6585435 0.7113417 -0.245588 0.6590844 0.7116073 -0.2433571 0.5953704 0.7729316 -0.2193421 0.6595878 0.7114099 -0.2425691 0.6609545 0.7106398 -0.2411018 0.6606881 0.7113201 -0.2398229 0.5966217 0.7728096 -0.2163513 0.6617553 0.7108307 -0.2383271 0.6632837 0.7110164 -0.2334753 0.6618437 0.7119261 -0.2347857 0.5979992 0.7726013 -0.2132703 0.6644104 0.7104339 -0.23204 0.6655018 0.7103345 -0.2291992 0.5995495 0.7725018 -0.2092396 0.6654465 0.7112563 -0.226485 0.6018657 0.7723144 -0.2031956 0.6679183 0.709913 -0.2234024 0.6044034 0.7716795 -0.1980089 0.6686433 0.7101188 -0.2205616 0.6711294 0.7097063 -0.2142486 0.6702389 0.7095175 -0.2176346 0.6058062 0.7714645 -0.1945294 0.6731309 0.7092961 -0.20927 0.6095927 0.7705516 -0.1861373 0.6761887 0.7080205 -0.2036562 0.607387 0.7711819 -0.190682 0.6113888 0.7701491 -0.1818632 0.6780504 0.7080205 -0.1973692 0.613344 0.7698159 -0.1766145 0.6811656 0.7071072 -0.1897705 0.6152715 0.7692115 -0.1724957 0.6177191 0.7685475 -0.1666071 0.6843683 0.7058234 -0.1829031 0.6196355 0.7681124 -0.1614171 0.6857181 0.7058306 -0.1777471 0.6217059 0.7676485 -0.1555562 0.6875461 0.7053696 -0.1724358 0.6893815 0.7050077 -0.1664856 0.6242353 0.76682 -0.1493904 0.6913545 0.703959 -0.1626985 0.6267859 0.7658343 -0.1436569 0.6930025 0.7034706 -0.1577239 0.6288084 0.7653799 -0.1370902 0.6943708 0.7034044 -0.1518936 0.6309756 0.7648004 -0.1301931 0.6335609 0.7638195 -0.1232085 0.6962577 0.7028498 -0.1456971 0.6986801 0.701671 -0.1396566 0.6365323 0.7624532 -0.1161549 0.7010486 0.7004382 -0.1338557 0.7021817 0.70032 -0.128424 0.6388661 0.7615548 -0.1090159 0.7040498 0.6996855 -0.1214668 0.6444158 0.7589549 -0.09335863 0.7065786 0.6983385 -0.1143246 0.6414104 0.7604942 -0.1011998 0.6475805 0.7572044 -0.08533084 0.7094934 0.6965225 -0.1071244 0.7116481 0.6955034 -0.09915703 0.7135055 0.6944922 -0.09268641 0.6502687 0.7557424 -0.07748776 0.7159763 0.6929649 -0.08472079 0.6529372 0.7542929 -0.06866919 0.7187784 0.6910368 -0.07632744 0.6560367 0.7523548 -0.05981725 0.6591788 0.7502779 -0.05066144 0.7217727 0.6888122 -0.06769096 0.7236506 0.6877596 -0.05759048 0.726195 0.6856355 -0.05044758 0.6622058 0.7481479 -0.04193335 0.7289276 0.6833314 -0.04150646 0.6648892 0.7462531 -0.03207552 0.7315247 0.6810758 -0.03174036 0.7303344 0.6781458 0.08203673 0.6753329 0.7339606 0.07230037 0.727856 0.6793913 0.09302294 0.6678013 0.744009 -0.02218776 0.7387157 0.6701087 0.07248294 0.7494837 0.6587814 0.06543254 0.6836553 0.7280299 0.05087506 0.6462857 0.711781 -0.2751048 0.5776714 0.7742163 -0.2586215 0.6414961 0.7122716 -0.284872 0.6403456 0.7120342 -0.2880365 0.6388662 0.7128151 -0.2893866 0.5756542 0.7744871 -0.2622824 0.638624 0.7122985 -0.2911881 0.6371421 0.7128899 -0.292981 0.3108398 0.9390813 -0.1466456 0.3506923 0.9221583 -0.1632149 0.6356906 0.7127829 -0.2963748 0.6712021 0.7411819 -0.01171922 0.7344802 0.6782939 -0.02136355 0.7398779 0.6727355 -0.002777218 0.7372815 0.6755107 -0.01007127 0.6743817 0.7383804 -0.001953184 0.6767612 0.7361513 0.008697926 0.7419216 0.6704456 0.007416129 0.745733 0.6655289 0.03088527 0.7437853 0.6681585 0.01864725 0.6794543 0.7334432 0.02008175 0.7480956 0.6624883 0.03824096 0.6822862 0.7304455 0.03058016 0.7489107 0.6608628 0.04892224 0.7491151 0.6596949 0.06024414 0.6838153 0.728465 0.04165881 0.6777486 0.7328365 0.06006252 0.7286596 0.6770812 0.1030347 0.6783562 0.7294458 0.0879876 0.7289229 0.6742019 0.1188421 0.6788072 0.7264476 0.1072138 0.7245524 0.673372 0.1469491 0.7284247 0.6724225 0.1313227 0.7338075 0.6519851 0.1908985 0.7229226 0.6680786 0.1762213 0.6824179 0.7182174 0.1359037 0.6907999 0.7022141 0.1723108 0.7013942 0.6786573 0.2178772 0.7369503 0.6380372 0.2231879 0.710915 0.650731 0.2667381 0.7503309 0.5989829 0.279684 0.7515709 0.6048032 0.263352 0.7553781 0.5617955 0.3373275 0.7169499 0.6186181 0.3213945 0.7570654 0.5667155 0.3250931 0.7183328 0.5853602 0.3759673 0.7557185 0.5213609 0.3963235 0.7549863 0.5295097 0.3868015 0.7110956 0.5573707 0.4285801 0.7407035 0.5050945 0.4429877 0.7487671 0.4954852 0.4402753 0.7243114 0.4858956 0.4891611 0.7029858 0.5227683 0.4822078 0.73166 0.4767356 0.4872341 0.703811 0.4754028 0.5278659 0.7220188 0.4392296 0.5345711 0.6665629 0.5013642 0.5516593 0.7083897 0.4180876 0.5686711 0.6888583 0.492373 0.532018 0.6914851 0.4198291 0.5878707 0.6763039 0.4478988 0.5848075 0.6584879 0.4473542 0.6052009 0.6627851 0.3897604 0.6393769 0.6511247 0.3588739 0.6687648 0.6681888 0.4092633 0.6213111 0.6474667 0.1918137 0.7375597 0.6515516 0.3494738 0.6733117 0.6470699 0.3023241 0.6999292 0.6122453 0.3611945 0.7033451 0.6380664 0.1344068 0.7581597 -0.08594292 0.989687 0.1146008 -0.09695774 0.9876754 0.1228681 -0.09876 0.9878752 0.1197878 -0.09332811 0.9874839 0.1271436 -0.08838343 0.9898278 0.1114864 -0.09781348 0.9866801 0.1299805 -0.1074262 0.9883823 0.1075178 -0.1094413 0.9880544 0.1084952 -0.1123408 0.9886054 0.1001942 -0.1257402 0.9897469 0.06775325 -0.1326053 0.9896724 0.05444598 -0.1287613 0.9902626 0.05292057 -0.1462159 0.988995 0.02258396 -0.1431661 0.9894668 0.02142453 -0.134589 0.9901903 0.0375384 -0.1396534 0.989995 0.02017283 -0.1560437 0.9875949 -0.01751786 -0.1638258 0.9857324 -0.03863698 -0.1509172 0.988363 -0.01904392 -0.1800344 0.9782106 -0.1034 -0.1662675 0.9823763 -0.08539217 -0.1751788 0.9809712 -0.08371353 -0.1791152 0.97404 -0.1384335 -0.1785376 0.9720379 -0.1525352 -0.1639777 0.9766027 -0.1391353 -0.1361754 0.9775823 -0.1605906 -0.1411196 0.9752943 -0.16996 -0.1227777 0.9783763 -0.1664503 -0.1079171 0.9808068 -0.1623945 -0.1132257 0.9790515 -0.1692282 -0.09485191 0.982273 -0.1616877 -0.1187193 0.9802128 -0.1583942 -0.04663336 0.9893115 -0.1381605 -0.04205536 0.9911096 -0.1262272 0.001037657 0.9949305 -0.1005612 0.2042951 0.9721567 0.1147825 0.244886 0.9481703 0.2024948 0.3042506 0.9153156 0.2638731 0.07315355 0.9921667 -0.1012614 0.09934002 0.9917216 -0.08136415 0.0935111 0.9912974 -0.09265655 0.1319656 0.9899868 -0.05011272 0.171702 0.9851353 -0.005188286 0.1572352 0.9869621 -0.03439515 0.264054 0.9491844 0.1712444 0.3655291 0.870348 0.3299741 0.3524975 0.853868 0.3829557 0.4063007 0.7980745 0.4449685 0.4918413 0.7283317 0.4771007 0.4283647 0.8096997 0.4011113 0.5090568 0.6424553 0.572811 0.4414941 0.8602511 0.2550508 0.4202172 0.8864877 0.1937961 0.3751417 0.9140189 0.1543965 0.4590148 0.7278621 0.5094333 0.5807572 0.7357661 0.3483811 0.6420459 0.6442738 0.4155581 0.5694622 0.7700359 0.2876762 0.5066174 0.8308526 0.2302668 0.5226465 0.8019 0.2894775 0.6424937 0.6006823 0.4757969 0.1489323 0.9888436 0.002716183 0.09894382 0.9945047 -0.03421223 0.1736834 0.9835039 0.05053937 0.2204107 0.9736893 0.05786466 0.2937451 0.9428532 0.1572948 0.2505621 0.9646186 0.08203542 0.1884853 0.9815521 0.03207546 0.2321258 0.9674451 0.100834 0.2839522 0.9524487 0.1105107 0.5311225 0.4931873 0.6889669 0.5927755 0.4077373 0.6945268 0.5553333 0.5350683 0.6366373 0.5703729 0.3370843 0.7490321 0.6242671 0.2014257 0.754797 0.5960747 0.09345042 0.7974723 0.3785353 0.7810592 0.4966464 0.46374 0.6519828 0.5998864 -0.1058093 0.9925691 0.06009185 0.522589 0.4736964 0.7088812 0.3192021 0.9370974 0.1412742 0.3435208 0.9168796 0.2032864 0.3830729 0.8914257 0.2421062 0.3935471 0.8677874 0.3034235 0.422443 0.8613663 0.282117 0.4638937 0.8238692 0.3256412 0.3978443 0.8923725 0.2130524 0.3569877 0.9175411 0.175152 0.5510547 0.7190629 0.4234234 0.4880939 0.8189833 0.3017131 0.5066828 0.7775118 0.372489 0.589967 0.6943427 0.412101 0.5959207 0.6450873 0.4782686 0.639446 0.5509698 0.5362288 0.5378714 0.7651178 0.3539623 0.3892738 0.8970847 -0.2090573 0.3904685 0.897278 -0.2059772 0.3895235 0.8972805 -0.2077479 0.3915305 0.8973247 -0.203746 0.3046737 0.9392606 -0.1579982 0.2746702 0.9511219 -0.1411499 0.3953472 0.8972374 -0.1966359 0.3973667 0.8972187 -0.1926099 0.4653285 0.856617 -0.2228828 0.6368057 0.7126755 -0.2942319 0.6408134 0.7125948 -0.2855994 0.6427754 0.7119941 -0.2826734 0.4694668 0.8564724 -0.2146064 0.4709774 0.856378 -0.2116529 0.6471247 0.7118555 -0.2729313 0.4720471 0.8564113 -0.2091205 0.6487713 0.7113351 -0.2703672 0.473164 0.8563889 -0.2066735 0.6502089 0.7118269 -0.265577 0.4745422 0.8563061 -0.2038373 0.4759193 0.8561909 -0.2010922 0.4802476 0.855876 -0.1919342 0.4793948 0.855879 -0.1940407 0.4772247 0.8560562 -0.1985562 0.4815046 0.8557335 -0.1894034 0.4783912 0.8559463 -0.196209 0.4828984 0.8555325 -0.1867443 0.4836684 0.8555145 -0.1848243 0.485074 0.8551512 -0.1828107 0.4861755 0.8552173 -0.1795462 0.4879781 0.8549765 -0.1757624 0.4903768 0.8545583 -0.1710581 0.4928796 0.8542535 -0.1652901 0.4950546 0.8539318 -0.1603792 0.496858 0.8536313 -0.1563515 0.4986493 0.8533102 -0.1523506 0.5005818 0.8529302 -0.1480809 0.5025916 0.8525258 -0.1435322 0.5047231 0.8520599 -0.1387394 0.506933 0.851562 -0.133646 0.5092447 0.8509997 -0.1283336 0.5116505 0.8503805 -0.1227473 0.514159 0.8496884 -0.1169195 0.5167204 0.8489524 -0.1108152 0.5193777 0.8481316 -0.1044981 0.5220953 0.847249 -0.09790623 0.5249047 0.846275 -0.09107011 0.5277395 0.8452316 -0.08411115 0.5305479 0.8441338 -0.0771833 0.5332912 0.8429993 -0.07037705 0.5359492 0.8418442 -0.06369376 0.5385327 0.8406677 -0.05710041 0.5410478 0.8394665 -0.05063164 0.5434908 0.8382478 -0.04425323 0.5458634 0.837015 -0.03793513 0.5481933 0.8357492 -0.03174036 0.550441 0.8344814 -0.02560544 0.5526703 0.8331713 -0.0195322 0.5548324 0.8318518 -0.01355034 0.5566118 0.8307366 -0.007751882 0.5590237 0.8291509 -0.001190245 0.5602618 0.8283073 0.003723263 0.5630097 0.8263864 0.01028478 0.5641222 0.8255521 0.01516813 0.5668413 0.823542 0.02166891 0.5678644 0.8226968 0.02645981 0.5704668 0.8206641 0.03283876 0.5723847 0.8190702 0.03872865 0.5756474 0.8162279 0.04901331 0.5805364 0.8116279 0.06509745 0.5871022 0.8047668 0.08752971 0.5950575 0.7952004 0.1164601 0.6040084 0.7823635 0.1519253 0.6134881 0.7655021 0.1940077 0.6230209 0.7436637 0.2425063 0.6067537 0.1284861 0.7844369 0.6049593 0.1725577 0.777334 0.631382 0.7164391 0.296769 0.6381062 0.6830312 0.3553715 0.575738 -0.01886063 0.8174167 0.4502478 0.8742187 0.1817105 0.4691416 0.8503573 0.2383247 0.3414161 0.9221624 -0.1818017 0.3423977 0.9221451 -0.1800342 0.2026494 0.973236 -0.1083747 0.2034409 0.9732263 -0.1069697 0.2231517 0.9675911 -0.1181983 0.3435846 0.9221362 -0.1778045 0.3448086 0.9221755 -0.1752121 0.4008667 0.8971358 -0.1856164 0.4020639 0.8971511 -0.1829338 0.4035594 0.8970599 -0.180065 0.4048693 0.8969627 -0.1775919 0.4063296 0.8968305 -0.1749042 0.4075472 0.8967627 -0.1724004 0.4086543 0.8966895 -0.1701455 0.4121043 0.8965092 -0.1626077 0.4110069 0.8966341 -0.1646835 0.4094502 0.8966948 -0.1681932 0.4103596 0.8967117 -0.1658712 0.4130463 0.8964392 -0.1605918 0.4140203 0.896159 -0.1596447 0.4143841 0.8962453 -0.1582094 0.4154565 0.896224 -0.1554948 0.4171022 0.8960359 -0.1521369 0.4191451 0.8958181 -0.1477414 0.4215323 0.8955577 -0.1424334 0.4240382 0.8951376 -0.1375514 0.4255871 0.8949078 -0.1342224 0.4275085 0.8945694 -0.1303156 0.4294083 0.8942497 -0.1261978 0.4314498 0.8938767 -0.1218021 0.4335548 0.8934781 -0.117163 0.4358107 0.8930152 -0.1122182 0.4381383 0.8925129 -0.107032 0.4405974 0.8919373 -0.1015965 0.4431387 0.891313 -0.09586077 0.4457942 0.8906118 -0.08987909 0.4485126 0.8898531 -0.08365356 0.4513412 0.88901 -0.07715129 0.4542521 0.8880866 -0.07040846 0.4571754 0.8870974 -0.06363219 0.4599862 0.886096 -0.05697941 0.4626679 0.8850812 -0.05069202 0.4651781 0.8840888 -0.04468053 0.4675542 0.8831036 -0.03900349 0.4697512 0.8821569 -0.03366261 0.4718335 0.8812239 -0.02859687 0.4737777 0.880322 -0.02383536 0.4772322 0.8786542 -0.01471036 0.4754308 0.8795378 -0.01947134 0.4783909 0.8780725 -0.01144474 0.4801592 0.8771534 -0.0070194 0.4824196 0.8759363 -0.002685666 0.4846793 0.8746873 0.002868771 0.4862927 0.8737643 0.007446646 0.4882104 0.8726568 0.01098674 0.4882796 0.8725797 0.01370316 0.4904462 0.8712668 0.01889145 0.4945594 0.8686302 0.02987802 0.5006945 0.8643589 0.04678559 0.508844 0.8580123 0.06994962 0.518772 0.8490855 0.09964644 0.5302973 0.8367991 0.136206 0.6320191 0.4952327 0.5960676 0.5430654 0.8201832 0.1799434 0.5564834 0.7981634 0.2307846 0.6196271 0.4329424 0.6546934 0.3339706 0.9349527 0.1196959 0.2939321 0.9426824 -0.1579682 0.2769045 0.9492515 -0.1491493 0.2710402 0.9513415 -0.1465832 0.3036973 0.9392306 -0.1600431 0.3029313 0.9391909 -0.16172 0.2472972 0.9605618 -0.127143 0.2250459 0.9675999 -0.1144762 0.2484241 0.9605833 -0.1247614 0.3485621 0.9222049 -0.16746 0.3518543 0.9221337 -0.1608355 0.3533535 0.9220822 -0.1578157 0.3548153 0.9220436 -0.1547319 0.3560383 0.9219885 -0.1522303 0.3571358 0.9219244 -0.1500324 0.358115 0.9218699 -0.1480192 0.3617388 0.9215137 -0.1412713 0.3606417 0.9216706 -0.143042 0.3593359 0.9217787 -0.1456082 0.3621746 0.9215051 -0.1402065 0.3628425 0.9214046 -0.1391369 0.3638837 0.9214134 -0.1363304 0.3655904 0.9212549 -0.1327893 0.3678496 0.9210126 -0.1281507 0.3703166 0.9208168 -0.1223198 0.372911 0.9204209 -0.1173148 0.3745632 0.9201868 -0.1138369 0.3765797 0.9198567 -0.1097785 0.3785864 0.9195333 -0.1055037 0.3806936 0.9191703 -0.1009873 0.3829542 0.9187483 -0.09616577 0.3853011 0.9182832 -0.0910989 0.3877446 0.9177689 -0.0857585 0.3903352 0.9171808 -0.08011174 0.3930013 0.916535 -0.07425421 0.3957724 0.9158189 -0.06811875 0.3986424 0.915028 -0.06170988 0.4015962 0.9141587 -0.05508631 0.4045634 0.9132282 -0.04840356 0.4073653 0.9122994 -0.04199385 0.4099618 0.9113892 -0.03607344 0.412372 0.9105023 -0.03057998 0.4145365 0.9096733 -0.02557468 0.4164964 0.9088943 -0.02102774 0.4182685 0.9081661 -0.01690775 0.4197316 0.9075517 -0.01324534 0.4216254 0.9067313 -0.00839281 0.4237912 0.9057523 -0.003723323 0.4252898 0.905057 -7.01949e-4 0.4260439 0.9047023 5.18821e-4 0.4263526 0.9045572 -1.22077e-4 0.4243981 0.9054701 -0.003204464 0.4237928 0.9057558 -0.00250256 0.4279394 0.9037939 0.004944086 0.4323909 0.9015266 0.01696842 0.4397771 0.8974078 0.03543239 0.4493921 0.8913072 0.06015288 0.4612397 0.8825295 0.09164971 0.5978712 0.5866401 0.5462633 0.4747601 0.8704138 0.1303179 0.4903219 0.8534398 0.1767063 0.592592 0.5238322 0.6119107 0.2966148 0.9508216 0.08920723 0.1207932 0.9926531 0.006988763 0.04889136 0.9964134 -0.06906437 0.2586799 0.9561635 -0.1372444 0.2445837 0.9608474 -0.1301965 0.1673659 0.9817335 -0.09048867 0.1590066 0.9835218 -0.08603447 0.1510694 0.9850032 -0.08334755 0.2719568 0.9511315 -0.1462481 0.2725967 0.9511586 -0.1448742 0.273545 0.9511356 -0.1432273 0.2240076 0.9675968 -0.1165205 0.2760145 0.9510964 -0.1386786 0.2772651 0.9511553 -0.1357485 0.3087987 0.9392145 -0.1500656 0.3098037 0.9391165 -0.1485996 0.3118421 0.9390665 -0.1445985 0.3129748 0.9390159 -0.1424638 0.3153225 0.9388871 -0.138068 0.3163673 0.9388779 -0.1357211 0.3174271 0.9388226 -0.1336117 0.3183482 0.9387778 -0.1317219 0.3200815 0.9387288 -0.1278129 0.3210598 0.9386422 -0.1259824 0.3192004 0.9387099 -0.1301339 0.3216412 0.9385858 -0.1249148 0.3216407 0.9385535 -0.1251587 0.3212493 0.9386913 -0.1251303 0.3225019 0.938512 -0.1232386 0.3237181 0.9384071 -0.1208258 0.3256969 0.9382097 -0.1169787 0.3281468 0.9379591 -0.1120374 0.3308868 0.9376956 -0.1060229 0.3332739 0.9374091 -0.1009588 0.3352863 0.9371293 -0.09680759 0.3372655 0.9368419 -0.09262514 0.339372 0.9365081 -0.08820009 0.3415958 0.9361305 -0.08349913 0.3439456 0.935703 -0.07849407 0.3463914 0.9352263 -0.07324576 0.3489859 0.9346778 -0.06772184 0.3516734 0.9340724 -0.06192356 0.3544515 0.9334033 -0.05588084 0.3573453 0.9326564 -0.04956257 0.3603352 0.9318299 -0.04303145 0.363301 0.9309589 -0.03643995 0.366111 0.9300796 -0.0302447 0.3686406 0.9292466 -0.02459841 0.3709041 0.9284657 -0.0195325 0.3729111 0.9277456 -0.0150153 0.3745329 0.927146 -0.01120054 0.37596 0.9266092 -0.007049798 0.3780452 0.9257789 -0.003906488 0.3798363 0.9250537 -3.66225e-4 0.380329 0.9248507 0.00112915 0.3798731 0.9250385 3.66231e-4 0.377973 0.9258126 -0.002746641 0.3756352 0.9267274 -0.008637011 0.371787 0.9281551 -0.01739603 0.3733687 0.9275621 -0.01498478 0.3772183 0.9261077 -0.005554497 0.3834987 0.9234976 0.009002983 0.3921714 0.9194207 0.02945095 0.4033126 0.9133207 0.05643016 0.5610115 0.6619094 0.497134 0.4167711 0.9044994 0.09045904 0.4326356 0.8918226 0.1322078 0.55063 0.6248835 0.5534682 0.2311821 0.9649528 -0.1241822 0.2212007 0.9677529 -0.1205189 0.2713133 0.9511837 -0.1471012 0.1511302 0.9850017 -0.08325588 0.1663299 0.9818047 -0.09161877 0.24452 0.9604707 -0.1330638 0.2449206 0.9605159 -0.1319977 0.2455909 0.9605118 -0.1307763 0.2463522 0.9605358 -0.1291579 0.2043853 0.9732182 -0.1052293 0.1854351 0.9779905 -0.09564739 0.2055174 0.9732017 -0.1031554 0.249673 0.9606046 -0.1220745 0.2781794 0.9512423 -0.1332453 0.2273669 0.9676674 -0.1091971 0.2068253 0.9731806 -0.1007117 0.2079861 0.9732166 -0.09793508 0.3139773 0.9389714 -0.1405389 0.2810785 0.9511806 -0.1274772 0.2821159 0.9511494 -0.1254018 0.2832183 0.9511008 -0.1232671 0.2842537 0.9510626 -0.1211603 0.2850466 0.9510607 -0.1192984 0.285809 0.95112 -0.1169787 0.2888619 0.9507569 -0.1123402 0.2884387 0.95074 -0.1135627 0.2873053 0.9508482 -0.1155142 0.2888015 0.9507895 -0.1122184 0.2881041 0.950896 -0.1131052 0.2888628 0.9507601 -0.1123101 0.2901435 0.9507259 -0.1092578 0.2919791 0.9505877 -0.1055055 0.2943314 0.9503818 -0.1007148 0.297077 0.9501031 -0.09512931 0.2995174 0.9498248 -0.09012377 0.3014714 0.949583 -0.08606487 0.303447 0.9493132 -0.08200359 0.3055241 0.9490138 -0.07763987 0.3077562 0.9486607 -0.07300204 0.3101046 0.948259 -0.06811863 0.3125498 0.9478126 -0.06296163 0.3151369 0.9473029 -0.05749738 0.3178266 0.946735 -0.05176049 0.3206071 0.9461039 -0.04580968 0.3235052 0.9453982 -0.03958356 0.3264912 0.9446212 -0.03308248 0.3294883 0.9437845 -0.02661293 0.3322662 0.9429621 -0.02053964 0.3347351 0.9421902 -0.01516807 0.3369001 0.9414829 -0.01040697 0.338765 0.9408511 -0.00613439 0.3410491 0.9400444 -0.00149542 0.3429718 0.9393424 0.002502501 0.3437945 0.9390336 0.00463885 0.3437418 0.9390563 0.00387597 0.3737357 0.927442 -0.01315367 0.3422747 0.9395998 6.10387e-4 0.337872 0.9411648 -0.007171869 0.3339377 0.9424538 -0.01632755 0.3318381 0.9430818 -0.02191293 0.3292118 0.9438404 -0.02801668 0.3279866 0.9442242 -0.02942019 0.3318685 0.943051 -0.02276748 0.3363218 0.9416707 -0.011994 0.3439483 0.9389758 0.004913508 0.3540176 0.9348201 0.02798569 0.5233151 0.7237967 0.449733 0.3669294 0.9284475 0.05786389 0.3823119 0.9191111 0.09524989 0.4001936 0.9055856 0.1405698 0.2962219 0.9000495 0.3196303 0.2393929 0.9358117 0.2587422 0.2817573 0.8785994 0.3855851 0.21415 0.9699467 -0.1155134 0.2022781 0.9733033 -0.1084635 0.2219985 0.9675584 -0.1206129 0.2224855 0.967583 -0.1195135 0.1680093 0.9818399 -0.08810949 0.1845799 0.9779868 -0.09732562 0.2262662 0.9675976 -0.1120649 0.251176 0.9605119 -0.1196977 0.2530637 0.9604033 -0.1165521 0.2540119 0.9603806 -0.1146609 0.2549893 0.9603527 -0.112708 0.2559058 0.9603257 -0.1108467 0.2568515 0.9603243 -0.1086491 0.2581955 0.960237 -0.106208 0.260758 0.9601108 -0.1009582 0.2602357 0.9601593 -0.101842 0.2592911 0.9602253 -0.1036126 0.2609391 0.9600424 -0.1011406 0.2603302 0.9600783 -0.1023619 0.2600854 0.9601675 -0.1021481 0.2613991 0.9601114 -0.09927976 0.2632909 0.9599572 -0.09570884 0.2655171 0.9597983 -0.09103876 0.268112 0.9595877 -0.0854845 0.2708882 0.9592484 -0.08038753 0.2725649 0.9590587 -0.07690781 0.2746683 0.9587756 -0.07284814 0.2767498 0.958492 -0.06857705 0.2789431 0.9581727 -0.06399822 0.281262 0.9578047 -0.05917608 0.2837058 0.9573853 -0.05407989 0.2863011 0.9569008 -0.04870873 0.2889823 0.9563669 -0.04303145 0.2917634 0.9557693 -0.03714179 0.2946631 0.9550991 -0.03097701 0.2976793 0.9543498 -0.02456754 0.3006698 0.9535555 -0.01815855 0.3034215 0.9527778 -0.01223814 0.3058277 0.9520608 -0.007049798 0.3079103 0.951412 -0.002563595 0.3096737 0.9508422 0.001159667 0.3113848 0.9502685 0.005432367 0.3131288 0.9496714 0.008636951 0.3131848 0.9496563 0.008270561 0.3111385 0.9503535 0.004608273 0.3400775 0.9403939 -0.002563595 0.3365908 0.9415935 -0.01040685 0.3089764 0.9510697 -3.05192e-5 0.3072935 0.9516059 -0.004119992 0.305069 0.9522877 -0.009003102 0.3024455 0.9530542 -0.01464921 0.2994544 0.9538776 -0.02108871 0.2960338 0.9547548 -0.02841311 0.2897793 0.9562259 -0.04074305 0.2914908 0.9558066 -0.03830182 0.2957319 0.9548264 -0.02914589 0.3021666 0.9531326 -0.0152899 0.3112307 0.9503247 0.004303097 0.4863222 0.7735377 0.4063621 0.3230496 0.9458929 0.03042799 0.3375468 0.9391493 0.06372493 0.3551815 0.9288799 0.1050162 0.03949105 0.9977753 -0.05371272 0.1924513 0.9758375 -0.1034586 0.2021276 0.9732217 -0.1094717 0.07092672 0.9966366 -0.04104834 0.08407986 0.9953472 -0.04706031 0.2286207 0.9676477 -0.1067263 0.2295641 0.9675751 -0.1053516 0.2305094 0.9675415 -0.1035812 0.2314278 0.9675228 -0.1016903 0.2327077 0.9674537 -0.09940052 0.2337166 0.9674307 -0.09723442 0.2357892 0.9673889 -0.09253334 0.2367074 0.9672776 -0.09134411 0.2347838 0.9674266 -0.09467041 0.2365878 0.9673183 -0.091223 0.2360662 0.9673678 -0.09204596 0.2356664 0.9673248 -0.09350967 0.2363401 0.9672426 -0.09265607 0.2377445 0.9672142 -0.08929914 0.2397906 0.9670672 -0.08533215 0.242355 0.9668566 -0.08032721 0.2451905 0.9666319 -0.07419192 0.2476616 0.9663841 -0.06903398 0.2497373 0.9661415 -0.06482243 0.2517789 0.9658851 -0.06061005 0.253977 0.9655824 -0.05609339 0.2562719 0.9652391 -0.05136424 0.2587136 0.9648425 -0.04632854 0.2612717 0.9643948 -0.04098677 0.2639595 0.9638839 -0.03540211 0.266768 0.963307 -0.02957302 0.2696677 0.9626674 -0.02346926 0.2726569 0.9619596 -0.01709061 0.2756482 0.9611982 -0.01077318 0.2783918 0.9604547 -0.005005061 0.2807418 0.9597834 0 0.282638 0.9592176 0.004181087 0.284776 0.9585515 0.009033679 0.286789 0.9579065 0.0129401 0.2870292 0.9578321 0.01312303 0.2850161 0.958477 0.009369254 0.2931039 0.9554261 -0.03537142 0.2827863 0.9591721 0.004577755 0.2810194 0.9597021 3.66229e-4 0.2786418 0.9603836 -0.004699945 0.2758623 0.9611386 -0.01062065 0.2726837 0.9619465 -0.01739555 0.2690598 0.9627983 -0.02502596 0.264967 0.9636719 -0.03360152 0.2608154 0.9644616 -0.04229933 0.2580975 0.9648826 -0.0488606 0.2566639 0.9652212 -0.04971528 0.2611188 0.9643633 -0.04266524 0.2655485 0.9635556 -0.0323199 0.2736033 0.9617162 -0.01559519 0.4461236 0.8193072 0.3601521 0.2841051 0.958767 0.007080495 0.2976815 0.9539603 0.03668373 0.3144342 0.9463852 0.0740689 0.1777428 0.9792948 -0.0968979 0.1840589 0.9779444 -0.09872829 0.1835698 0.9779404 -0.09967398 0.1560131 0.985031 -0.07330662 0.1710607 0.9818367 -0.08206641 0.1548244 0.9850409 -0.0756573 0.2085343 0.973333 -0.09558457 0.2096053 0.9733161 -0.09338849 0.2106141 0.973232 -0.09198534 0.2117426 0.973198 -0.08972656 0.2132039 0.9731203 -0.08706992 0.2144892 0.9730451 -0.08472138 0.2154346 0.972981 -0.08304256 0.2154622 0.9729983 -0.08276677 0.2150049 0.9730002 -0.08392667 0.214003 0.9730854 -0.08548521 0.2144554 0.9730606 -0.08462852 0.2158616 0.9730103 -0.08157753 0.2178463 0.9728924 -0.07761043 0.2202846 0.9727253 -0.07266521 0.2231248 0.9724896 -0.06692826 0.2256572 0.9722427 -0.06183141 0.2277002 0.9720215 -0.05768036 0.229745 0.9717777 -0.05352985 0.2319176 0.9714967 -0.0490753 0.2342314 0.9711676 -0.04437422 0.2366485 0.9707961 -0.03940069 0.2392048 0.9703695 -0.03411978 0.2418617 0.9698885 -0.02862662 0.2446691 0.9693379 -0.02282804 0.2475678 0.9687252 -0.01678526 0.2505925 0.9680361 -0.010468 0.253555 0.9673118 -0.004211664 0.2562698 0.9666042 0.001434385 0.2585613 0.965973 0.006500601 0.2613378 0.9651767 0.01168888 0.2636863 0.9644693 0.01638883 0.2641737 0.9643134 0.01767057 0.2622492 0.9648867 0.01480168 0.2603912 0.9654497 0.01016294 0.2584691 0.9660013 0.005951285 0.2561122 0.9666466 9.15558e-4 0.2533107 0.9673723 -0.004974603 0.250073 0.9681555 -0.01178032 0.2463796 0.9689772 -0.01950162 0.2422022 0.969816 -0.02819991 0.2375332 0.970642 -0.03784412 0.2327395 0.9713656 -0.04776257 0.2282834 0.9719439 -0.05667406 0.2284375 0.9719201 -0.05646079 0.2333502 0.9712754 -0.0466029 0.2400289 0.9702174 -0.03262436 0.2495248 0.9682824 -0.01290959 0.2620684 0.9649564 0.01339793 0.1841528 0.9827486 -0.01712125 0.229687 0.9725533 0.03720277 0.2128727 0.9770781 0.001922667 0.2775992 0.9595422 0.04709053 0.2620035 0.9630803 0.06189203 0.09021502 0.9946546 -0.05023473 0.09695774 0.9938398 -0.05368226 0.1671857 0.9818423 -0.08963572 0.1665406 0.9818484 -0.09076267 0.1102961 0.9921154 -0.05951225 0.0968365 0.9938483 -0.05374377 0.09732508 0.9938513 -0.05279785 0.1688944 0.98184 -0.08640044 0.1863779 0.9780035 -0.09366196 0.1875377 0.978004 -0.09131211 0.1887597 0.9780104 -0.08868807 0.1723707 0.9818236 -0.07944065 0.1903783 0.9779552 -0.08578926 0.1916889 0.9779156 -0.08328592 0.1937937 0.9777884 -0.0798369 0.1958118 0.9777163 -0.07568782 0.1959626 0.9777683 -0.07461899 0.1948035 0.9777718 -0.07754909 0.1962068 0.9777076 -0.07477158 0.1956245 0.9777563 -0.07565569 0.1948022 0.977765 -0.07764011 0.1948008 0.977758 -0.07773107 0.196209 0.9777187 -0.07461982 0.1981 0.9776211 -0.07080447 0.2005112 0.977469 -0.065952 0.2033185 0.9772537 -0.06030583 0.2058539 0.9770206 -0.05527079 0.2078641 0.9768179 -0.05118012 0.2098826 0.9765933 -0.04706102 0.2120446 0.976327 -0.04269576 0.2143331 0.9760202 -0.03802633 0.2167469 0.9756662 -0.03311324 0.2192786 0.9752634 -0.02789431 0.2219623 0.9747972 -0.02243119 0.22471 0.9742827 -0.01669377 0.227643 0.973686 -0.01068168 0.2306306 0.9730314 -0.004425227 0.2336207 0.9723262 0.001739561 0.2362767 0.9716582 0.007324516 0.2386879 0.9710185 0.01229906 0.2411348 0.9703379 0.01727402 0.243084 0.9697726 0.02124124 0.243327 0.969707 0.02145475 0.2412567 0.9703066 0.01733505 0.2386305 0.971033 0.01226872 0.2363702 0.9716355 0.007324576 0.2336565 0.9723178 0.001617491 0.2304498 0.9730714 -0.005005121 0.226787 0.9738628 -0.01260435 0.2226687 0.9746641 -0.02118039 0.2180007 0.9754638 -0.03076362 0.2128105 0.9762181 -0.04135352 0.2073779 0.9768581 -0.0523709 0.1992904 0.9776522 -0.06692862 0.2013949 0.97731 -0.06561583 0.2042018 0.9771534 -0.05893194 0.2099677 0.9765634 -0.04730373 0.2183301 0.9754053 -0.03027445 0.229503 0.9732822 -0.007080376 0.1078222 0.9920687 -0.06460791 0.1451788 0.9891206 -0.02374374 0.243942 0.9695118 0.0232253 -0.006836175 0.9962505 -0.08624565 0.1212208 0.9829509 0.1382504 0.1898894 0.9395898 0.2848037 0.1440821 0.9862653 -0.08075433 0.1361154 0.987814 -0.0754739 0.1523498 0.9849945 -0.08108842 0.1516188 0.9850035 -0.08234047 0.1529613 0.9850316 -0.07947146 0.1699017 0.9818413 -0.08438628 0.1926661 0.9778575 -0.08169919 0.1735945 0.9818406 -0.07651221 0.1749683 0.9817817 -0.07410132 0.1756055 0.9817616 -0.07284855 0.1767036 0.9817274 -0.07062035 0.17863 0.9815955 -0.06753939 0.1787532 0.981571 -0.06757032 0.1778669 0.9816557 -0.06866854 0.1779552 0.9816377 -0.06869781 0.176917 0.9817566 -0.06967419 0.1764301 0.9817035 -0.07162797 0.1768911 0.9816604 -0.07107996 0.1782032 0.9816288 -0.0681805 0.1800652 0.9815386 -0.06448775 0.1824425 0.981399 -0.05975615 0.1852229 0.9812023 -0.05417209 0.1876904 0.9809955 -0.04919624 0.1897084 0.9808011 -0.04516863 0.1917228 0.9805878 -0.04110956 0.1938584 0.98034 -0.0367757 0.1961438 0.9800475 -0.03216671 0.1985251 0.979716 -0.02728384 0.2010601 0.979329 -0.02212637 0.2037125 0.9788884 -0.01669371 0.2064933 0.9783864 -0.01098692 0.2093889 0.9778195 -0.005035579 0.2123814 0.9771862 0.00112915 0.215341 0.9765119 0.007263481 0.2179952 0.9758665 0.01275682 0.2203177 0.9752698 0.01757901 0.2225763 0.97466 0.02230948 0.2245892 0.974105 0.0260632 0.2242212 0.9742193 0.02493381 0.2222084 0.9747446 0.02227878 0.220776 0.9751498 0.01846408 0.2186987 0.9756906 0.01409971 0.2161627 0.9763181 0.008758783 0.2036241 0.9771636 -0.06073319 0.2131119 0.9770248 0.002441465 0.2095766 0.9777802 -0.004852533 0.2055158 0.9785655 -0.01315373 0.2009708 0.9793397 -0.0224623 0.1959047 0.980073 -0.03283894 0.1902274 0.9807409 -0.04428362 0.1843669 0.9812555 -0.0560944 0.1793608 0.9815559 -0.06616544 0.1759731 0.9816776 -0.07309323 0.1749072 0.9817509 -0.07465064 0.1782599 0.9815438 -0.069247 0.3280168 0.9150471 0.2347206 0.1823537 0.9813837 -0.06027591 0.1895865 0.980802 -0.04565697 0.1995972 0.9795522 -0.0252701 0.08450621 0.9933529 -0.07815837 0.0619536 0.9939435 -0.09076356 0.09576737 0.9938082 -0.05633735 0.1801514 0.9637477 0.1968146 0.1308658 0.9871094 0.09213709 0.1309557 0.9887752 -0.07193255 0.1228412 0.9901462 -0.06723457 0.1364185 0.9877675 -0.07553368 0.07172042 0.9966085 -0.0403465 0.06506621 0.9972042 -0.03674471 0.05826139 0.9977077 -0.03442579 0.1368768 0.9877714 -0.07464897 0.1373353 0.9877765 -0.07373374 0.1380079 0.9877551 -0.07275784 0.1108456 0.9921177 -0.0584442 0.1537872 0.9850442 -0.0777024 0.1133785 0.9921154 -0.05340844 0.1263474 0.9900876 -0.06134253 0.1123421 0.9921262 -0.05536228 0.1573573 0.9850091 -0.07068258 0.1587926 0.9849845 -0.06775313 0.16047 0.9849159 -0.06473124 0.1617183 0.9848673 -0.06231904 0.1625447 0.9848209 -0.0608856 0.1623021 0.9848608 -0.06088614 0.1616306 0.9848912 -0.06216794 0.1608375 0.9849236 -0.06369405 0.1600735 0.9849483 -0.06521964 0.160319 0.9849264 -0.06494551 0.1615661 0.9849 -0.06219714 0.1633991 0.9848202 -0.05856609 0.1657185 0.9846975 -0.05392718 0.1684659 0.9845184 -0.04840338 0.1709354 0.9843207 -0.04351967 0.1729198 0.9841414 -0.03955239 0.1749064 0.983944 -0.03552448 0.1770389 0.9837086 -0.03122061 0.1792971 0.9834334 -0.02667331 0.1816809 0.9831154 -0.0218212 0.1842131 0.9827446 -0.01669389 0.1868392 0.9823253 -0.01132261 0.1896173 0.9818416 -0.005707085 0.1924819 0.9813005 1.83113e-4 0.1954724 0.9806887 0.006347894 0.1984363 0.9800352 0.0124213 0.2010593 0.9794163 0.01785361 0.2032577 0.9788725 0.02224844 0.2046916 0.978473 0.02630746 0.2069836 0.9779074 0.02923768 0.2067679 0.9779282 0.03006142 0.2051782 0.9783735 0.02621567 0.2027408 0.9790034 0.02118051 0.2002679 0.9796097 0.01605314 0.1974263 0.9802649 0.01019328 0.1941015 0.9809759 0.003326535 0.1902534 0.9817247 -0.00451672 0.1858637 0.9824834 -0.01345908 0.1809494 0.9832124 -0.02346938 0.175485 0.9838758 -0.03454762 0.1693787 0.9844414 -0.04675459 0.1630644 0.9848263 -0.05939048 0.1575683 0.9849929 -0.07043725 0.1530227 0.9850343 -0.07931911 0.152718 0.9850372 -0.07986867 0.1569293 0.9850045 -0.07168936 0.1631544 0.9848169 -0.05929833 0.1721263 0.9842027 -0.04144459 0.199837 0.9797142 0.01501524 0.0634492 0.9946178 0.08191329 0.09061241 0.9790658 0.1822625 0.1153305 0.9912812 -0.06372326 0.1091677 0.992123 -0.0614354 0.1226557 0.9900963 -0.06830143 0.05810773 0.9977198 -0.03433358 0.1235731 0.9901109 -0.06641024 0.1230837 0.9901017 -0.06744724 0.1244565 0.9900974 -0.06494438 0.138589 0.9877938 -0.07111036 0.1395939 0.9877781 -0.06933915 0.1406612 0.9877724 -0.06723296 0.1418841 0.9877566 -0.06485342 0.1432278 0.9877315 -0.06222915 0.1444166 0.987722 -0.05957335 0.1464285 0.987614 -0.05636793 0.1472237 0.9875953 -0.05459851 0.1470732 0.9876092 -0.05475187 0.1463074 0.9876511 -0.05603259 0.1454527 0.9876807 -0.05771106 0.1446586 0.987707 -0.05923676 0.1444448 0.9877364 -0.05926722 0.1457275 0.9877125 -0.05645984 0.1476505 0.9876228 -0.0529198 0.1499071 0.9875192 -0.04831081 0.1525028 0.9873777 -0.04275691 0.1553124 0.987145 -0.03772175 0.1570523 0.9869943 -0.03430366 0.1591596 0.9867895 -0.03024488 0.1612939 0.9865638 -0.02600234 0.1635493 0.9863012 -0.02148509 0.1659002 0.9860013 -0.01669377 0.1684052 0.9856497 -0.01159727 0.1710583 0.9852411 -0.006256341 0.1738044 0.98478 -6.71413e-4 0.1766776 0.9842553 0.005157768 0.1796957 0.9836575 0.01129198 0.182628 0.9830298 0.01730448 0.1852482 0.9824259 0.02285844 0.1882122 0.9817129 0.028566 0.1904073 0.9811517 0.03296035 0.1907445 0.9810677 0.03350996 0.1885154 0.9816414 0.02902346 0.1855864 0.9823477 0.02346915 0.1830202 0.9829443 0.01800596 0.179942 0.9836078 0.01168888 0.1763371 0.9843203 0.004333615 0.1722168 0.9850507 -0.004058957 0.1675207 0.985775 -0.01358109 0.1622718 0.9864494 -0.02420186 0.1564386 0.9870343 -0.03592044 0.150002 0.9874806 -0.04880023 0.1432881 0.9877266 -0.06216776 0.1372121 0.9877686 -0.0740689 0.1292481 0.9876875 -0.08813893 0.1294006 0.9876866 -0.08792525 0.1342542 0.9876337 -0.08096754 0.1385282 0.9877648 -0.07162934 0.1867787 0.9716154 0.1451807 0.1496965 0.9865625 0.0654636 0.1464912 0.9876255 -0.05600237 0.0712313 0.9948273 -0.07242155 0.03939956 0.9939008 -0.1030004 0.1046815 0.992796 -0.05829203 0.1093798 0.9921092 -0.06128197 0.1097771 0.9921141 -0.06048876 0.1253716 0.9900946 -0.06320464 0.1274788 0.9900745 -0.05917674 0.1450887 0.9876965 -0.05835288 0.1287274 0.990054 -0.0567646 0.1298872 0.9900546 -0.05404847 0.1310176 0.9900327 -0.05166846 0.1326657 0.9899724 -0.04852503 0.1329401 0.98994 -0.04843342 0.1319039 0.990012 -0.04977679 0.1318749 0.9899927 -0.05023515 0.1308643 0.9900274 -0.05215644 0.1299493 0.990063 -0.05374372 0.1307117 0.9899973 -0.05310255 0.1321182 0.9899864 -0.04971599 0.134224 0.9898944 -0.04574847 0.1368163 0.9897595 -0.04071223 0.1396871 0.9895908 -0.03460896 0.1422188 0.989398 -0.02942037 0.1443238 0.9892087 -0.0252391 0.14643 0.9889975 -0.02102756 0.1486275 0.9887549 -0.0165413 0.1510099 0.9884621 -0.01178044 0.1535121 0.9881238 -0.006744742 0.1561332 0.987735 -0.001434326 0.1588818 0.9872892 0.004089534 0.1617524 0.9867815 0.009918749 0.1647392 0.9862076 0.01599168 0.1676692 0.9855985 0.02197337 0.1703863 0.9849937 0.02749741 0.1731666 0.9843399 0.03299134 0.1753647 0.9837946 0.03735578 0.1749678 0.9838848 0.03683692 0.1734092 0.9842394 0.03466963 0.1716393 0.9846984 0.03015285 0.1695342 0.9851909 0.02563613 0.1667264 0.9858012 0.01995956 0.1634294 0.9864666 0.0132147 0.1595842 0.9871696 0.005401849 0.1551905 0.9878785 -0.003479182 0.1335532 0.9876405 -0.08203631 0.150213 0.9885612 -0.01351976 0.1446588 0.9891736 -0.02468961 0.1384953 0.989671 -0.03701955 0.1317189 0.989998 -0.05053901 0.1246397 0.9900984 -0.06457823 0.1182623 0.9899854 -0.07709175 0.1134392 0.9897626 -0.08661299 0.1100808 0.9895372 -0.09326499 0.1105095 0.9895809 -0.09228962 0.1155762 0.9898595 -0.08258491 0.1052286 0.994087 0.02679544 0.1223511 0.9900704 -0.06921732 0.01742613 0.9932908 -0.1143229 -0.002716183 0.9922978 -0.1238464 0.02270579 0.9946008 -0.1012607 -0.08902519 0.9863577 -0.1384667 -0.0808745 0.9857231 -0.1476799 -0.1125541 0.9801185 -0.1633989 0.03341871 0.9992354 -0.02029538 0.02136296 0.9996663 -0.01452684 0.02172929 0.9996697 -0.01373338 0.1117011 0.9920948 -0.05719333 0.07413017 0.9966531 -0.03445571 0.08664292 0.9953411 -0.04229909 0.07327634 0.9966624 -0.03598201 0.09979707 0.9938505 -0.04797583 0.1008035 0.9938442 -0.04596126 0.1145063 0.9921034 -0.05117988 0.1159126 0.9920629 -0.04873943 0.1171643 0.9920356 -0.04623699 0.1182598 0.9919785 -0.04464876 0.1184445 0.9920225 -0.04315394 0.1187815 0.9920333 -0.04196417 0.1189921 0.992008 -0.0419631 0.1185678 0.9920025 -0.04327648 0.117011 0.9920608 -0.04608416 0.1181682 0.9919784 -0.0448929 0.1160961 0.9920669 -0.04822081 0.1162762 0.9920709 -0.0477007 0.1178659 0.9920335 -0.04446673 0.1198791 0.9919633 -0.04046833 0.1224129 0.9918466 -0.03543287 0.1253097 0.9916741 -0.02966415 0.1300131 0.991304 -0.02032595 0.1320865 0.9911068 -0.01614457 0.1343153 0.9908694 -0.0117194 0.136665 0.9905927 -0.006988883 0.1391648 0.9902672 -0.002014219 0.1279367 0.9914795 -0.02450692 0.1417624 0.9898955 0.003235042 0.1444788 0.9894694 0.008728504 0.1473472 0.9889782 0.01452714 0.1503369 0.9884209 0.0205698 0.153265 0.9878301 0.02649021 0.1559503 0.9872481 0.03195303 0.1585457 0.9866459 0.0373246 0.1606832 0.9861648 0.04074299 0.1583958 0.9866929 0.03671485 0.1607722 0.9861184 0.04150533 0.1566529 0.9870996 0.03308236 0.1540611 0.9876641 0.02801662 0.151071 0.9882794 0.02194344 0.1475601 0.9889424 0.01480174 0.1434689 0.9896332 0.006561517 0.1388311 0.9903122 -0.002777218 0.1336112 0.9909446 -0.01330614 0.1277512 0.9914913 -0.02499479 0.1212822 0.9918953 -0.03787392 0.1141703 0.9921008 -0.05197328 0.106725 0.992052 -0.06665354 0.1000107 0.9917758 -0.07986819 0.09473043 0.9914042 -0.09024417 0.09030503 0.9910054 -0.09875869 0.09015256 0.990946 -0.09949135 0.05130225 0.9924444 -0.111455 0.0305801 0.9924203 -0.1190245 0.05557465 0.9931118 -0.1031535 0.1194499 0.9919774 -0.0413832 0.07965356 0.9957919 -0.04532009 0.08450758 0.9953524 -0.04617547 0.09790533 0.9938552 -0.0516383 0.09879034 0.9938549 -0.04992926 0.1019342 0.993828 -0.04376453 0.1030005 0.9938099 -0.04162746 0.1046499 0.9937618 -0.03854554 0.105565 0.9937276 -0.03689736 0.1054444 0.9937416 -0.03686738 0.1046189 0.993758 -0.03872853 0.1033689 0.9938008 -0.04092639 0.1024515 0.9938134 -0.04287886 0.1025437 0.9938197 -0.04251289 0.1041 0.9937874 -0.03936934 0.1060836 0.9937258 -0.03543239 0.1085577 0.9936216 -0.03051942 0.111456 0.9934604 -0.02478152 0.1140204 0.993284 -0.01965445 0.116094 0.9931167 -0.0155341 0.1181687 0.9929283 -0.01138347 0.1203986 0.9927011 -0.006988883 0.1227159 0.9924392 -0.002319395 0.1251873 0.9921297 0.002624571 0.1277824 0.9917712 0.007843315 0.1305006 0.991359 0.01330637 0.133367 0.9908832 0.0190742 0.1363291 0.9903468 0.02505618 0.1392596 0.9897722 0.03094655 0.1419441 0.9892139 0.03616505 0.1463404 0.9882481 0.04416149 0.1438072 0.9887967 0.04001086 0.1443845 0.9886572 0.04135298 0.1465545 0.9881597 0.04541295 0.1417914 0.9892436 0.03595137 0.1390142 0.9898238 0.03039693 0.1358709 0.9904361 0.023988 0.1321458 0.9910933 0.01648002 0.1278425 0.9917636 0.007843255 0.1229602 0.9924098 -0.001953184 0.1174671 0.9929926 -0.01293998 0.1113647 0.9934622 -0.02511733 0.1046198 0.9937663 -0.03851521 0.09720224 0.9938438 -0.05316364 0.08945119 0.9936381 -0.06842362 0.08236968 0.9931972 -0.08230865 0.07660335 0.9926699 -0.09348052 0.06863647 0.9918873 -0.1069985 0.06906473 0.9918409 -0.1071526 0.01254343 0.9922143 -0.1239085 0.03518873 0.9930672 -0.1121584 0.07703125 0.9927082 -0.09271824 -0.02539205 0.9903213 -0.1364519 -0.009063959 0.9929524 -0.1181679 0.04098695 0.9991 0.01092576 -4.5779e-4 0.9999956 -0.002929806 -0.001709043 0.999994 -0.003021359 0.009552359 0.9999215 -0.008117973 0.07123219 0.9966409 -0.04040765 0.07147556 0.9966603 -0.03949159 0.08511793 0.9953522 -0.04504626 0.05975574 0.99772 -0.03137326 0.04687726 0.9985841 -0.02514767 0.06030505 0.99772 -0.03030514 0.0857284 0.9953529 -0.04385602 0.08746773 0.99535 -0.0403462 0.08850443 0.9953392 -0.03830105 0.1036127 0.9937967 -0.04040741 0.08957195 0.9953325 -0.03592032 0.09079349 0.9952799 -0.03427261 0.09115928 0.9953059 -0.03250235 0.09204673 0.9952708 -0.03103828 0.09259438 0.995222 -0.03097665 0.09161889 0.9952647 -0.03247249 0.09033721 0.995297 -0.03497517 0.08890312 0.9953305 -0.03759992 0.08902513 0.9953299 -0.0373252 0.09051829 0.995305 -0.03427243 0.09247207 0.9952503 -0.03042727 0.09491342 0.995157 -0.02557474 0.09778267 0.995009 -0.01989829 0.1003479 0.9948418 -0.01483243 0.1023923 0.9946858 -0.0107733 0.1044346 0.9945095 -0.00665301 0.1066319 0.994296 -0.002288877 0.1089539 0.9940442 0.002319455 0.1114234 0.9937466 0.007263422 0.1140198 0.9934008 0.0124213 0.1167358 0.993002 0.01788419 0.1195741 0.992545 0.02359127 0.1225343 0.9920245 0.0295425 0.1254332 0.9914714 0.03537154 0.1279662 0.9909526 0.04046821 0.1300424 0.9905012 0.04468011 0.1318746 0.9900825 0.04843437 0.132147 0.9900343 0.04867768 0.1300742 0.9905108 0.04437536 0.1269877 0.9911515 0.0386365 0.124212 0.9917122 0.03283834 0.1208553 0.9923264 0.02612429 0.1169794 0.9929667 0.01825034 0.1124632 0.9936132 0.009216785 0.107366 0.9942191 -9.7661e-4 0.1016291 0.9947452 -0.01239079 0.0731849 0.9922078 -0.1008352 0.09528052 0.9951352 -0.02505612 0.08825987 0.9953349 -0.03897225 0.0805695 0.9952776 -0.05414026 0.07251256 0.9949117 -0.06994897 0.06509637 0.9942995 -0.08444523 0.05908459 0.9936044 -0.09622609 0.05450636 0.9929565 -0.1051979 0.05105823 0.9924158 -0.1118215 0.07956224 0.9965272 -0.02456754 0.06216686 0.9980272 -0.00878942 0.08423155 0.9952446 0.0489214 -0.1373664 0.9747802 -0.1758816 -0.1227468 0.9798693 -0.1574468 0.05237132 0.9981076 -0.03222846 0.04526025 0.9985942 -0.02758949 0.05856549 0.9977201 -0.03354012 0.05917578 0.9977184 -0.03250241 0.07205551 0.9966615 -0.03839296 0.07275694 0.9966545 -0.03723299 0.0750454 0.9966483 -0.03256338 0.07632696 0.9966148 -0.03054904 0.07760894 0.9965868 -0.02813816 0.07867717 0.9965578 -0.026124 0.0791673 0.9965502 -0.02490383 0.078372 0.9965882 -0.02587985 0.07904374 0.9965616 -0.02484232 0.07709127 0.996632 -0.02795547 0.07608413 0.9966324 -0.03058016 0.07544249 0.9966223 -0.03244149 0.0755344 0.9966272 -0.0320754 0.07690888 0.9966111 -0.02917653 0.07883042 0.9965654 -0.02536123 0.08124202 0.9964816 -0.02060043 0.0840792 0.9963464 -0.01498466 0.08664238 0.9961896 -0.009979546 0.08865731 0.9960446 -0.005920648 0.09070342 0.9958762 -0.001861631 0.09286862 0.9956754 0.002441465 0.09518837 0.9954344 0.007049858 0.09762907 0.9951514 0.01193273 0.1002234 0.9948182 0.01709043 0.1029106 0.9944363 0.02249258 0.1057473 0.993994 0.02816873 0.1087091 0.993489 0.0340898 0.1115763 0.9929562 0.03985738 0.114081 0.9924566 0.04489386 0.1161558 0.9920239 0.04895263 0.1180493 0.991608 0.05270707 0.1177717 0.991675 0.05206489 0.1163385 0.9919292 0.05041742 0.1145681 0.9923545 0.04590046 0.1123402 0.9928116 0.04129207 0.109411 0.9933661 0.03540211 0.1059009 0.9939733 0.02832162 0.1017798 0.9946037 0.02011179 0.09708034 0.9952189 0.01071208 0.0917409 0.995783 9.15578e-5 0.08582025 0.9962413 -0.01174992 0.07919776 0.9965494 -0.02484273 0.07193398 0.9966381 -0.03921729 0.06396752 0.9964406 -0.05490338 0.05563658 0.9959048 -0.07126247 0.04791516 0.9951103 -0.08636945 0.04153591 0.9942381 -0.09881955 0.03647071 0.9934076 -0.1086797 0.03207528 0.9925948 -0.1171618 0.01263499 0.9987788 -0.04776287 -0.04348921 0.9887475 -0.1431331 -0.06393772 0.986289 -0.1521382 0.04828089 0.9951297 -0.08594119 -0.1514049 0.9718484 -0.1805201 -0.05649125 0.9981037 -0.02444595 -0.01391661 0.9968725 0.07779288 0.04074341 0.9988698 -0.02447652 0.03329581 0.9992414 -0.02020329 0.04553413 0.9985775 -0.02774161 0.04577875 0.9985873 -0.0269789 0.04626697 0.9985859 -0.02618539 0.0611 0.9977132 -0.02890193 0.06210613 0.9976965 -0.02728396 0.06311231 0.9976819 -0.02545243 0.06369268 0.9976893 -0.02365201 0.06415104 0.9976989 -0.02194321 0.06491345 0.9976896 -0.02005082 0.06583034 0.9976486 -0.01907461 0.06573885 0.9976505 -0.0192883 0.06460845 0.9976924 -0.02087485 0.06302082 0.9977135 -0.02441483 0.06430399 0.9976734 -0.02264523 0.06198334 0.9977159 -0.02685642 0.06195265 0.9977128 -0.0270394 0.06332737 0.9977038 -0.02401858 0.06521898 0.9976646 -0.02029508 0.06762903 0.9975897 -0.01553392 0.07040625 0.9974682 -0.01001006 0.07290953 0.9973257 -0.005066096 0.07495528 0.9971864 -0.001037597 0.0769692 0.9970291 0.002960324 0.07913541 0.9968377 0.007232964 0.0814256 0.9966095 0.01181095 0.08386743 0.9963377 0.01666361 0.08642995 0.9960197 0.02179056 0.08911544 0.9956518 0.02713137 0.09192335 0.9952266 0.03277742 0.09488373 0.9947383 0.0386371 0.09775257 0.9942196 0.04440522 0.1002255 0.9937402 0.04934972 0.1022082 0.9933332 0.05331671 0.1040388 0.9929625 0.05658197 0.1039462 0.9929826 0.05639827 0.1022085 0.9933365 0.05325585 0.1001927 0.9937481 0.04925704 0.0976929 0.9942336 0.04422271 0.094608 0.9947881 0.03802627 0.09094721 0.9953842 0.03064125 0.08664393 0.9959937 0.02212637 0.08176106 0.9965758 0.01232975 0.07620632 0.9970912 0.001312315 0.07001084 0.9974867 -0.01089531 0.06317472 0.9977031 -0.02444583 0.05566716 0.9976753 -0.03930878 0.04745715 0.9973328 -0.05545312 0.03885048 0.9966238 -0.07232969 0.03085434 0.9956411 -0.08801579 0.02414041 0.9945793 -0.1011395 0.01861679 0.9935572 -0.1117923 0.009796679 0.9920304 -0.1256175 0.02655166 0.9995029 -0.01699912 0.02096629 0.9996684 -0.01495409 0.03302186 0.9992328 -0.02105832 0.04742687 0.9985895 -0.02386599 0.04815924 0.998587 -0.02246206 0.04889154 0.9985841 -0.02096658 0.04953277 0.9985904 -0.01907449 0.05078405 0.9985603 -0.0172739 0.05194377 0.9985297 -0.01550376 0.0527364 0.9985133 -0.01379448 0.05249273 0.9985227 -0.01403874 0.05175971 0.9985421 -0.01532036 0.05084508 0.9985603 -0.01709079 0.04983711 0.9985741 -0.01913523 0.04858642 0.998586 -0.021577 0.0486167 0.9985812 -0.02172946 0.04992866 0.9985736 -0.01892161 0.05179023 0.9985424 -0.01519829 0.05413997 0.9984775 -0.01055943 0.05691778 0.9983661 -0.005066096 0.05938929 0.9982349 -1.52593e-4 0.06140494 0.9981058 0.003784358 0.06341755 0.9979571 0.007751703 0.06558442 0.9977747 0.01202428 0.06784468 0.9975584 0.01657205 0.07028514 0.9972981 0.02136325 0.07281827 0.9969942 0.02645993 0.07550477 0.9966391 0.03177058 0.0783115 0.9962289 0.03735512 0.08411043 0.9952564 0.04889148 0.08655154 0.9947934 0.05380475 0.08853566 0.9944015 0.05768096 0.08124279 0.9957584 0.04318499 0.09003049 0.9940894 0.06067138 0.08975553 0.9941475 0.06012189 0.0880782 0.9944965 0.05673503 0.08591109 0.9949206 0.05246222 0.08328634 0.9954081 0.04718238 0.08005148 0.995959 0.04071241 0.0762065 0.9965442 0.03305226 0.07175105 0.9971297 0.02417135 0.0666542 0.997677 0.01406937 0.06091684 0.9981393 0.002685666 0.05453759 0.9984623 -0.009949207 0.04745727 0.9985874 -0.02389651 0.01529014 0.9927918 -0.1188725 0.03970575 0.9984428 -0.03918689 0.03125178 0.9979516 -0.0558198 0.02240115 0.9970668 -0.07318538 0.01413023 0.9958938 -0.08942043 0.007080316 0.9946371 -0.1031839 0.001342833 0.9934319 -0.1144166 -0.003112971 0.9923686 -0.1232678 -0.006988942 0.9913954 -0.130715 -0.04437398 0.9885886 -0.1439561 -0.06415122 0.9863175 -0.1518632 -0.03405922 0.9960197 -0.08237087 -0.007355034 0.9995284 -0.02981704 -0.008423209 0.9912553 -0.1316892 -0.07687771 0.9850661 -0.1540606 -0.05237013 0.9964678 -0.06564581 0.0070194 0.9995381 0.0295732 0.01699918 0.999781 -0.01220768 -0.06708025 0.997262 0.03112912 -0.06631678 0.9973158 0.03103733 -0.05835223 0.9979397 0.02667355 0.03384596 0.999235 -0.01959341 0.03430283 0.9992387 -0.0185858 0.03488272 0.9992395 -0.01742607 0.03555411 0.9992384 -0.01608324 5.1883e-4 0.9999992 0.001190245 0.01147508 0.9999205 -0.005249202 -1.83117e-4 1 6.10389e-5 0.03644007 0.9992339 -0.014283 0.03744679 0.9992223 -0.01236015 0.03820943 0.9992137 -0.01058995 0.03930813 0.9991833 -0.009369194 0.03979617 0.9991781 -0.007721185 0.03994965 0.9991692 -0.008057057 0.03885084 0.9991962 -0.009888172 0.03793466 0.9992112 -0.01174968 0.03686696 0.9992242 -0.01385563 0.03561598 0.9992317 -0.01635831 0.03558534 0.9992288 -0.01660239 0.03866785 0.9991996 -0.01025444 0.041018 0.9991427 -0.005615532 0.04376435 0.9990419 -2.13634e-4 0.04620593 0.9989213 0.004608333 0.04822021 0.9988002 0.008545339 0.05020308 0.9986608 0.01251262 0.05233997 0.9984889 0.01675486 0.0546292 0.9982808 0.0212413 0.05700963 0.998035 0.02600222 0.05957388 0.9977412 0.03103822 0.06222879 0.997401 0.03631794 0.06500619 0.997006 0.0418725 0.06793606 0.9965487 0.04770171 0.07080507 0.9960626 0.05334794 0.07321482 0.9956184 0.058169 0.07513713 0.9952468 0.061953 0.07623696 0.9950181 0.06424295 0.07657313 0.9949625 0.06470108 0.07428395 0.9954176 0.06021457 0.07199531 0.9958487 0.05569791 0.06921815 0.9963391 0.05017399 0.06583029 0.9968853 0.04342907 0.06183165 0.9974554 0.03549367 0.05722385 0.9980147 0.0263077 0.05197393 0.9985224 0.01586985 0.04605376 0.9989303 0.004150629 0.03946065 0.999182 -0.008850395 0.03219717 0.9992117 -0.02322465 0.02423208 0.9989489 -0.03891175 0.01553422 0.9983115 -0.05597209 0.006470084 0.9972525 -0.07379591 -0.002044737 0.9958899 -0.09054929 -0.009369373 0.9944361 -0.1049248 -0.01544266 0.9930322 -0.1168273 -0.0204479 0.9917555 -0.1265025 -0.0280472 0.9899231 -0.1388016 -0.1224713 0.989476 -0.07705962 -0.1678869 0.9717668 -0.1657811 -0.1417629 0.978149 -0.1520785 -0.1760643 0.9673011 -0.1825649 0.02105838 0.9996632 -0.01516813 0.00979644 0.9999126 -0.008880913 0.009765982 0.9999192 -0.008148491 -0.01196342 0.9999228 0.00338757 -8.54542e-4 0.9999977 -0.001983702 -0.01220756 0.9999218 0.002716183 0.02209556 0.9996729 -0.01287889 0.02255344 0.9996766 -0.01174974 0.02322483 0.9996749 -0.01052898 0.02404868 0.9996684 -0.009216606 0.02499526 0.999659 -0.007568776 0.0255751 0.9996575 -0.005554497 0.02639877 0.9996458 -0.00338757 0.02749758 0.9996199 -0.002044737 0.0276196 0.9996158 -0.002349913 0.02679526 0.9996361 -0.00314337 0.02630716 0.9996429 -0.004699885 0.02539193 0.9996563 -0.006531059 0.02432328 0.9996669 -0.008636713 0.02301108 0.9996718 -0.0112614 0.02291953 0.9996704 -0.01156657 0.02414023 0.999669 -0.00891143 0.02594113 0.9996491 -0.005371332 0.02826088 0.9996003 -8.24022e-4 0.03097712 0.9995098 0.004547357 0.03341799 0.9993979 0.009338736 0.03540205 0.9992855 0.01324522 0.03738546 0.9991537 0.01715153 0.03949207 0.9989915 0.02136355 0.04174995 0.9987945 0.025819 0.04416126 0.9985572 0.0305497 0.04666358 0.9982777 0.03555464 0.04931908 0.9979493 0.0408042 0.05209553 0.997567 0.04632747 0.05499583 0.9971282 0.05206596 0.05783343 0.9966586 0.05768084 0.0602442 0.9962269 0.06247204 0.06210666 0.9958739 0.06616574 0.06347864 0.9956076 0.0688194 0.06338739 0.9956741 0.06793469 0.06085526 0.9961163 0.06363254 0.05847525 0.9965514 0.05887198 0.0555759 0.9970397 0.05313432 0.05206543 0.9975757 0.0461753 0.04794555 0.9981282 0.03796577 0.04315334 0.9986618 0.02850437 0.03772145 0.9991305 0.017762 0.03161722 0.9994838 0.005706965 0.02487325 0.9996613 -0.007660329 0.01739597 0.9995984 -0.02237063 0.009247183 0.9992164 -0.03848421 -0.02340793 0.9908559 -0.1328791 3.96749e-4 0.998434 -0.05594158 -0.008850455 0.9972048 -0.07419139 -0.01764005 0.9956576 -0.09140491 -0.02520889 0.9940115 -0.106329 -0.03161817 0.9924023 -0.1189039 -0.03686743 0.9909346 -0.1291886 -0.04095607 0.9896904 -0.1372425 -0.07526046 0.99096 -0.1110595 -0.01336747 0.9999076 0.002472043 -0.001525938 0.9999945 -0.002960324 0.01007121 0.9999243 -0.007080376 0.01089519 0.9999198 -0.006469964 0.01208543 0.9999193 -0.003936886 0.01303142 0.9999119 -0.002563536 0.01382523 0.9999039 -0.001098692 0.0149542 0.999888 7.32452e-4 0.0157479 0.9998726 0.00262463 0.01556485 0.9998746 0.002929806 0.01507622 0.9998844 0.002014219 0.01425242 0.9998984 4.27268e-4 0.01330608 0.9999105 -0.001464843 0.01217699 0.9999192 -0.003662228 0.01083415 0.9999215 -0.006317377 0.0107426 0.9999198 -0.006714105 0.01193284 0.9999204 -0.004119992 0.01370316 0.999906 -6.10387e-4 0.01599192 0.9998647 0.003875911 0.01864731 0.9997842 0.009155809 0.0210886 0.9996808 0.01391667 0.02304154 0.9995762 0.01779234 0.02502518 0.9994514 0.02169865 0.02713173 0.9992976 0.02584993 0.02939003 0.9991095 0.0302751 0.03173965 0.9988842 0.03497463 0.03424239 0.9986149 0.03994947 0.03689712 0.9982979 0.04516768 0.03967422 0.9979292 0.05063039 0.04254305 0.9975033 0.05636799 0.04535096 0.9970501 0.06192266 0.04776239 0.9966324 0.06665372 0.04950118 0.996311 0.07010126 0.05096703 0.9960243 0.07306289 0.05020421 0.9962108 0.07101839 0.04782408 0.9966151 0.06686824 0.04544335 0.9970383 0.06204593 0.04245233 0.9975243 0.056064 0.03881961 0.9980494 0.04889076 0.03454756 0.9985847 0.04043775 0.02963358 0.9990893 0.03070175 0.02404868 0.999517 0.01968449 0.01779276 0.9998149 0.007324635 0.01083415 0.9999212 -0.006347894 0.003204464 0.9997654 -0.02142417 -0.005096554 0.9992696 -0.0378735 -0.01413041 0.998346 -0.05572813 -0.02359086 0.9969515 -0.07437384 -0.03256368 0.9952223 -0.09204506 -0.04040694 0.9933883 -0.1074568 -0.04709029 0.9915825 -0.1206098 -0.1182617 0.9781694 -0.1708767 -0.09595257 0.9820799 -0.1622099 -0.05267518 0.9899029 -0.1315964 -0.05719321 0.9884302 -0.1404805 -0.05060124 0.9920657 -0.1150889 -0.1405724 0.9737219 -0.1791794 -0.1265014 0.9766701 -0.1735312 -4.27272e-4 0.9999992 -0.001220762 0.001190245 0.9999956 0.002716183 0.002075254 0.9999881 0.004425227 0.003051817 0.9999746 0.006439387 0.003875911 0.9999608 0.007965505 0.004120051 0.9999591 0.008056998 0.003570735 0.999969 0.00701946 0.002716124 0.9999819 0.005371272 0.001709043 0.9999929 0.003387629 5.79869e-4 0.9999993 0.001129209 -6.40907e-4 0.9999985 -0.001648008 -0.001312315 0.9999969 -0.002136349 -3.05194e-5 0.9999999 5.4935e-4 0.001831114 0.9999905 0.003967463 0.006622493 0.9998821 0.01385545 0.009369373 0.9997795 0.01879984 0.01110905 0.9996942 0.02209603 0.004028499 0.9999563 0.008453726 0.01318395 0.9995735 0.02606278 0.01528984 0.9994274 0.03018301 0.0175178 0.9992485 0.03457784 0.01986771 0.9990321 0.03924709 0.02237057 0.9987726 0.04419183 0.02499526 0.9984688 0.04934966 0.02777189 0.9981105 0.05481135 0.03064113 0.9976986 0.06048876 0.03344839 0.9972581 0.06601184 0.0358293 0.9968422 0.07086509 0.03845417 0.9964222 0.0752604 0.03845435 0.9963033 0.07681709 0.03735482 0.9965873 0.07361102 0.03549391 0.9969124 0.07004171 0.03302162 0.9973325 0.06509715 0.02990841 0.9978121 0.05896228 0.02615445 0.9983266 0.05157649 0.02175974 0.9988434 0.04287862 0.01672446 0.9993187 0.03289961 0.01098674 0.9997062 0.02160733 0.004577815 0.9999493 0.008972525 -0.002471983 0.9999845 -0.005005061 -0.01025432 0.9997397 -0.02038663 -0.0187692 0.9991338 -0.03714168 -0.02795577 0.9980767 -0.0553317 -0.05990839 0.9874054 -0.1464292 -0.0375989 0.9965237 -0.07434326 -0.04675531 0.9946197 -0.09244257 -0.05478191 0.9926064 -0.1083126 -0.06170892 0.9906083 -0.122014 -0.07919722 0.9844875 -0.1565634 -0.06756931 0.9887276 -0.1336126 -0.07239151 0.9870521 -0.143135 -0.076146 0.9856559 -0.1506134 -0.1962359 0.9619527 -0.1901016 -0.1894955 0.9660335 -0.1757007 -0.02545297 0.9996257 0.01004081 -0.03292953 0.9993613 0.01388591 -0.02273666 0.999712 0.007690787 -0.04986774 0.9984852 0.02325534 -0.04046833 0.9990136 0.01828092 -0.05002069 0.9984915 0.02264511 -0.01095634 0.9999288 0.004730463 -0.009582996 0.9999288 0.007110953 -0.008819997 0.9999251 0.008484244 -0.008026421 0.999918 0.009979605 -0.008087575 0.9999054 0.01113951 -0.00689733 0.9999014 0.0122382 -0.006836175 0.9998874 0.01336723 -0.006836235 0.999895 0.01278746 -0.007385611 0.9999031 0.01181095 -0.008270561 0.9999151 0.01007115 -0.009308278 0.9999243 0.008056998 -0.01043748 0.9999284 0.005859613 -0.01248222 0.9999207 0.001709043 -0.01141411 0.9999266 0.004089534 -0.01171928 0.9999263 0.003173947 -0.01019334 0.9999275 0.006408989 -0.008178949 0.9999135 0.01031529 -0.005676507 0.9998676 0.01525956 -0.00262463 0.999771 0.02124118 0 0.9996563 0.02621597 0.001922667 0.9995407 0.0302447 0.003997921 0.9994015 0.03436422 0.006195366 0.9992306 0.03872889 0.008575916 0.9990224 0.04336804 0.01104795 0.9987727 0.04828143 0.01367235 0.9984793 0.05340766 0.01638883 0.9981328 0.0588411 0.0192576 0.9977347 0.06445658 0.02206534 0.9973065 0.06994998 0.02450656 0.9968973 0.07480162 0.0267347 0.9965102 0.07907503 0.02722334 0.9964311 0.07990002 0.02569705 0.9966928 0.07709121 0.02371352 0.9970364 0.07318538 0.02114963 0.9974531 0.06811845 0.01791441 0.9979279 0.06180012 0.01409977 0.9984306 0.05420178 0.009582996 0.9989266 0.0453211 0.00439471 0.9993732 0.03512728 -0.001403868 0.9997207 0.02359139 -0.007934808 0.9999116 0.0106815 -0.01516771 0.9998788 -0.003540098 -0.02310264 0.9995482 -0.01922672 -0.03174006 0.9988362 -0.03631794 -0.04107922 0.9976513 -0.05481296 -0.05087465 0.9959478 -0.07416045 -0.06018334 0.9938806 -0.09262502 -0.06839376 0.9916945 -0.1089234 -0.1439909 0.973663 -0.1767688 -0.07556456 0.9895117 -0.1231129 -0.08169853 0.9874322 -0.1352893 -0.08679604 0.9855505 -0.1454536 -0.0909776 0.983907 -0.153786 -0.1576011 0.9701744 -0.1841832 -0.08853602 0.9960228 0.01001024 -0.1691682 0.9796075 -0.1084044 -0.02046078 0.9997783 0.004958033 -0.0223096 0.9997213 0.007721364 -0.0217598 0.9997308 0.008056879 -0.03210586 0.9994019 0.01284843 -0.02154612 0.9997287 0.008850395 -0.02169907 0.9997157 0.009888172 -0.01977658 0.999725 0.01260447 -0.01953214 0.9997107 0.01403874 -0.01861661 0.9997121 0.01513743 -0.01773148 0.9997085 0.01638865 -0.01712089 0.9996984 0.01760923 -0.01712089 0.9996978 0.01763975 -0.01770102 0.9997115 0.01623606 -0.01867783 0.9997218 0.01440507 -0.01986807 0.9997239 0.01254343 -0.02090519 0.9997286 0.01028472 -0.02267569 0.9997152 0.007446646 -0.02261483 0.9997233 0.006470084 -0.02136307 0.9997313 0.009002983 -0.01977598 0.9997274 0.01242101 -0.0175178 0.9997062 0.0167548 -0.01474064 0.9996506 0.02194315 -0.01260429 0.9995574 0.02694821 -0.0107733 0.9994762 0.03051924 -0.008850455 0.9993713 0.0343337 -0.006775081 0.9992398 0.03839236 -0.004577875 0.9990764 0.04272687 -0.002227842 0.9988766 0.04733443 2.13632e-4 0.9986374 0.0521872 0.002807736 0.9983522 0.05731552 0.005554497 0.9980178 0.06268703 0.008392632 0.9976295 0.06830108 0.01116997 0.9972131 0.07376474 0.01361149 0.9968168 0.07855629 0.01577842 0.9964516 0.08267647 0.01617515 0.9963918 0.08331745 0.01452708 0.9966628 0.08032631 0.0124824 0.9970093 0.07626807 0.009827136 0.9974245 0.07104837 0.006531119 0.9978932 0.06454855 0.002563595 0.9983825 0.05679666 -0.002014219 0.9988582 0.04773175 -0.007293939 0.9992766 0.03732442 -0.01324516 0.999586 0.02554428 -0.01989865 0.9997249 0.01242136 -0.02725362 0.9996265 -0.002044737 -0.03531014 0.9992142 -0.01800602 -0.04406958 0.9984021 -0.0353716 -0.05356132 0.9970958 -0.05414122 -0.06347924 0.9952511 -0.0737946 -0.07291013 0.9930309 -0.09259498 -0.08130276 0.9906795 -0.1092888 -0.08865714 0.9883217 -0.123937 -0.09500437 0.9860559 -0.1366317 -0.100378 0.9839737 -0.1473778 -0.1110288 0.9847323 -0.1340708 -0.1050145 0.9820892 -0.1564384 -0.2136043 0.9571451 -0.1955674 -0.2073464 0.9610757 -0.1825955 -0.04965388 0.9985111 0.02258384 -0.05023407 0.9984869 0.02237033 -0.04135346 0.998984 0.01791471 -0.04113906 0.9989961 0.0177313 -0.03204464 0.9993963 0.01342821 -0.03134304 0.9994072 0.01425236 -0.03067177 0.9994127 0.01529008 -0.02948129 0.9994054 0.01788407 -0.02865713 0.9994003 0.01944047 -0.0278024 0.9993911 0.0210883 -0.02725362 0.9993817 0.02221792 -0.02713149 0.9993808 0.02240103 -0.02786397 0.9993808 0.02148544 -0.02871793 0.999392 0.01977604 -0.02969479 0.9994007 0.01779246 -0.03057992 0.9994035 0.01605296 -0.03143453 0.999406 0.01413029 -0.03241121 0.9994081 0.01153618 -0.03286874 0.9993997 0.01095622 -0.03177028 0.9994062 0.01333677 -0.03009176 0.9994084 0.01666337 -0.02789479 0.999391 0.02096688 -0.02530008 0.9993385 0.02612406 -0.02295053 0.9992651 0.03070247 -0.0210579 0.9991844 0.03445565 -0.01913511 0.9990854 0.03823971 -0.01706033 0.9989606 0.04226934 -0.01489335 0.9988039 0.04657238 -0.01257377 0.9986103 0.05118024 -0.01010185 0.9983795 0.05600297 -0.007507741 0.9981035 0.06109964 -0.004791438 0.9977791 0.06643921 -0.001953184 0.9974009 0.07202547 7.93496e-4 0.9969978 0.07742691 0.003204405 0.9966143 0.08215594 0.005218684 0.9962576 0.08627676 0.005493402 0.9962296 0.08658218 0.003875851 0.9965028 0.08346915 0.001739561 0.9968502 0.07928901 -9.76603e-4 0.997264 0.07391661 -0.004333674 0.9977259 0.06726378 -0.008392572 0.9982016 0.05935859 -0.01306194 0.9986598 0.05008095 -0.01846414 0.9990494 0.03949195 -0.02453738 0.9993199 0.02752828 -0.03128206 0.9994099 0.01419138 -0.03872847 0.9992497 -5.18821e-4 -0.04690742 0.9987598 -0.01669377 -0.05581927 0.9978504 -0.03433388 -0.06543362 0.9964283 -0.0533784 -0.07544219 0.994452 -0.0733059 -0.08499586 0.9920866 -0.09241199 -0.1569915 0.9740859 -0.1628206 -0.09354102 0.9895821 -0.1094415 -0.1010501 0.9870621 -0.1244891 -0.1076111 0.9846148 -0.1376727 -0.1132549 0.9823359 -0.1489617 -0.1513454 0.9734758 -0.1715798 -0.1621457 0.9714706 -0.1730714 -0.1665123 0.9691346 -0.1818023 -0.1744492 0.966368 -0.1889459 -0.09140527 0.9912976 -0.09473192 -0.05923712 0.9978761 0.02710074 -0.04022383 0.999004 0.0193184 -0.038881 0.9990049 0.02185148 -0.03827065 0.9990046 0.02291965 -0.03790485 0.9989854 0.02432376 -0.03732454 0.9989736 0.02566635 -0.0366531 0.9989737 0.0266124 -0.03668355 0.9989709 0.02667337 -0.03729414 0.9989778 0.02554434 -0.03821009 0.9989869 0.0237745 -0.0391553 0.9989942 0.02185124 -0.04004043 0.9989969 0.0200507 -0.04144495 0.998983 0.01776212 -0.0426045 0.9989783 0.01507633 -0.04254364 0.9989823 0.01498484 -0.04150623 0.9989885 0.01730442 -0.0398572 0.9989943 0.02053898 -0.03766053 0.9989818 0.0248425 -0.0350964 0.9989354 0.02993875 -0.0327472 0.9988674 0.03451734 -0.03085458 0.9987921 0.03824013 -0.02896231 0.9986981 0.04199385 -0.02691763 0.9985778 0.04602247 -0.02472037 0.9984285 0.05029523 -0.02243131 0.9982414 0.05487287 -0.01995915 0.998019 0.05966383 -0.01739573 0.9977532 0.06469994 -0.01467984 0.9974361 0.07004207 -0.01184147 0.9970682 0.07559651 -0.009094774 0.9966753 0.0809682 -0.006714224 0.9963064 0.08560693 -0.004822015 0.9960014 0.08920824 -0.004425287 0.9959374 0.08994042 -0.006286859 0.9962302 0.0865212 -0.008484363 0.9965807 0.08218872 -0.01126146 0.9969911 0.07669395 -0.01471 0.9974422 0.06994879 -0.01883012 0.9979071 0.06186181 -0.02362185 0.9983451 0.052432 -0.02908474 0.9987086 0.04165858 -0.03524923 0.9989428 0.02951169 -0.04211646 0.9989848 0.01599204 -0.04968488 0.9987645 0.001037597 -0.05795472 0.9982012 -0.01535081 -0.06695836 0.9972042 -0.03317397 -0.07663273 0.9956767 -0.05249238 -0.08676534 0.9935752 -0.07266563 -0.1259509 0.9805979 -0.1502133 -0.09644001 0.9910737 -0.09204524 -0.1051079 0.9884238 -0.1094111 -0.1127992 0.9857423 -0.1248543 -0.1195419 0.9831308 -0.138433 -0.1248221 0.9851791 -0.1176502 -0.1531746 0.9788648 -0.1355041 -0.2081116 0.9577895 -0.1983149 -0.2077162 0.9577041 -0.1991402 -0.1900415 0.9623238 -0.1944668 -0.2239183 0.9564061 -0.1874785 -0.2289843 0.9529264 -0.19874 -0.08053916 0.9959821 0.03915566 -0.07370316 0.996656 0.03527981 -0.08038711 0.9960194 0.03851503 -0.04910457 0.9985107 0.02377402 -0.04764002 0.9984878 0.02743649 -0.04702937 0.9984824 0.02865707 -0.04580843 0.9984784 0.03070175 -0.04583901 0.9984798 0.0306102 -0.04638862 0.9984858 0.02957278 -0.04721361 0.9985055 0.02752852 -0.04858589 0.998483 0.02591043 -0.04901301 0.9985115 0.02392667 -0.05035668 0.9984975 0.02160757 -0.05175948 0.9984763 0.01913511 -0.05175977 0.9984821 0.01883006 -0.05072253 0.9984896 0.02111911 -0.04910534 0.9984967 0.02435427 -0.04693806 0.9984877 0.02862673 -0.04440456 0.9984474 0.0336315 -0.04208505 0.9983843 0.03817868 -0.04019379 0.9983142 0.04187232 -0.0383017 0.9982255 0.04559582 -0.03625607 0.9981113 0.04959273 -0.0340895 0.9979662 0.05386573 -0.03177028 0.9977887 0.05838286 -0.02935916 0.9975707 0.06317406 -0.02679598 0.9973111 0.06821072 -0.02407974 0.9970053 0.0734905 -0.02127146 0.9966467 0.07901269 -0.018525 0.9962611 0.08438491 -0.01617515 0.9959036 0.08896356 -0.0140081 0.9955855 0.09280776 -0.01403862 0.9955823 0.09283798 -0.01593089 0.9958639 0.08945101 -0.01818948 0.9962126 0.08502686 -0.0210579 0.9966197 0.07940971 -0.02456796 0.9970626 0.07254415 -0.02874892 0.9975162 0.06430369 -0.03363168 0.9979336 0.05475068 -0.03918612 0.9982705 0.04382497 -0.04541277 0.9984717 0.03149598 -0.05237108 0.9984692 0.0177927 -0.06003135 0.998193 0.00262463 -0.06839215 0.997561 -0.01394695 -0.07745772 0.9964826 -0.03198409 -0.08725333 0.9948533 -0.05151575 -0.1312339 0.981569 -0.1389248 -0.09747809 0.9926347 -0.07193356 -0.107244 0.9900081 -0.0915572 -0.1160026 0.9872282 -0.1091969 -0.1238172 0.9844035 -0.1249769 -0.1423699 0.9781561 -0.1514645 -0.1857385 0.9651014 -0.1846092 -0.1856201 0.9638087 -0.1913578 -0.1692891 0.9676062 -0.1872953 -0.0581994 0.9979355 0.02716171 -0.05771112 0.997936 0.02816885 -0.05734568 0.9979191 0.02948158 -0.0563693 0.9979236 0.03116029 -0.05572843 0.9979237 0.0322895 -0.04635804 0.9984844 0.02966427 -0.05526947 0.9979029 0.03369271 -0.05508732 0.9979202 0.03347963 -0.05441558 0.9979142 0.03473073 -0.05584895 0.9979269 0.03198343 -0.05719178 0.997927 0.02951145 -0.05847507 0.9979227 0.02704012 -0.05948221 0.9979225 0.02475118 -0.06048858 0.9979092 0.02276712 -0.06051933 0.9979136 0.02249252 -0.05948227 0.9979233 0.02472066 -0.05786359 0.9979339 0.02792465 -0.0557574 0.9979271 0.03213602 -0.05319529 0.9978932 0.03714209 -0.05087447 0.9978359 0.04165786 -0.04901397 0.9977679 0.04535168 -0.04712074 0.9976845 0.04904341 -0.045107 0.997573 0.05304193 -0.04297119 0.9974327 0.05728477 -0.04065102 0.9972623 0.06176996 -0.03824013 0.9970513 0.06653112 -0.03567624 0.9967998 0.07153564 -0.03299075 0.9964994 0.07681578 -0.03018355 0.9961495 0.08231049 -0.02746713 0.9957753 0.08762013 -0.02511674 0.995424 0.09219658 -0.02322471 0.995124 0.09585928 -0.02313321 0.995126 0.09585946 -0.02505636 0.9954198 0.09226 -0.02737534 0.9957671 0.08774149 -0.0303052 0.9961662 0.08206522 -0.03387635 0.9966068 0.07501631 -0.03814828 0.9970447 0.06668323 -0.04309248 0.9974451 0.05697852 -0.04870826 0.9977564 0.04593098 -0.05502653 0.9979246 0.03344929 -0.06207555 0.9978792 0.01959317 -0.06979751 0.9975522 0.004242122 -0.07825171 0.9968555 -0.0124824 -0.0873748 0.9957005 -0.03076273 -0.1346206 0.982996 -0.1248849 -0.09726458 0.9939793 -0.05044817 -0.1464292 0.9793789 -0.1391962 -0.107519 0.991659 -0.07107907 -0.1758185 0.970649 -0.1640993 -0.1174073 0.9889134 -0.09091663 -0.1812511 0.9677202 -0.1751168 -0.1262569 0.9860064 -0.1088611 -0.1773766 0.9728553 -0.1486276 -0.1366018 0.9902411 -0.02761942 -0.1961442 0.9729083 -0.1223803 -0.06595098 0.9973219 0.0316174 -0.06585979 0.9972974 0.03256368 -0.06534212 0.9973145 0.03308308 -0.06479114 0.9973196 0.03399777 -0.06445556 0.9973225 0.0345472 -0.06387585 0.9973244 0.0355544 -0.05429261 0.9979283 0.03451651 -0.06329566 0.9973193 0.03671389 -0.06262576 0.9973124 0.0380271 -0.06265562 0.9973024 0.03824037 -0.06323587 0.9973084 0.0371114 -0.0639975 0.9973176 0.03552365 -0.06515806 0.9973304 0.03296047 -0.06653052 0.9973176 0.03051859 -0.06750702 0.997316 0.02835172 -0.06860685 0.9973025 0.02609378 -0.06897389 0.9972836 0.02584993 -0.06799739 0.9972853 0.028261 -0.06628769 0.9973062 0.03140419 -0.06421202 0.9973005 0.03561568 -0.06176984 0.9972598 0.04071193 -0.05917656 0.9972127 0.04544293 -0.05749863 0.9971626 0.04858696 -0.05548346 0.9970853 0.05237054 -0.05346852 0.9969808 0.05630671 -0.05133312 0.9968463 0.06051939 -0.04904347 0.9966791 0.06500476 -0.04663294 0.9964749 0.06973582 -0.04409986 0.9962297 0.07471036 -0.04138422 0.9959385 0.0799607 -0.03860664 0.995594 0.08545345 -0.03589046 0.9952283 0.09073328 -0.03357094 0.9948902 0.09521937 -0.03173983 0.9945868 0.09894287 -0.03183138 0.9946172 0.09860718 -0.03366202 0.9949076 0.09500449 -0.03607344 0.9952551 0.09036672 -0.03903383 0.9956529 0.0845682 -0.04266566 0.9960824 0.07745742 -0.04696887 0.9965102 0.0690037 -0.05197334 0.9968938 0.05917578 -0.05768102 0.9971802 0.04800647 -0.06408894 0.9973162 0.03540152 -0.07117003 0.9972354 0.02136319 -0.07898205 0.9968587 0.005890071 -0.08749741 0.9961035 -0.01104778 -0.1360242 0.9847334 -0.1086179 -0.09674668 0.9948733 -0.02945125 -0.149025 0.9809467 -0.1246402 -0.1066352 0.9930743 -0.0493195 -0.1615371 0.9750216 -0.1524425 -0.1170104 0.9906513 -0.07013297 -0.1274181 0.9877573 -0.0900014 -0.07407057 0.9966416 0.03491419 -0.07440435 0.9966158 0.03494375 -0.07324647 0.9966712 0.0357992 -0.07291054 0.9966682 0.03656208 -0.07257413 0.9966586 0.03747731 -0.07196384 0.9966598 0.03860652 -0.07150512 0.9966472 0.03976577 -0.07062107 0.9966608 0.04098707 -0.0703473 0.9966433 0.04187268 -0.07025432 0.9966537 0.04178029 -0.07089579 0.9966613 0.04049879 -0.07193398 0.9966691 0.03842377 -0.07260531 0.9966982 0.0363484 -0.07397741 0.9966508 0.03485238 -0.0748021 0.9966596 0.03277742 -0.07590013 0.9966512 0.03042715 -0.0772739 0.9965953 0.02874881 -0.07608377 0.9966583 0.02972543 -0.07477182 0.9966629 0.03274697 -0.07281768 0.9966805 0.03640884 -0.07040834 0.9966734 0.04104864 -0.06769204 0.9966116 0.04672521 -0.06531035 0.9965327 0.05154633 -0.06332713 0.9964494 0.05548375 -0.06131231 0.9963483 0.05942016 -0.05917561 0.9962195 0.06360077 -0.05688792 0.9960582 0.06805801 -0.05447614 0.9958609 0.07275694 -0.0519737 0.9956187 0.07773166 -0.04928755 0.9953343 0.08294957 -0.04651027 0.9949976 0.08841234 -0.04379469 0.9946432 0.09363216 -0.04150581 0.9943089 0.09811854 -0.03973561 0.9940318 0.1015974 -0.03979653 0.9940293 0.1015972 -0.04175037 0.9943495 0.09760069 -0.04419112 0.9946972 0.0928685 -0.0472123 0.9950909 0.08697813 -0.0509063 0.995512 0.07977765 -0.05526995 0.9959274 0.07123136 -0.06033605 0.9962934 0.06131267 -0.06607323 0.9965618 0.04998981 -0.07251399 0.9966711 0.0372641 -0.07968634 0.9965522 0.02310323 -0.0875582 0.9961312 0.007507562 -0.1543964 0.9841514 -0.08722376 -0.1695015 0.9799288 -0.1049237 -0.09616565 0.9953195 -0.009552478 -0.145363 0.9835122 -0.1075802 -0.1054424 0.9940273 -0.02813827 -0.1158496 0.9921075 -0.04797565 -0.1263173 0.9895721 -0.0692166 -0.1914485 0.9676194 -0.1644998 -0.1396874 0.9862049 -0.08881151 -0.1981278 0.9609749 -0.1930617 -0.08124071 0.9959467 0.0386061 -0.1018729 0.9935206 0.05038708 -0.09750849 0.9940376 0.04879999 -0.09778428 0.9940491 0.04800707 -0.0790742 0.9960119 0.04132246 -0.07846391 0.9960128 0.04245167 -0.07788544 0.9959999 0.04379528 -0.07727432 0.9959905 0.04507666 -0.07739609 0.9959865 0.04495441 -0.07803744 0.9959921 0.04370337 -0.07864743 0.9959878 0.04269605 -0.07950145 0.9960118 0.04049843 -0.08060157 0.9959985 0.03860694 -0.08136421 0.9959945 0.03708082 -0.08224773 0.9960066 0.03473019 -0.08389633 0.9959523 0.03225839 -0.08368241 0.9959492 0.0328992 -0.08197402 0.9959881 0.03589034 -0.08014374 0.9959983 0.03955304 -0.07779294 0.9959883 0.04422205 -0.07501482 0.9959455 0.04965382 -0.07257479 0.9958741 0.05447685 -0.07055944 0.9957976 0.05838239 -0.06857722 0.9956974 0.0623207 -0.06644064 0.9955719 0.06650167 -0.06418204 0.9954168 0.07089626 -0.06177037 0.9952235 0.07559543 -0.05926829 0.9949878 0.08054023 -0.05661273 0.9947063 0.08575838 -0.05380558 0.9943816 0.09116131 -0.05111896 0.9940283 0.0964089 -0.04886108 0.9937027 0.1008352 -0.04699981 0.9934363 0.1042847 -0.04718244 0.9934567 0.104009 -0.04922735 0.9937648 0.1000418 -0.05173033 0.9941083 0.09525102 -0.05478203 0.9945 0.08926874 -0.05853497 0.9949116 0.08200389 -0.0629304 0.9953197 0.07333737 -0.06802612 0.9956719 0.06332623 -0.07382488 0.9959192 0.05191242 -0.08035743 0.9959991 0.03909528 -0.08792597 0.9958127 0.02502578 -0.09567654 0.9953721 0.008972525 -0.1045274 0.9944906 -0.00790435 -0.1564119 0.9819617 -0.106238 -0.113898 0.9931286 -0.02688747 -0.1648628 0.978495 -0.1239675 -0.12708 0.9908214 -0.04608327 -0.1381302 0.9880919 -0.06778329 -0.212534 0.957502 -0.1949856 -0.2278667 0.9522606 -0.203167 -0.2416512 0.9495752 -0.1997788 -0.2369821 0.9529029 -0.1892499 -0.08749806 0.995287 0.04181104 -0.0871616 0.9953087 0.04199379 -0.08533108 0.9953463 0.04477131 -0.08523911 0.9953111 0.04571717 -0.08392685 0.9953119 0.04806721 -0.08386737 0.9953302 0.04779338 -0.08453863 0.9953284 0.0466336 -0.08581876 0.9953085 0.04467946 -0.08676522 0.9953434 0.04199397 -0.0882312 0.9953253 0.03927826 -0.09006059 0.9952751 0.03628665 -0.09027552 0.9953196 0.03448659 -0.08981812 0.9952936 0.03637892 -0.08868712 0.995304 0.03878915 -0.08691769 0.9953119 0.04242122 -0.08459997 0.9953016 0.04709154 -0.08194285 0.9952473 0.05261433 -0.07913583 0.9951956 0.05765044 -0.07736563 0.9951327 0.06103795 -0.07525992 0.9950429 0.06500554 -0.07312387 0.9949244 0.06912589 -0.07086521 0.9947683 0.07358139 -0.06848424 0.9945787 0.07825028 -0.0659523 0.994351 0.08316522 -0.06329709 0.994076 0.08835345 -0.06051898 0.9937573 0.09372359 -0.0578649 0.9934091 0.09894412 -0.05557513 0.9930894 0.1033679 -0.05374348 0.9928352 0.106724 -0.05377382 0.992863 0.106449 -0.05649089 0.9931232 0.1025443 -0.05908566 0.9934701 0.09760129 -0.06216758 0.9938573 0.09155756 -0.06595259 0.9942637 0.08420324 -0.07013183 0.9946948 0.07525902 -0.07541173 0.9950014 0.06546258 -0.08142453 0.9952229 0.0538659 -0.08789551 0.9952949 0.04077374 -0.09784394 0.9948286 0.02725344 -0.102758 0.9946503 0.01055961 -0.1146291 0.9933916 -0.00576806 -0.124518 0.9919017 -0.02502566 -0.1923635 0.9694778 -0.1520169 -0.1912326 0.9718807 -0.1373969 -0.1970605 0.9644581 -0.176033 -0.202034 0.9614927 -0.1863169 -0.2146438 0.9586487 -0.186871 -0.223916 0.9547485 -0.1957472 -0.09354221 0.9945999 0.04495519 -0.09262496 0.9947037 0.04455763 -0.1112278 0.9923163 0.05419272 -0.09244149 0.9947001 0.04501521 -0.09131294 0.9946762 0.04776227 -0.09186267 0.9946806 0.04660272 -0.08459877 0.9953176 0.04675513 -0.0906403 0.9946935 0.0486772 -0.08969438 0.9946956 0.05035579 -0.09051924 0.9946743 0.04928809 -0.08990955 0.9946513 0.05084496 -0.09158766 0.9946771 0.04721295 -0.09250354 0.9946805 0.04532092 -0.09366363 0.9946537 0.04348993 -0.09451711 0.9946729 0.04113948 -0.09585994 0.9946424 0.03869795 -0.09613573 0.9946544 0.03769129 -0.0952509 0.9946563 0.0398277 -0.09363299 0.994683 0.04287952 -0.09152555 0.9946959 0.0469377 -0.08887201 0.994683 0.05203527 -0.08594292 0.9946004 0.05817013 -0.08368349 0.9944665 0.06351035 -0.08166837 0.9943645 0.06759917 -0.07931894 0.9942792 0.07153654 -0.0769391 0.9941355 0.075993 -0.07483267 0.9939136 0.08084493 -0.07242065 0.9936858 0.08569622 -0.06976598 0.9934175 0.09085446 -0.06677663 0.9931346 0.09604477 -0.06424283 0.9927585 0.1015068 -0.06186211 0.9924798 0.1056264 -0.05990833 0.9922268 0.1090741 -0.06009274 0.9923089 0.1082219 -0.06518959 0.9922797 0.1055058 -0.06784349 0.9926276 0.1004377 -0.07095748 0.9930086 0.09433531 -0.07471084 0.9934288 0.08670485 -0.0762977 0.9940981 0.07712173 -0.08423185 0.9941194 0.06805688 -0.09045827 0.9943089 0.05627697 -0.09711164 0.9943414 0.04306238 -0.1398064 0.9892046 -0.04391646 -0.1508532 0.98636 -0.06585901 -0.112278 0.9935951 0.01275676 -0.1783524 0.9762997 -0.1225944 -0.220655 0.9544933 -0.2006343 -0.2006921 0.9666245 -0.1592475 -0.166573 0.9850025 -0.04498505 -0.2100015 0.9694987 -0.1263794 -0.09854477 0.9939932 0.04760909 -0.09814929 0.9940366 0.04751819 -0.09714269 0.9940418 0.04944109 -0.09671556 0.9940436 0.05023473 -0.09064239 0.9946556 0.04944127 -0.09613651 0.9940515 0.05118119 -0.09576773 0.9940251 0.05237007 -0.09509825 0.9940456 0.05319517 -0.09488427 0.9940726 0.05307292 -0.09549355 0.9940914 0.05160737 -0.09640872 0.9941177 0.04934877 -0.09796643 0.9940693 0.04721307 -0.09878897 0.9940549 0.04577803 -0.09970504 0.9940596 0.04364192 -0.100928 0.9940504 0.04095715 -0.1017807 0.994002 0.04001033 -0.100865 0.9940006 0.04229915 -0.09924721 0.9940289 0.04535096 -0.09720313 0.9940358 0.0494408 -0.09439575 0.9940398 0.05453771 -0.09155583 0.9939612 0.06048786 -0.0908541 0.9936271 0.0667138 -0.08905577 0.9935308 0.07046943 -0.08462965 0.9936739 0.07382583 -0.0825845 0.9935169 0.07812875 -0.08224964 0.993069 0.08395868 -0.07989937 0.9928524 0.08865839 -0.07721346 0.9926053 0.09366327 -0.0720247 0.992568 0.0980879 -0.07159787 0.9919638 0.1043144 -0.06723326 0.9918974 0.107793 -0.06561553 0.9916489 0.1110275 -0.06589078 0.9916884 0.1105097 -0.08447623 0.9932367 0.07965421 -0.1356867 0.9904888 -0.02282804 -0.1092598 0.9935623 0.02993959 -0.1877866 0.9768997 -0.1019963 -0.1817696 0.9798955 -0.08224797 -0.1258293 0.9920462 -0.003357052 -0.2029218 0.9674571 -0.1511613 -0.2038707 0.9651201 -0.1642562 -0.2095715 0.961795 -0.1761536 -0.2242823 0.9564883 -0.1866222 -0.2321276 0.9528038 -0.1956574 -0.2205017 0.961174 -0.1659027 -0.1027579 0.9934587 0.04980719 -0.1021777 0.993517 0.04983758 -0.1018711 0.9934724 0.05133229 -0.1014463 0.9934665 0.05227965 -0.1009561 0.9934776 0.05301105 -0.1004981 0.9934764 0.05389606 -0.1001015 0.9934461 0.05517786 -0.1003755 0.9934405 0.05478078 -0.09952217 0.9934822 0.05557489 -0.1013549 0.9934369 0.05301219 -0.1025736 0.993447 0.050417 -0.1034589 0.9934805 0.04788404 -0.1045285 0.9934635 0.04587042 -0.1065728 0.9934281 0.04175013 -0.1053508 0.9934473 0.04431325 -0.1060854 0.9934373 0.04275768 -0.1048318 0.9934456 0.04556441 -0.1028488 0.9934827 0.04913544 -0.100316 0.9935163 0.05349981 -0.09824025 0.9934809 0.05783325 -0.09735536 0.9931165 0.06512737 -0.09891271 0.9931865 0.06161826 -0.09131234 0.9928693 0.07663279 -0.08920723 0.9927242 0.08087551 -0.07883 0.9917691 0.1008951 -0.07388699 0.9911418 0.1103574 -0.07016313 0.9911342 0.1128286 -0.07028561 0.9912016 0.112158 -0.07440537 0.9912886 0.1086782 -0.07700061 0.991639 0.1035526 -0.08017301 0.9920153 0.09735512 -0.08426415 0.9924009 0.08966612 -0.09378594 0.9930694 0.07083541 -0.09982913 0.993256 0.05896359 -0.1066347 0.9932537 0.04556542 -0.1501826 0.9877687 -0.0419327 -0.1611083 0.9848695 -0.06384515 -0.1220145 0.9924134 0.01510685 -0.1887633 0.9745194 -0.1211625 -0.2106433 0.9659624 -0.1501543 -0.2131475 0.963223 -0.1636145 -0.2493141 0.9477843 -0.1988653 -0.1047269 0.9931995 0.0508632 -0.1046863 0.9932051 0.05083841 -0.1046774 0.9931703 0.05153101 -0.1043052 0.9932224 0.05128306 -0.1028454 0.9933104 0.05251115 -0.1047729 0.993098 0.05271852 -0.1042106 0.9931079 0.05363762 -0.1025821 0.9932401 0.05432575 -0.1013287 0.9933286 0.05505359 -0.1016595 0.993197 0.05679178 -0.101957 0.9931939 0.05630797 -0.1026082 0.9932075 0.05486994 -0.1018857 0.9932042 0.05625605 -0.1036792 0.9932168 0.05263996 -0.1026165 0.9932062 0.05487573 -0.1051156 0.9932087 0.04987293 -0.103738 0.9932085 0.05268108 -0.1061447 0.9931983 0.04786056 -0.1071767 0.9931827 0.04584068 -0.1051235 0.9932075 0.04987877 -0.109559 0.9929854 0.0444622 -0.1061514 0.9931972 0.04786747 -0.1068463 0.9932335 0.04551118 -0.1083168 0.9932224 0.04215228 -0.1075459 0.9933148 0.04194802 -0.1068748 0.9932737 0.04455596 -0.1048024 0.9933527 0.04761242 -0.1104773 0.9929228 0.04358053 -0.1094708 0.9929283 0.04593074 -0.1023474 0.9934148 0.05149793 -0.1080075 0.9929426 0.04898333 -0.1010053 0.993279 0.05652201 -0.1009076 0.9931131 0.05953288 -0.1055664 0.993008 0.05282896 -0.1039478 0.9929668 0.05667376 -0.09437644 0.9930428 0.07042133 -0.1041324 0.9927372 0.06024539 -0.09699004 0.9925458 0.07379543 -0.09872967 0.9926377 0.07016366 -0.09012264 0.9921119 0.08713173 -0.08765178 0.991912 0.09180241 -0.08517831 0.9916518 0.09680604 -0.07974559 0.9910065 0.1074567 -0.0730049 0.9909234 0.1128777 -0.0717498 0.9907679 0.1150266 -0.09268623 0.9922952 0.08221822 -0.13468 0.9908883 -0.001281738 -0.1444153 0.9892995 -0.02075278 -0.1179578 0.9924935 0.03228956 -0.1578138 0.9866493 -0.04022401 -0.1963881 0.9731819 -0.1197861 -0.2002946 0.9702218 -0.1362052 -0.218824 0.9598043 -0.1757611 -0.2359268 0.9501772 -0.2037199 -0.2402437 0.9509343 -0.1949539 -0.2333788 0.9544819 -0.1857386 -0.2308791 0.9519301 -0.2013058 -0.108472 0.9926996 0.05273884 -0.1076625 0.9928059 0.05239522 -0.10789 0.9927417 0.05313915 -0.1083724 0.992673 0.05343931 -0.1074745 0.9927352 0.05409353 -0.1069961 0.9927353 0.05503249 -0.1074257 0.9927422 0.05406165 -0.1115717 0.9920766 0.05775731 -0.1029597 0.9932357 0.05368775 -0.1035539 0.9931445 0.05422884 -0.1069639 0.9927401 0.05500912 -0.1035557 0.9930887 0.05523699 -0.1065964 0.9927392 0.05573362 -0.1052538 0.9928637 0.05606591 -0.1030986 0.9930649 0.05650538 -0.1015032 0.9932183 0.05669748 -0.1060029 0.9926428 0.05851334 -0.1057553 0.992697 0.05803912 -0.1044915 0.9928325 0.05801159 -0.1073952 0.9925786 0.05704355 -0.1045675 0.9928901 0.05687701 -0.1090743 0.992506 0.05508816 -0.1052656 0.9929313 0.05483323 -0.1097911 0.9925949 0.05197387 -0.1071613 0.9928219 0.05311518 -0.1104761 0.99263 0.04980695 -0.1095127 0.9926458 0.0515902 -0.1116213 0.9926079 0.0476486 -0.1104895 0.9926277 0.04982519 -0.1111763 0.9926803 0.04717648 -0.113736 0.9925032 0.04473859 -0.1104184 0.9928742 0.04481858 -0.1105208 0.9928513 0.04507374 -0.1130247 0.9926058 0.04426217 -0.1097205 0.9928242 0.04755741 -0.1072821 0.9929181 0.05103152 -0.1121864 0.9925717 0.04707372 -0.10871 0.9925205 0.05554521 -0.1113362 0.9925135 0.05021291 -0.1087997 0.9923208 0.05884033 -0.1055665 0.9923072 0.06467056 -0.1103884 0.9925191 0.05215752 -0.1040089 0.9922661 0.0677523 -0.09799784 0.9920035 0.07953363 -0.09592145 0.9918702 0.08362227 -0.08566659 0.9909186 0.1036422 -0.076918 0.9905849 0.1132484 -0.07184845 0.990754 0.1150841 -0.08075261 0.9903034 0.1130415 -0.07773303 0.9902345 0.1157298 -0.07452815 0.9906263 0.1144779 -0.07492387 0.990674 0.1138049 -0.07587182 0.9902677 0.1166763 -0.07935047 0.9901419 0.1154245 -0.08157753 0.9904361 0.1112726 -0.08426392 0.9907803 0.1060853 -0.08749902 0.9911469 0.09985935 -0.09152615 0.9915283 0.09216701 -0.1295551 0.9914245 0.01712137 -0.1012314 0.992172 0.07312345 -0.1072731 0.9923449 0.06118988 -0.1141095 0.9923166 0.04782283 -0.1686771 0.983711 -0.06213617 -0.202128 0.9721555 -0.1185667 -0.2069509 0.9689858 -0.1350476 -0.2164444 0.9648444 -0.1490879 -0.220169 0.9617974 -0.1627004 -0.2178471 0.9678294 -0.1258923 -0.1830257 0.9819972 -0.04672539 -0.1114865 0.9922783 0.05435639 -0.1117692 0.9922167 0.05489742 -0.1103683 0.9923998 0.05441921 -0.1095561 0.9924498 0.0551458 -0.111985 0.9921503 0.05565369 -0.1092689 0.9924243 0.05616456 -0.1111139 0.9922108 0.05631738 -0.1066872 0.9927255 0.0558027 -0.1087496 0.9924439 0.05682331 -0.1069328 0.992608 0.05739992 -0.1046404 0.9928614 0.05724191 -0.1084684 0.992398 0.05814409 -0.1095209 0.9922272 0.05908006 -0.104919 0.9927697 0.05831331 -0.1087104 0.9922564 0.06007844 -0.109356 0.9921736 0.06027334 -0.1090101 0.9922934 0.05891305 -0.109844 0.9923182 0.05691206 -0.1089158 0.9923076 0.05884963 -0.1111199 0.9923188 0.05436807 -0.1099005 0.9923097 0.05695235 -0.1155775 0.9921786 0.04715579 -0.1144655 0.9921973 0.04941952 -0.1153352 0.9922934 0.04529714 -0.1149114 0.9922945 0.0463379 -0.1151021 0.9923222 0.04525864 -0.1143193 0.9922826 0.04802531 -0.1129084 0.9923005 0.05090624 -0.1166798 0.9920821 0.0464639 -0.1110484 0.9923049 0.05476665 -0.1144604 0.9922568 0.04822063 -0.1103579 0.9922549 0.05702072 -0.1132678 0.9922354 0.05137425 -0.1132861 0.992155 0.05286514 -0.1100531 0.9919431 0.06274795 -0.1112319 0.992255 0.05529475 -0.1048948 0.9918159 0.07278847 -0.1030918 0.991732 0.07641851 -0.09625637 0.9913125 0.08963376 -0.09381568 0.9911075 0.094365 -0.09134209 0.9908465 0.09939897 -0.08591067 0.9902163 0.1099596 -0.07561606 0.9903061 0.1165164 -0.08105772 0.9898139 0.1170393 -0.1244242 0.9916403 0.03418076 -0.09903424 0.9915022 0.08435457 -0.1412419 0.9899751 4.27266e-4 -0.1935811 0.9759013 -0.1007122 -0.2256918 0.958313 -0.1752126 -0.2388455 0.9499495 -0.2013675 -0.113942 0.9919284 0.0556364 -0.1139561 0.9919263 0.05564576 -0.1137831 0.9919295 0.05594044 -0.1137872 0.9919289 0.05594331 -0.113528 0.99193 0.05644667 -0.1135594 0.9919253 0.05646753 -0.1127294 0.9919818 0.0571357 -0.113888 0.9918297 0.05747503 -0.1104362 0.9922364 0.05719202 -0.1137546 0.9918011 0.05822932 -0.1101896 0.9921908 0.0584436 -0.1117191 0.9919755 0.05919069 -0.1075904 0.9924274 0.0592643 -0.1125268 0.9917758 0.06097871 -0.1111745 0.9919117 0.06124913 -0.1116574 0.9919269 0.06011372 -0.1141098 0.9917223 0.05887174 -0.1123136 0.9918261 0.06055408 -0.1112126 0.9920631 0.05867534 -0.1138258 0.9919161 0.05609029 -0.1146529 0.991941 0.05392223 -0.111914 0.9921053 0.05659162 -0.1155695 0.9919328 0.05208885 -0.1136464 0.9919513 0.0558325 -0.1168604 0.9919096 0.04958945 -0.1146366 0.9919447 0.05389136 -0.1155748 0.9919316 0.05209761 -0.1188664 0.9917991 0.04696333 -0.1182951 0.9917875 0.0486204 -0.1183013 0.9918652 0.0469951 -0.1184958 0.9918599 0.04661208 -0.1113931 0.9919371 0.06043446 -0.1077961 0.9918817 0.06746059 -0.1065169 0.9918448 0.06998616 -0.111831 0.9919405 0.05956447 -0.1109371 0.9915672 0.06698954 -0.1033667 0.9912774 0.08175951 -0.1093791 0.991523 0.07013201 -0.1012926 0.9911351 0.08597201 -0.09106975 0.9902008 0.1058716 -0.0830211 0.9897997 0.1157758 -0.07888466 0.9899193 0.1176317 -0.08618646 0.9895881 0.1152713 -0.08359253 0.9894686 0.118171 -0.0835905 0.989811 0.1152689 -0.08198446 0.9894506 0.1194403 -0.08722436 0.9897436 0.1131353 -0.08981806 0.9900745 0.1080991 -0.09305298 0.9904389 0.1018425 -0.09707963 0.9908164 0.09411931 -0.1128916 0.9916086 0.06299221 -0.1197564 0.9915608 0.0496543 -0.1352282 0.9906361 0.01879948 -0.1068477 0.9914461 0.0749551 -0.1515563 0.9884423 0.003540158 -0.1597374 0.987021 -0.01654136 -0.1746284 0.9827654 -0.06064075 -0.1869896 0.9790171 -0.08099722 -0.1981922 0.9750912 -0.0995844 -0.2067077 0.9713401 -0.117347 -0.2211124 0.963922 -0.1482018 -0.2121714 0.9680172 -0.133889 -0.2269117 0.9604148 -0.1616002 -0.2310016 0.957242 -0.1741439 -0.2332547 0.9579527 -0.1670901 -0.1164266 0.9915676 0.05690908 -0.1162075 0.9915986 0.05681663 -0.1166544 0.9914962 0.05768185 -0.1154981 0.9916808 0.05682909 -0.1161825 0.9914953 0.05864077 -0.1145048 0.9916926 0.05860584 -0.1155641 0.9915916 0.05823397 -0.1161366 0.9914384 0.05968505 -0.1133356 0.9917861 0.05929303 -0.1124749 0.9918493 0.0598706 -0.1136819 0.9917361 0.05946379 -0.1113955 0.9919644 0.05998218 -0.1143935 0.9915343 0.06143271 -0.1110324 0.9919328 0.06116533 -0.113627 0.9915626 0.06239199 -0.1141287 0.9915671 0.06139481 -0.1153745 0.9914728 0.06058406 -0.1147343 0.9914692 0.0618475 -0.1156328 0.9915805 0.05828648 -0.1147669 0.9915806 0.05997174 -0.1170435 0.9915038 0.05675393 -0.1160327 0.9915143 0.05861735 -0.1203423 0.9915357 0.04873323 -0.1188774 0.9915644 0.05165499 -0.120629 0.9915156 0.04843151 -0.120847 0.9915102 0.04799658 -0.119484 0.9915513 0.05049383 -0.1179893 0.9915795 0.05337345 -0.1205261 0.991533 0.04833084 -0.1172854 0.9915818 0.05486071 -0.1162689 0.9915529 0.05748409 -0.119479 0.9915523 0.05048751 -0.1155683 0.9915534 0.05887055 -0.1180092 0.9915741 0.05342984 -0.1123627 0.9915688 0.06454533 -0.1173561 0.9915452 0.05537122 -0.1162698 0.9915527 0.05748742 -0.1066693 0.9914083 0.07570642 -0.1130189 0.9915773 0.06325596 -0.1077625 0.9910731 0.07849478 -0.1096228 0.9911525 0.0748316 -0.1010488 0.9906511 0.09164893 -0.09860807 0.990445 0.09641069 -0.09604406 0.9901973 0.1014155 -0.09064143 0.989579 0.1118827 -0.08155602 0.9895287 0.1190863 -0.08206164 0.9900034 0.1147139 -0.0857892 0.9893208 0.1178331 -0.08466953 0.9893269 0.1185889 -0.1039471 0.9908549 0.08603256 -0.1295836 0.990921 0.03582924 -0.1464908 0.9892101 0.001983702 -0.1697477 0.9847932 -0.03698921 -0.1803689 0.9818357 -0.05887168 -0.2358548 0.9562682 -0.1729846 -0.2409479 0.952866 -0.1843656 -0.1181047 0.9913186 0.0577827 -0.1194216 0.9911127 0.05860203 -0.1191983 0.9910916 0.05940842 -0.1171276 0.9914262 0.05792587 -0.1184604 0.9911344 0.06016594 -0.1165851 0.9914414 0.05875349 -0.1162191 0.9914171 0.05987918 -0.1169556 0.9913081 0.06024754 -0.114975 0.9915098 0.06073826 -0.1138361 0.9916537 0.06053352 -0.1169627 0.991207 0.06187397 -0.1129253 0.9917188 0.0611695 -0.1136717 0.9915558 0.06241762 -0.1169616 0.9911243 0.06318753 -0.1154147 0.9913048 0.06320124 -0.1166818 0.9911995 0.06252127 -0.1164353 0.991113 0.06432563 -0.1189218 0.9911162 0.05955183 -0.1177746 0.9911134 0.06183332 -0.1172859 0.9912608 0.06038308 -0.1193254 0.9912728 0.05603373 -0.1202344 0.9912645 0.05420762 -0.1183161 0.9912778 0.05804985 -0.1209468 0.9913069 0.05179429 -0.1193287 0.9912719 0.0560413 -0.1202644 0.9912578 0.05426484 -0.1226617 0.9912601 0.04855495 -0.1216215 0.9913111 0.0501042 -0.1227381 0.9912251 0.04907274 -0.123121 0.991185 0.04892367 -0.1163334 0.9912337 0.06262886 -0.1125278 0.9912131 0.06952911 -0.113591 0.9909157 0.07199388 -0.1169327 0.9912373 0.06144589 -0.1137803 0.9912393 0.06707382 -0.1075494 0.990682 0.08356142 -0.1125288 0.9912133 0.06952393 -0.105442 0.9905444 0.08777165 -0.0954014 0.9895989 0.1076699 -0.08777183 0.9891517 0.1177923 -0.08433771 0.9891742 0.12009 -0.09048861 0.9889962 0.11704 -0.08840101 0.989005 0.1185517 -0.08792573 0.9891875 0.1173768 -0.08600592 0.9888918 0.1212279 -0.08827686 0.9892311 0.1167441 -0.09149748 0.9891678 0.1147838 -0.09424376 0.989468 0.1098697 -0.1113635 0.9908277 0.07654148 -0.09744733 0.9898549 0.1033985 -0.1174667 0.990975 0.06457769 -0.1014752 0.9902149 0.09579867 -0.1242737 0.990924 0.05124151 -0.1921796 0.9781416 -0.07941102 -0.2027385 0.9742924 -0.09824103 -0.2111642 0.9705498 -0.1159434 -0.2171463 0.9671025 -0.1325157 -0.2467785 0.9480494 -0.2007555 -0.2447648 0.9510731 -0.1885482 -0.244664 0.9479002 -0.2040216 -0.2541025 0.9468571 -0.1972148 -0.119848 0.9910482 0.05882263 -0.1206488 0.9909307 0.05916452 -0.1213078 0.990797 0.06004911 -0.1187652 0.9911568 0.0591861 -0.1205785 0.9908459 0.06070697 -0.1194289 0.9909796 0.06079822 -0.1195871 0.9909138 0.06155508 -0.1190159 0.9910507 0.06044644 -0.1176713 0.99117 0.06112062 -0.1192125 0.9909792 0.06122606 -0.1190431 0.9909701 0.06170123 -0.1164994 0.9912859 0.06148439 -0.1159905 0.9913008 0.06220215 -0.1156665 0.991266 0.06334936 -0.1179194 0.9909761 0.06373029 -0.1177417 0.9909605 0.06429898 -0.1178287 0.9909462 0.0643596 -0.119233 0.9907663 0.06454163 -0.118772 0.9909901 0.0619027 -0.118088 0.9909867 0.06325209 -0.120714 0.9909784 0.05822288 -0.1196849 0.9909754 0.06036019 -0.1237444 0.9908365 0.05413484 -0.1239683 0.9909923 0.05065792 -0.1256383 0.9908229 0.04985231 -0.1234889 0.9908961 0.0536229 -0.1247689 0.9908444 0.05157542 -0.1235408 0.9909588 0.05233049 -0.1221477 0.9909754 0.05520689 -0.1244071 0.9909361 0.05068188 -0.1205847 0.9910746 0.05683869 -0.1202087 0.9909778 0.05926972 -0.1235671 0.9909529 0.05237925 -0.1194435 0.9909919 0.06056737 -0.1222079 0.9909587 0.05537301 -0.1167065 0.9909346 0.06654709 -0.1201636 0.9909906 0.05914694 -0.1134403 0.9905967 0.07648146 -0.1172928 0.9909421 0.06539285 -0.1115469 0.9905248 0.08011233 -0.1048331 0.9901011 0.0933274 -0.1024532 0.9898929 0.09805846 -0.09988844 0.9896372 0.103154 -0.09448796 0.9890416 0.1134405 -0.08759576 0.9891231 0.1181633 -0.08937913 0.9886359 0.120874 -0.107764 0.990324 0.08743804 -0.2328584 0.959267 -0.159949 -0.2254781 0.9631344 -0.1467377 -0.2468991 0.9495087 -0.1935823 -0.2478614 0.9474177 -0.2023969 -0.1216333 0.9907774 0.05971163 -0.1221047 0.990687 0.06024873 -0.1210865 0.9908309 0.05993497 -0.1226938 0.9905583 0.06115913 -0.1213098 0.9907305 0.06113064 -0.1210668 0.9907296 0.06162643 -0.1211298 0.9907614 0.06098788 -0.1210609 0.9907307 0.06162142 -0.1233801 0.9902881 0.06408482 -0.1208522 0.9907293 0.06204962 -0.1183415 0.9910023 0.06252747 -0.1206379 0.9906454 0.06378352 -0.1189743 0.990768 0.06499278 -0.1212678 0.9904925 0.06495195 -0.1201424 0.9907348 0.06332916 -0.1208174 0.9907355 0.06201863 -0.120812 0.9907369 0.0620079 -0.1215889 0.9907354 0.06049597 -0.1220795 0.9907257 0.05965989 -0.1230941 0.9906833 0.05826306 -0.1226286 0.990782 0.05756199 -0.1229036 0.9908886 0.05508595 -0.123402 0.9907726 0.05605006 -0.1271221 0.9904896 0.05263602 -0.1272456 0.9905576 0.0510317 -0.126598 0.9906918 0.05002796 -0.1261676 0.9907047 0.05085384 -0.1175422 0.9906719 0.06894189 -0.1163507 0.9906518 0.0712161 -0.1163562 0.9906463 0.0712819 -0.1149593 0.9906131 0.07396149 -0.110876 0.9901931 0.08499574 -0.1087103 0.9900516 0.08933049 -0.09949189 0.9889982 0.1094716 -0.09427458 0.988464 0.1185376 -0.09165054 0.9885937 0.1195102 -0.08757716 0.9887285 0.1214345 -0.09163856 0.988602 0.1194512 -0.09073048 0.9890567 0.1163398 -0.08989262 0.9883894 0.1224982 -0.08869057 0.9886611 0.1211753 -0.1004697 0.9894372 0.1044982 -0.09200352 0.9887111 0.1182619 -0.1058713 0.9895875 0.09750908 -0.09854727 0.9888606 0.1115486 -0.09479236 0.9886973 0.1161558 -0.11582 0.9901928 0.07812893 -0.1218618 0.9903373 0.06619542 -0.1748439 0.9839662 -0.03521901 -0.1636434 0.9864077 -0.01486277 -0.1852797 0.9810273 -0.05707013 -0.2516886 0.9470291 -0.1994709 -0.2511445 0.9465193 -0.2025534 -0.1234115 0.9905121 0.0604602 -0.1231293 0.990552 0.06038212 -0.1235603 0.9904721 0.0608108 -0.1233526 0.9904817 0.06107431 -0.1228586 0.99057 0.06063854 -0.1229858 0.9905061 0.06141883 -0.122489 0.9905902 0.06105393 -0.1231264 0.9904424 0.06215953 -0.1224652 0.9905065 0.06244391 -0.1227583 0.9905064 0.06186753 -0.1223955 0.9905244 0.06229698 -0.1222994 0.990494 0.0629642 -0.1222327 0.9905061 0.06290441 -0.120135 0.9907609 0.06293296 -0.120054 0.9907658 0.06301075 -0.1198486 0.9907416 0.06377649 -0.1195727 0.9907518 0.06413573 -0.1205244 0.9905383 0.06563466 -0.120662 0.9905157 0.0657218 -0.1197521 0.9906789 0.06492108 -0.1211869 0.990508 0.06486648 -0.1219022 0.9905117 0.06345462 -0.1227614 0.9905157 0.06171172 -0.1233141 0.9905637 0.05980956 -0.1269585 0.9902599 0.05715608 -0.1257308 0.9906212 0.05349361 -0.1259175 0.9903562 0.05778926 -0.1246956 0.9907129 0.05421245 -0.1270783 0.990579 0.05103486 -0.1278138 0.9903625 0.05334633 -0.1284981 0.9903827 0.05128878 -0.1276591 0.9904057 0.0529139 -0.1274636 0.99049 0.05179417 -0.126586 0.9904062 0.05542182 -0.1263652 0.9905314 0.05365967 -0.124992 0.990413 0.05881398 -0.1235494 0.9904722 0.06083083 -0.1246626 0.9905877 0.05652761 -0.1221767 0.9904987 0.06312787 -0.1235488 0.9904865 0.06059902 -0.122141 0.9904724 0.06360781 -0.1213908 0.9904958 0.06467211 -0.1157853 0.9903362 0.07634204 -0.1143487 0.9903212 0.07866692 -0.1172859 0.9900178 0.0781601 -0.1086466 0.989539 0.09491318 -0.1146605 0.990042 0.08166927 -0.1062056 0.9893298 0.09973561 -0.1037044 0.9890679 0.1048336 -0.09833312 0.9884585 0.1152408 -0.1049872 0.9878873 0.1142652 -0.1062988 0.9876975 0.1146917 -0.1107543 0.989891 0.08859729 -0.2215048 0.9663138 -0.1310473 -0.1249663 0.9902591 0.0614047 -0.1244384 0.9903342 0.06126564 -0.1249448 0.9902371 0.06180065 -0.1242516 0.9903086 0.06205213 -0.1244676 0.9903067 0.0616492 -0.1243217 0.9902966 0.06210333 -0.1240153 0.9903087 0.06252086 -0.1223948 0.9904567 0.06336551 -0.1234705 0.9903228 0.06337136 -0.1235508 0.9902348 0.06457793 -0.1230447 0.9902473 0.06534808 -0.1210044 0.9905055 0.06524586 -0.121698 0.9904043 0.06549072 -0.1224263 0.9902421 0.06657671 -0.1222526 0.9902716 0.06645619 -0.1224466 0.9902585 0.0662955 -0.1225308 0.990243 0.06637042 -0.1229447 0.9903124 0.06454449 -0.1227693 0.9902909 0.06520473 -0.12357 0.9903158 0.06328666 -0.1235767 0.9903142 0.06329852 -0.1242744 0.9903155 0.06189531 -0.1264106 0.9900851 0.0612533 -0.1256785 0.9903836 0.0578382 -0.1249349 0.9902577 0.06148988 -0.1244547 0.990486 0.05872333 -0.1281259 0.9901775 0.05596673 -0.1277892 0.9903655 0.05335056 -0.1299269 0.9900974 0.05316138 -0.1290775 0.9903012 0.05140775 -0.1215346 0.9903235 0.06699806 -0.1208356 0.9903155 0.06836736 -0.1139276 0.9897331 0.08630788 -0.1117913 0.9895809 0.09073317 -0.09479349 0.9884214 0.118479 -0.09296697 0.9879689 0.1235912 -0.09253764 0.9883238 0.1210491 -0.104162 0.9888831 0.1061152 -0.09519046 0.98831 0.1190881 -0.196514 0.9774126 -0.07776325 -0.2454994 0.9519972 -0.1828427 -0.2508701 0.9487893 -0.191998 -0.2533913 0.9462227 -0.2011361 -0.1255549 0.9901698 0.06164234 -0.1257359 0.9901393 0.06176537 -0.1257905 0.990108 0.06215292 -0.125544 0.990142 0.06210982 -0.125324 0.9901384 0.06260901 -0.12529 0.9901443 0.06258428 -0.1253111 0.9900876 0.06343346 -0.1248388 0.9901748 0.06300175 -0.125343 0.9900498 0.063959 -0.1242389 0.9902011 0.06377136 -0.1243572 0.9901541 0.06426638 -0.1224659 0.9903604 0.06471854 -0.124167 0.9901314 0.06498014 -0.1240578 0.9900581 0.06629294 -0.1241386 0.9901579 0.0646317 -0.1242282 0.9903254 0.06183087 -0.1274891 0.9900243 0.05998837 -0.1283623 0.9899648 0.05910092 -0.1271502 0.9902302 0.05724614 -0.1279688 0.9903292 0.05359399 -0.1282866 0.9901586 0.05593448 -0.1308043 0.9900199 0.0524494 -0.1299553 0.9900405 0.05414426 -0.1286612 0.990105 0.05602097 -0.1289387 0.9900396 0.05653774 -0.1271961 0.990127 0.05890375 -0.1213303 0.9901276 0.07018917 -0.1199452 0.9900999 0.07290649 -0.119944 0.9900997 0.0729115 -0.1187125 0.9900685 0.07531118 -0.09802585 0.9879189 0.1200298 -0.09387576 0.9881854 0.1211481 -0.09266513 0.9879931 0.1236244 -0.09565502 0.9880707 0.120692 -0.09787344 0.9882566 0.1173444 -0.09455496 0.9878705 0.1231719 -0.113469 0.9894818 0.08972537 -0.1391374 0.9894963 0.03921723 -0.1561657 0.987717 0.005249261 -0.2293528 0.9624276 -0.1453636 -0.2403977 0.9553955 -0.1715469 -0.2495244 0.950305 -0.1861667 -0.2396382 0.9567828 -0.1647436 -0.1267424 0.9899761 0.0623216 -0.1265833 0.9899863 0.06248265 -0.1263731 0.9899753 0.0630775 -0.1260265 0.9899093 0.06478416 -0.1252202 0.9900702 0.06388276 -0.1252447 0.9900054 0.06483119 -0.1252724 0.989977 0.06521105 -0.1238134 0.9901297 0.06567859 -0.123577 0.9901688 0.06553393 -0.1244186 0.9900361 0.06594485 -0.1246721 0.9899566 0.06665503 -0.1241641 0.9899731 0.06735426 -0.1241811 0.9899699 0.06737029 -0.1239352 0.9900728 0.06630212 -0.1245065 0.9899346 0.06728899 -0.1254516 0.9899023 0.06599551 -0.1257895 0.9899603 0.06446593 -0.1269143 0.9898597 0.06380039 -0.1257006 0.9899836 0.06428134 -0.1260606 0.9900401 0.06268656 -0.1269356 0.9900116 0.06135457 -0.1295622 0.9898869 0.05777066 -0.129855 0.9899633 0.05577182 -0.1302753 0.9900324 0.05351942 -0.1309151 0.9898581 0.0551576 -0.1312808 0.9899507 0.05256593 -0.129986 0.9900366 0.05414026 -0.1241354 0.9899423 0.06785899 -0.1231067 0.9899294 0.06988954 -0.1172282 0.9897791 0.08120828 -0.1178641 0.9895463 0.08310306 -0.1031236 0.988449 0.1110586 -0.09694319 0.9882022 0.118569 -0.09479242 0.9876833 0.1244843 -0.09672123 0.987727 0.1226395 -0.1024828 0.9882664 0.113256 -0.109898 0.9889909 0.09909439 -0.1198195 0.989595 0.07965588 -0.1494813 0.9884751 0.02392673 -0.167244 0.9858245 -0.01339781 -0.2065512 0.9736412 -0.09674453 -0.2149736 0.9698839 -0.1145061 -0.2549559 0.9464558 -0.1980379 -0.2544478 0.9459066 -0.2012888 -0.1276648 0.9898334 0.06270319 -0.1274083 0.9898713 0.06262582 -0.1277751 0.9897994 0.06301313 -0.1271465 0.9898915 0.06283903 -0.1271694 0.9898733 0.06307786 -0.1272025 0.9898146 0.06392699 -0.1267654 0.989865 0.06401497 -0.1267576 0.9898425 0.06437754 -0.1269091 0.989835 0.06419283 -0.1268847 0.9897915 0.06490784 -0.1267564 0.9898427 0.06437689 -0.1265483 0.9898318 0.06495046 -0.1248481 0.9900301 0.06521999 -0.1263202 0.9897888 0.06604188 -0.1252757 0.9899163 0.06611901 -0.1247502 0.9899481 0.06663471 -0.1261515 0.9898154 0.06596636 -0.1280661 0.989758 0.06307393 -0.128778 0.989785 0.06117182 -0.1283911 0.9898971 0.06016421 -0.1290679 0.9898648 0.0592398 -0.1304844 0.9897551 0.0579552 -0.1327131 0.9897195 0.05331683 -0.1314631 0.9897927 0.05502712 -0.1304877 0.9898154 0.05690711 -0.1300501 0.9897554 0.05891728 -0.1285554 0.9898506 0.0605753 -0.1305014 0.9898123 0.05693179 -0.1274986 0.9898574 0.06266045 -0.1262795 0.9898583 0.06506866 -0.1285248 0.98984 0.06081247 -0.127497 0.9898572 0.06266766 -0.1233793 0.9897862 0.0714209 -0.1262807 0.9898586 0.06506395 -0.1221047 0.9897623 0.07389968 -0.1253735 0.989854 0.06686246 -0.1200955 0.9897548 0.07721722 -0.1221054 0.9897606 0.07392114 -0.1166436 0.989304 0.0875895 -0.1199876 0.9897018 0.07806068 -0.1142943 0.9891878 0.09189325 -0.1186338 0.9897031 0.0800867 -0.1119133 0.9890302 0.09640961 -0.1094723 0.9888215 0.1012321 -0.1068764 0.9885609 0.1064186 -0.1017215 0.9879472 0.1166761 -0.09612441 0.9878535 0.1220882 -0.09490782 0.9876521 0.1246435 -0.1008669 0.987824 0.1184461 -0.09786707 0.9878275 0.1209083 -0.1223518 0.9891911 0.08081507 -0.188546 0.9804821 -0.05572754 -0.1992892 0.9769445 -0.07657223 -0.2364027 0.9586426 -0.1584869 -0.2225153 0.9672137 -0.1224124 -0.1285271 0.9896888 0.06322187 -0.128184 0.9897331 0.06322431 -0.1285785 0.9896628 0.063524 -0.1284115 0.9896677 0.0637837 -0.1282836 0.9896916 0.06367027 -0.1257779 0.9898362 0.06636524 -0.125678 0.9898559 0.06626129 -0.1258226 0.9897981 0.06684803 -0.125793 0.9897098 0.06819671 -0.1258566 0.9896979 0.06825101 -0.1260888 0.9897117 0.06762027 -0.1257848 0.9897761 0.06724327 -0.1274705 0.9897772 0.06397336 -0.1276801 0.9896093 0.06611663 -0.1285315 0.9895451 0.06542366 -0.1295108 0.9897683 0.05988144 -0.1313706 0.9897224 0.05649417 -0.1312074 0.9895749 0.0593816 -0.1324469 0.98966 0.0550549 -0.1315301 0.9896795 0.0568723 -0.1322223 0.9897183 0.05454331 -0.1329072 0.9896931 0.05332255 -0.1321196 0.9897087 0.05496668 -0.1325599 0.9896759 0.0544942 -0.09795111 0.9875953 0.1227242 -0.09696352 0.9873976 0.1250768 -0.1280894 0.9893741 0.06879043 -0.1419761 0.9890413 0.04049921 -0.1590035 0.9872564 0.006531 -0.1781109 0.9834251 -0.03393751 -0.2090541 0.9732154 -0.09564602 -0.2172069 0.9695114 -0.1134408 -0.2243154 0.965838 -0.1297672 -0.2317644 0.9620333 -0.1441432 -0.2431184 0.9549248 -0.1703293 -0.2481206 0.9515866 -0.1814363 -0.2423821 0.9567103 -0.1611099 -0.1291217 0.9895929 0.06351023 -0.1288045 0.9896271 0.06362038 -0.128655 0.9895945 0.06442421 -0.12859 0.9895984 0.06449532 -0.1284252 0.9895952 0.0648725 -0.1285829 0.9896025 0.06444776 -0.1284107 0.9895985 0.06485038 -0.1281815 0.9895627 0.06584346 -0.1279363 0.9896519 0.06497359 -0.1278336 0.989638 0.06538498 -0.1278598 0.9896011 0.06589037 -0.1277764 0.9895808 0.06635665 -0.127388 0.9895806 0.06710118 -0.1268864 0.9896154 0.06753766 -0.1272169 0.9895284 0.06818777 -0.1268692 0.9895933 0.06789302 -0.1282598 0.9897365 0.06301647 -0.1307526 0.9895852 0.06020808 -0.1297371 0.9895946 0.06221503 -0.132381 0.9895593 0.05698853 -0.1328946 0.9895488 0.05596804 -0.1199721 0.9865422 0.1110909 -0.09720784 0.9873991 0.1248752 -0.1007735 0.9874707 0.1214348 -0.1001186 0.9877342 0.1198232 -0.0977807 0.9874098 0.124342 -0.1164286 0.989018 0.09103715 -0.1696845 0.9854217 -0.01229906 -0.1290713 0.9896019 0.06347262 -0.1302664 0.9893989 0.06419068 -0.1296095 0.9894716 0.06439942 -0.1292369 0.9895135 0.06450688 -0.1292977 0.9895296 0.06413602 -0.1279489 0.9894993 0.06723177 -0.1275418 0.9895622 0.06708174 -0.1268532 0.9896253 0.06745386 -0.1270597 0.9895414 0.0682916 -0.1267393 0.9895923 0.06815028 -0.127399 0.989458 0.06886494 -0.1272119 0.9894813 0.06887513 -0.1276381 0.9894626 0.0683549 -0.1268927 0.9895483 0.06850177 -0.1269451 0.9896727 0.06658077 -0.1278623 0.9895938 0.06599694 -0.128323 0.9893659 0.06847321 -0.1304944 0.9896421 0.05983215 -0.133376 0.9893435 0.05839765 -0.1340565 0.9894044 0.05574929 -0.1333596 0.9893627 0.05811017 -0.1342058 0.9893567 0.05623245 -0.1348028 0.9893941 0.05410629 -0.1346286 0.9894144 0.05416959 -0.1340584 0.9893915 0.0559715 -0.1344044 0.9893831 0.05528736 -0.1259482 0.98949 0.07104021 -0.1267904 0.9894988 0.06940138 -0.2070448 0.9703395 0.1247946 -0.1201081 0.9893223 0.0825572 -0.09896236 0.9875848 0.1219949 -0.09762305 0.9872016 0.1261066 -0.09894621 0.9873924 0.1235554 -0.1351073 0.9892712 0.05557495 -0.1907724 0.980108 -0.05471998 -0.2387193 0.9582649 -0.1572947 -0.2534934 0.9484181 -0.1903795 -0.1306375 0.9893461 0.0642513 -0.1301317 0.989421 0.064125 -0.130418 0.9893682 0.06435787 -0.1303132 0.9893624 0.06465816 -0.1303207 0.9893612 0.06465959 -0.1301893 0.9893604 0.06493747 -0.1293724 0.9894393 0.06536769 -0.1297852 0.9893673 0.06563645 -0.1289915 0.989431 0.0662387 -0.129771 0.9893301 0.06622409 -0.1288701 0.9894022 0.06690055 -0.1288153 0.9893863 0.06724125 -0.1291064 0.9894017 0.06645244 -0.1288794 0.9894012 0.06689983 -0.1278207 0.9893946 0.06899636 -0.1281431 0.9893782 0.06863105 -0.127483 0.9894601 0.0686807 -0.1296306 0.9893578 0.06608521 -0.1303235 0.9893803 0.0643621 -0.1295242 0.9894185 0.06538045 -0.1311973 0.9893928 0.0623629 -0.1302666 0.9894085 0.06404346 -0.1323875 0.9893258 0.06089448 -0.1313653 0.9893391 0.0628609 -0.1315872 0.9893761 0.06180524 -0.1330101 0.9893745 0.0587061 -0.1348702 0.9893395 0.05492985 -0.1350595 0.9893334 0.05457502 -0.1350437 0.9893308 0.05466246 -0.1331341 0.989397 0.0580427 -0.1341149 0.9893691 0.05623203 -0.1321094 0.9894207 0.05994933 -0.1339264 0.9893412 0.0571646 -0.1331492 0.989404 0.05789011 -0.1321073 0.989421 0.05994731 -0.131169 0.9894312 0.06181335 -0.1300891 0.98944 0.06391698 -0.1288609 0.9894421 0.06632697 -0.1259877 0.9893514 0.07287627 -0.1229071 0.9893435 0.07806116 -0.1997182 0.9717956 0.1254038 -0.1899802 0.9737974 0.1250054 -0.17765 0.976297 0.1236317 -0.1622703 0.9792985 0.1210084 -0.1435024 0.9827263 0.116859 -0.103062 0.9876198 0.1182605 -0.1028802 0.98751 0.1193301 -0.1006531 0.9874341 0.1218313 -0.1516497 0.988119 0.02496463 -0.1796069 0.9831841 -0.03302204 -0.2259324 0.9655919 -0.1287903 -0.1290931 0.9893009 0.06796252 -0.1275437 0.989484 0.06822061 -0.1280646 0.989341 0.06931155 -0.1281151 0.989329 0.06938809 -0.1280817 0.9893344 0.06937313 -0.1280778 0.9893342 0.06938165 -0.1281382 0.9893289 0.06934738 -0.1283047 0.9893088 0.06932473 -0.1285648 0.9892817 0.06923156 -0.1286411 0.9892643 0.06933683 -0.1284592 0.9893137 0.06896865 -0.1285123 0.9893257 0.06869703 -0.128972 0.9892899 0.06834906 -0.1296727 0.9891752 0.06868517 -0.1291932 0.9893065 0.06768894 -0.129123 0.9893926 0.06655389 -0.1325334 0.9892802 0.06131702 -0.1325013 0.9893753 0.05983388 -0.2105379 0.9731065 0.09347563 -0.136282 0.9890762 0.05617451 -0.1355861 0.9892491 0.05479568 -0.1355981 0.9892616 0.05454087 -0.1356944 0.9892528 0.05446195 -0.2695842 0.9038066 0.3323522 -0.2827391 0.9496561 0.1349515 -0.1311702 0.9894314 0.0618059 -0.291789 0.9459289 0.1416958 -0.1300852 0.9894379 0.06395632 -0.2992336 0.9426527 0.1478686 -0.1288597 0.9894419 0.06633281 -0.3047708 0.9399773 0.1534844 -0.1275816 0.9894352 0.06885409 -0.3082572 0.9380455 0.1582669 -0.3088377 0.9370673 0.1628624 -0.1240235 0.9894536 0.07483136 -0.1230089 0.9892867 0.07861793 -0.3038911 0.9380567 0.1664329 -0.1208972 0.9892711 0.08201587 -0.09938532 0.9870607 0.1258325 -0.1003285 0.9871987 0.123988 -0.09905815 0.9870133 0.1264607 -0.09939688 0.9870665 0.1257777 -0.09939253 0.9870103 0.1262215 -0.1002179 0.9871512 0.1244553 -0.2008762 0.9767003 -0.07553458 -0.2564236 0.9466798 -0.1950492 -0.1311751 0.9892517 0.06460869 -0.1309349 0.9892825 0.06462448 -0.1307927 0.9892832 0.06490224 -0.1311224 0.9892391 0.06490695 -0.1305812 0.9892877 0.06525737 -0.1309213 0.9892429 0.06525653 -0.1302117 0.9893027 0.0657655 -0.1305986 0.9892581 0.06566971 -0.1299568 0.9892994 0.06631767 -0.1304703 0.9892399 0.06619721 -0.1298985 0.9892712 0.06684935 -0.1299567 0.9892238 0.06743615 -0.1301505 0.989246 0.066733 -0.129419 0.989268 0.06782114 -0.129778 0.9892611 0.06723308 -0.1293542 0.9892769 0.06781399 -0.129141 0.9892554 0.06853079 -0.12857 0.9893208 0.06866097 -0.0972895 0.9937582 0.05458384 -0.09535545 0.9943379 0.04689991 -0.09055835 0.9945683 0.05131471 -0.0885365 0.9951147 0.0436818 -0.08376252 0.9953302 0.04797542 -0.0816642 0.9958391 0.04044395 -0.07698291 0.9960368 0.04454797 -0.07483333 0.9965013 0.03722029 -0.07025671 0.9966807 0.04112821 -0.06806612 0.9971002 0.03403484 -0.06366062 0.9972596 0.03769218 -0.06146162 0.9976302 0.03092896 -0.05736929 0.9977663 0.03422331 -0.05488717 0.9981043 0.02784639 -0.04848158 0.9983807 0.02975833 -0.04855072 0.9983949 0.02916234 -0.04127341 0.9989188 0.02139574 -0.03887587 0.99897 0.02340525 -0.03327006 0.999288 0.01779574 -0.0325005 0.9992942 0.01884263 -0.03050482 0.9993888 0.01707601 -0.03503823 0.9992187 0.01828533 -0.03716766 0.9991572 0.01742446 -0.04266119 0.9987914 0.0244075 -0.04853159 0.998587 0.02164828 -0.05292499 0.9981626 0.02950161 -0.06036579 0.9978323 0.02620369 -0.06640666 0.9971224 0.03656691 -0.07598775 0.9965791 0.03250044 -0.08391296 0.9954259 0.04567092 -0.09597373 0.994539 0.04100292 -0.1058469 0.9927468 0.05701059 -0.1213872 0.9912463 0.05192172 -0.133686 0.9884527 0.07133942 -0.1502273 0.9865265 0.06478559 -0.1646862 0.9824789 0.0872569 -0.1849718 0.979426 0.08068639 -0.2013626 0.9737601 0.1060396 -0.2235093 0.9696745 0.0988689 -0.2414548 0.9621275 0.1265323 -0.2655298 0.9566789 0.1194135 -0.2841008 0.9472565 0.1482974 -0.3090091 0.9405336 0.1411026 -0.3275302 0.929341 0.1704386 -0.3527336 0.9213821 0.1632 -0.3706631 0.9086188 0.192408 -0.3952682 0.8996931 0.1852447 -0.4119488 0.8858605 0.2134237 -0.4354251 0.8762407 0.2064149 -0.4505445 0.8618014 0.2330412 -0.472569 0.8517881 0.2261319 -0.4860212 0.8371 0.2510914 -0.5060721 0.8270693 0.2446374 -0.5174589 0.8129633 0.2670714 -0.2724776 0.9513193 0.1440398 -0.2828822 0.9474304 0.14951 -0.2918616 0.9439372 0.1542708 -0.2992601 0.9409621 0.1582205 -0.3047733 0.9386794 0.1612274 -0.308302 0.9372058 0.1630808 -0.3089521 0.9368042 0.1641544 -0.3038715 0.9388942 0.1616789 -0.2965121 0.9402111 0.167582 -0.2963868 0.9418848 0.1581391 -0.2892605 0.9439574 0.1589742 -0.2753433 0.9489609 0.1538162 -0.2567561 0.955305 0.1465216 -0.2326458 0.962903 0.1367248 -0.2021552 0.9714682 0.1240276 -0.164008 0.9805687 0.1076397 -0.1138039 0.9874606 0.1094092 -0.1009967 0.9872136 0.1233245 -0.1025144 0.9872084 0.1221078 -0.1021386 0.9873623 0.1211757 -0.1001539 0.9870887 0.1250007 -0.1297049 0.9891145 0.06949132 -0.1437739 0.9887475 0.04132241 -0.1607112 0.9869729 0.007507562 -0.2107343 0.9729485 -0.09467017 -0.2186065 0.9692789 -0.1127367 -0.2447623 0.9546953 -0.1692583 -0.2497661 0.9513942 -0.1801832 -0.257386 0.9455153 -0.199382 -0.2570961 0.946226 -0.1963623 -0.1296802 0.9892228 0.06797999 -0.1271879 0.9899278 0.06217908 -0.1229912 0.9901757 0.06652307 -0.1213237 0.9908521 0.05910003 -0.1167682 0.9911122 0.06373327 -0.1151284 0.9917596 0.05619913 -0.1104269 0.9920228 0.06080061 -0.1086866 0.992653 0.05317324 -0.1039254 0.9929075 0.05774366 -0.1020889 0.9935144 0.0500701 -0.1133178 0.9884256 0.100866 -0.1182301 0.9887196 0.09195333 -0.2574371 0.945565 -0.1990804 -0.1315518 0.9891944 0.0647189 -0.1314166 0.9892135 0.0647037 -0.1312329 0.9892207 0.06496381 -0.1315559 0.9891777 0.06496638 -0.1310552 0.9892205 0.06532508 -0.1314138 0.9891793 0.06522947 -0.1308879 0.9892101 0.06581693 -0.1312599 0.9891742 0.06561499 -0.1305837 0.989221 0.06625461 -0.1311092 0.9891608 0.06611663 -0.1303311 0.9892162 0.06682378 -0.1306824 0.9891746 0.06675267 -0.1299821 0.9892273 0.067335 -0.1304184 0.989176 0.0672459 -0.1295382 0.9891955 0.06864553 -0.1301526 0.9891802 0.06769818 -0.104436 0.9875296 0.1178069 -0.1050783 0.9874253 0.1181101 -0.1040081 0.9873144 0.1199694 -0.1020968 0.9872182 0.1223783 -0.1241497 0.9888945 0.08169829 -0.136389 0.9890574 0.05624634 -0.2332856 0.96183 -0.1430415 -0.2525125 0.9503552 -0.181831 -0.1297739 0.9891969 0.0681796 -0.1293597 0.9892195 0.06863576 -0.1143563 0.9882497 0.1014161 -0.1809762 0.9829483 -0.0325635 -0.1846727 0.9824799 -0.02508687 -0.1324453 0.9890413 0.06523525 -0.1320981 0.9890985 0.06507205 -0.1319078 0.9891189 0.06514757 -0.1318655 0.9891038 0.06546121 -0.1320754 0.9890841 0.06533724 -0.1315552 0.9891253 0.06576138 -0.1319087 0.9890921 0.06555128 -0.13134 0.9891244 0.06620222 -0.1316935 0.9890946 0.06594461 -0.1307719 0.9891172 0.06742304 -0.1312026 0.9890787 0.06715166 -0.1306419 0.9890989 0.0679419 -0.1308748 0.9890863 0.06767821 -0.1304569 0.9890883 0.06845009 -0.1303513 0.9890821 0.0687403 -0.1306703 0.9890891 0.06802886 -0.1065236 0.9876515 0.1148799 -0.1070919 0.9875408 0.1153016 -0.1390749 0.9886007 0.05768078 -0.2415565 0.9579861 -0.1546389 -0.247052 0.9545457 -0.1667563 -0.2562094 0.9483261 -0.1871748 -0.1304474 0.9890912 0.06842613 -0.1299115 0.9891325 0.06884753 -0.1124631 0.9875394 0.1100826 -0.1727384 0.9849141 -0.0102849 -0.2584667 0.9463378 -0.1940102 -0.1327285 0.9889915 0.06541496 -0.1323887 0.9890525 0.06518071 -0.1322197 0.9890615 0.06538695 -0.1320559 0.9890649 0.06566572 -0.1320953 0.9890324 0.06607437 -0.1319612 0.989051 0.06606489 -0.1317728 0.9890452 0.06652599 -0.1318287 0.9890329 0.06659656 -0.1316794 0.9890329 0.06689184 -0.1314321 0.9890495 0.06713247 -0.1312047 0.9890783 0.06715226 -0.1305972 0.9890307 0.06901162 -0.1306056 0.9890128 0.06925272 -0.130249 0.989054 0.0693354 -0.1021064 0.986952 0.1244997 -0.1053518 0.9867122 0.1236938 -0.1009216 0.9868074 0.1265943 -0.1022688 0.9870064 0.1239331 -0.1009506 0.9868197 0.1264753 -0.1005582 0.9867573 0.1272714 -0.1016954 0.9868921 0.1253079 -0.1005548 0.9867547 0.127295 -0.103269 0.9871047 0.122311 -0.1017339 0.9869096 0.1251384 -0.1032789 0.9871109 0.1222518 -0.1064519 0.9868782 0.1214065 -0.1453301 0.9884709 0.04248201 -0.153663 0.9877772 0.02615475 -0.1624829 0.9866778 0.00814855 -0.2202246 0.9690679 -0.1113941 -0.2276732 0.965353 -0.1275092 -0.2514171 0.9512525 -0.1786288 -0.2584595 0.9455119 -0.1980049 -0.2240417 0.9687417 -0.1065121 -0.1313338 0.9890167 0.06780523 -0.1213741 0.9881751 0.09369337 -0.1270493 0.9883782 0.08346861 -0.1926075 0.9798231 -0.05337828 -0.2026793 0.9764073 -0.07449781 -0.2359389 0.9615787 -0.1403548 -0.2585799 0.9456195 -0.1973331 -0.1326478 0.9889807 0.06574159 -0.1325751 0.9889963 0.06565296 -0.1324974 0.9889992 0.06576699 -0.1323448 0.9889931 0.06616258 -0.1324638 0.9889705 0.0662623 -0.1320562 0.989005 0.06656157 -0.1318651 0.9889685 0.06747525 -0.1312184 0.9890381 0.06771582 -0.1313965 0.9889649 0.06843614 -0.1313709 0.988971 0.06839632 -0.1308528 0.9890237 0.06862741 -0.1061449 0.9873616 0.1176882 -0.1078852 0.98702 0.1189637 -0.1102337 0.9869761 0.1171614 -0.1173168 0.9877321 0.1030642 -0.1328514 0.9885576 0.07144618 -0.1493619 0.9877602 0.04495501 -0.1574481 0.9871106 0.02868795 -0.1662348 0.9860257 0.01092565 -0.1837844 0.9824928 -0.03051882 -0.2133576 0.9725764 -0.09259432 -0.2560566 0.9512244 -0.1720676 -0.2587151 0.947025 -0.19029 -0.2553246 0.9515312 -0.1714575 -0.1337457 0.9888174 0.06597232 -0.1332321 0.9889084 0.06564682 -0.1321205 0.9890692 0.06547147 -0.1329662 0.9888926 0.06641781 -0.1334418 0.9888082 0.06672221 -0.132754 0.9888929 0.06683659 -0.1321499 0.9889265 0.06753492 -0.130704 0.9890825 0.06806135 -0.1313576 0.9888735 0.06981694 -0.1061317 0.9861186 0.127696 -0.1069334 0.9864655 0.1243036 -0.1128594 0.9857046 0.1250976 -0.178904 0.9838501 -0.005707085 -0.1891574 0.9815862 -0.02661263 -0.1962708 0.9792481 -0.05050969 -0.2063689 0.9758424 -0.07171946 -0.2236741 0.9686442 -0.1081595 -0.2311521 0.9649244 -0.1244571 -0.2445171 0.9582008 -0.1485353 0.04635882 -0.8308269 0.5545968 0.02450692 -0.9136541 0.4057531 -0.1347894 0.9886382 0.06653219 -0.1344921 0.9886904 0.06635671 -0.1353536 0.9885053 0.06735658 -0.1334314 0.9888141 0.06665509 -0.1342316 0.9886311 0.06775331 -0.1343287 0.9886126 0.06783026 -0.1338081 0.9886449 0.06838607 -0.1334936 0.9887034 0.06815516 -0.133942 0.9885563 0.06939816 -0.1339545 0.9885538 0.06940919 -0.1332442 0.9886083 0.06999719 -0.1327016 0.9887313 0.06928724 -0.109404 0.9874017 0.1143194 -0.1038485 0.9865638 0.1261252 -0.1053329 0.9859129 0.1299262 -0.1026875 0.9865109 0.1274816 -0.1027548 0.9864602 0.1278198 -0.127327 0.9870892 0.09717375 -0.1326357 0.9873518 0.08685714 -0.1385272 0.9875134 0.07501643 -0.1453004 0.9874689 0.06158709 -0.2186976 0.9718096 -0.08807718 -0.2110705 0.9751178 -0.06778305 -0.2407008 0.9610943 -0.1355029 -0.2465341 0.9576315 -0.1488726 -0.2519661 0.9543337 -0.1605002 -0.2605158 0.9485815 -0.1797913 -0.2624348 0.9467368 -0.1865945 -0.2606189 0.945658 -0.1944447 -0.1376522 0.9881526 0.06786918 -0.1362602 0.9883854 0.06728714 -0.1370404 0.9882137 0.06821858 -0.1369009 0.988239 0.0681324 -0.1365423 0.9882338 0.06892257 -0.1362018 0.9882338 0.06959336 -0.1360465 0.988263 0.06948149 -0.1349648 0.9883811 0.0699104 -0.1360679 0.9881706 0.07074189 -0.1349426 0.988313 0.07090848 -0.135815 0.9881407 0.07164061 -0.1320117 0.9886468 0.07176715 -0.1090139 0.9862222 0.124426 -0.1050149 0.9862428 0.1276597 -0.1116708 0.9855662 0.1272358 -0.1078253 0.9857484 0.1291279 -0.1080074 0.9858917 0.1278753 -0.1121585 0.9849499 0.1315077 -0.1125841 0.9850275 0.1305598 -0.1043826 0.9861704 0.1287333 -0.1074438 0.9862348 0.1256859 -0.1155458 0.9860156 0.1200932 -0.1186889 0.9864091 0.1136227 -0.1227176 0.9867457 0.1061761 -0.1543353 0.9868367 0.04831176 -0.1623301 0.9862191 0.03195327 -0.1712126 0.9851285 0.01443552 -0.2010279 0.9784662 -0.04681593 -0.2355157 0.9644336 -0.120001 -0.26157 0.9459831 -0.1915653 -0.2620657 0.9477946 -0.1816789 -0.1433769 0.9871279 0.07086443 -0.1433476 0.9871057 0.07123124 -0.1387716 0.9879429 0.06863808 -0.1430123 0.9871388 0.0714451 -0.1387407 0.987879 0.06961447 -0.1365628 0.98823 0.06893634 -0.1426771 0.9871429 0.07205575 -0.1383414 0.9878919 0.07022362 -0.1418825 0.9872263 0.0724824 -0.1378248 0.9879072 0.07101821 -0.1413626 0.9872491 0.07318383 -0.1372137 0.9879328 0.07184189 -0.141303 0.9871984 0.07397806 -0.1349545 0.9883233 0.07074272 -0.1413336 0.9872599 0.07309305 -0.1132577 0.985107 0.129372 -0.1135869 0.9844792 0.1337863 -0.115691 0.9847377 0.1300283 -0.1141116 0.9854981 0.1255868 -0.1167647 0.9858164 0.120549 -0.1200017 0.986169 0.1143251 -0.1238755 0.9865485 0.1066629 -0.1285179 0.9868806 0.0977236 -0.1397775 0.9872931 0.07559579 -0.146553 0.987234 0.06238114 -0.1539975 0.9869147 0.04779231 -0.1620842 0.9862694 0.03164774 -0.1707834 0.9852091 0.0140081 -0.1800941 0.9836356 -0.005218744 -0.1901952 0.9814036 -0.02594125 -0.2007534 0.9784976 -0.04733484 -0.2106714 0.9751679 -0.06830108 -0.2196763 0.9716356 -0.08755922 -0.2281616 0.9680388 -0.1041315 -0.2279141 0.9680247 -0.1048014 -0.2417138 0.9609039 -0.1350484 -0.2476331 0.9574803 -0.1480183 -0.2529407 0.9542042 -0.1597359 -0.2576144 0.9511986 -0.169871 -0.2259028 -0.3047643 0.9252495 0.02407968 -0.7345682 0.6781076 -0.2629205 0.9480398 -0.1791461 0.01519852 -0.5577383 0.8298778 -0.1393816 0.9878487 0.06875997 -0.1456519 0.9867092 0.0720458 -0.1458892 0.9866635 0.07219111 -0.1459125 0.9866238 0.07268399 -0.1451571 0.9867711 0.07219636 -0.1458235 0.9866113 0.07303184 -0.144844 0.986767 0.07287728 -0.1455937 0.9866093 0.07351619 -0.1445172 0.986781 0.07333564 -0.144503 0.9867841 0.07332259 -0.1441683 0.9867717 0.07414412 -0.1436899 0.9867396 0.07548761 -0.1452871 0.9867327 0.07245957 -0.1384353 0.9880908 0.06717282 -0.1063794 0.9861149 0.1275176 -0.104435 0.9849912 0.1374257 -0.1110896 0.9845166 0.1355965 -0.1147159 0.9847547 0.1307619 -0.1130719 0.9853278 0.127843 -0.1148842 0.984667 0.131273 -0.1135037 0.9845015 0.1336935 -0.1154875 0.9848794 0.1291332 -0.1337973 0.9871519 0.08734667 -0.2352119 0.9644391 -0.1205511 -0.1449064 0.9868471 0.07165968 -0.1420344 0.9873742 0.07013213 -0.1419737 0.9873765 0.07022386 -0.1451802 0.9867802 0.07202553 -0.1420655 0.9873175 0.07086491 -0.1445397 0.9868742 0.07202565 -0.144631 0.9868116 0.07269698 -0.1414234 0.9873701 0.07141363 -0.1443264 0.9868156 0.07324665 -0.1418523 0.9872284 0.0725131 -0.1410293 0.9872967 0.07318508 -0.1405404 0.9873234 0.07376462 -0.1441724 0.986959 0.07159793 -0.142495 0.987455 0.06802773 -0.1415165 0.9879608 0.06250286 -0.1390186 0.9882776 0.06309813 -0.1001636 0.9841188 0.1465527 -0.1071206 0.9846557 0.1377614 -0.08401978 0.9895594 0.1171028 -0.09717184 0.9877715 0.1219226 -0.1115782 0.9850687 0.1311105 -0.1117907 0.9848446 0.1326045 -0.1125833 0.9851124 0.129918 -0.08649188 0.9898044 0.1131658 -0.09985685 0.98804 0.1174966 -0.08871954 0.9901067 0.1087096 -0.1024831 0.9883916 0.1121577 -0.1059937 0.9887049 0.1059632 -0.09161722 0.9904244 0.1032754 -0.109838 0.9890917 0.09814924 -0.0957995 0.9908036 0.09555536 -0.1145385 0.9894629 0.08856672 -0.1000409 0.9911314 0.08746713 -0.1072144 0.9910546 0.07947236 -0.1085267 0.9915732 0.07074379 -0.1196973 0.9897459 0.07794666 -0.1260415 0.9898079 0.06628626 -0.1222883 0.9915212 0.04394686 -0.140511 0.9893451 0.0381186 -0.1327885 0.9897339 0.052859 -0.1305289 0.9910674 0.02734482 -0.1487194 0.9886347 0.02200424 -0.1392295 0.9902026 0.01068174 -0.1577225 0.9874752 0.004059016 -0.1488716 0.988815 -0.009064137 -0.1674585 0.9857686 -0.01477122 -0.1595236 0.9867754 -0.02874898 -0.1776847 0.9834306 -0.03595197 -0.1703871 0.9840217 -0.05166852 -0.188458 0.9804091 -0.05728513 -0.1991996 0.9768322 -0.07822102 -0.1824414 0.9804779 -0.07333666 -0.2082899 0.9731487 -0.09796488 -0.1938284 0.9764361 -0.09488463 -0.2169589 0.9693112 -0.1156056 -0.2031073 0.9724737 -0.114204 -0.2122309 0.9681931 -0.1325146 -0.2147301 0.9661329 -0.1431025 -0.223946 0.9653362 -0.1340685 -0.2312763 0.9615761 -0.1479277 0.2291683 -0.9577217 0.1739286 -0.2750657 0.9588997 -0.06964379 -0.06781286 -0.7339784 0.6757789 0.2360685 -0.9534911 0.1874204 0.06821 -0.8351532 0.5457717 0.2417731 -0.9495443 0.1997787 0.2481213 -0.9455774 0.2105216 0.2525792 -0.9436621 0.2137889 0.1432576 -0.8717538 0.4685326 0.2526692 -0.9433817 0.2149168 0.2458341 -0.9448514 0.2163828 0.2359452 -0.9534859 0.1876025 -0.1810107 0.9826037 0.04153692 0.1981289 -0.9799633 0.02041715 0.2173271 -0.9552503 0.2006636 -0.1396872 0.9877978 0.06886982 -0.1401532 0.9877005 0.0693168 -0.1390443 0.9878818 0.06896471 -0.1404272 0.9876114 0.07002907 -0.1385295 0.9879166 0.06950157 -0.1398836 0.987645 0.07063883 -0.1385747 0.9878507 0.07034248 -0.1395896 0.9876245 0.07150244 -0.138071 0.98787 0.07105815 -0.1381657 0.9877783 0.07214152 -0.1385512 0.9877048 0.07240855 -0.1376316 0.9878142 0.07266914 -0.1379224 0.9877529 0.07295107 -0.1447038 0.987696 0.05930793 -0.09794795 0.9841884 0.1475787 -0.09759443 0.9837043 0.1510009 -0.1095739 0.9856606 0.1283236 -0.1095529 0.9856672 0.1282903 -0.08423405 0.9894759 0.117653 -0.08383536 0.9895752 0.117101 -0.108295 0.9854447 0.1310385 -0.08472132 0.9898911 0.1137452 -0.08417111 0.9896367 0.1163381 -0.08716344 0.989867 0.1120978 -0.08945006 0.990329 0.1060522 -0.09341824 0.9905202 0.1007122 -0.09668511 0.9910837 0.09167993 -0.1030315 0.9912819 0.08212614 -0.1152101 0.9916615 0.05774235 -0.144384 0.989508 0.005218684 -0.1534788 0.9880443 -0.01458793 -0.1639168 0.9857597 -0.03753817 -0.1746895 0.9828272 -0.05945056 -0.1868063 0.978986 -0.08179068 -0.1961773 0.9749353 -0.1049554 -0.2060058 0.9708216 -0.1227489 -0.2228217 0.9620305 -0.1576324 0.2503783 -0.9448395 0.2111613 0.2563643 -0.9440312 0.2075635 0.2531283 -0.9426847 0.2174205 0.2516898 -0.9396786 0.2316388 -0.2634586 0.945703 -0.1903562 0.2526382 -0.9437158 0.213482 0.2448219 -0.9511797 0.1879348 0.2343875 -0.9556481 0.1783237 -0.112737 0.9921103 0.05484253 -0.1260137 0.9901036 0.06177079 -0.11231 0.9921738 0.05456799 -0.1112422 0.9922991 0.05447661 -0.1254626 0.9901507 0.06213617 -0.1114549 0.9922601 0.05475085 -0.111515 0.9922214 0.05533021 -0.1118823 0.9921696 0.05551385 -0.1265624 0.9899156 0.06363219 -0.1137759 0.9918766 0.05688792 -0.114448 0.9917604 0.05755966 -0.1142618 0.9917641 0.05786329 -0.1154242 0.9916045 0.05829197 -0.1279056 0.9896436 0.0651583 -0.1171 0.991306 0.05999958 -0.1170723 0.9913 0.06015366 -0.1179881 0.9911487 0.06085568 -0.1283642 0.989497 0.06647104 -0.1185966 0.9910421 0.0614041 -0.1185976 0.9910193 0.06177079 -0.117895 0.991105 0.06173992 -0.1168894 0.991241 0.06146615 -0.1272333 0.9896061 0.06701952 -0.1167951 0.9912484 0.06152576 -0.1153333 0.9914271 0.0614053 -0.08615595 0.9890689 0.1196661 -0.1077641 0.9855235 0.1308825 -0.109851 0.98541 0.13 -0.1139572 0.9910374 0.06970494 -0.1196973 0.9913029 0.05469083 -0.1279662 0.9909223 0.04120069 -0.1351076 0.9905551 0.02337753 -0.2235226 0.9646508 -0.1395948 -0.2298056 0.9609414 -0.1542108 0.2357007 -0.9565976 0.171366 0.2396706 -0.9519376 0.1907171 0.2469009 -0.9487221 0.1973986 0.1974592 -0.9535722 0.2273985 0.4519613 -2.50334e-5 0.8920376 0.4520372 1.34215e-4 0.8919992 0.4515484 -8.24746e-4 0.8922463 0.4520041 3.40365e-4 0.8920158 0.4521809 1.38366e-4 0.8919262 0.451706 -8.4431e-5 0.8921669 0.4517887 -1.15135e-4 0.8921251 0.4518965 -1.16133e-4 0.8920704 0.4519259 4.10185e-5 0.8920555 0.451909 3.78356e-5 0.8920641 0.4518935 4.4182e-5 0.8920719 0.4518887 4.61205e-5 0.8920744 0.4518681 0 0.8920848 0.4519342 4.42639e-5 0.8920513 0.4519671 1.32549e-4 0.8920347 0.4518427 -4.81196e-5 0.8920977 0.4518898 0 0.8920738 0.451839 -9.94571e-5 0.8920996 0.451868 4.05263e-4 0.8920848 0.4519223 -1.36863e-4 0.8920573 0.4516777 -8.4174e-5 0.8921813 0.4521236 1.3734e-4 0.8919553 0.4519427 5.80306e-5 0.8920471 0.4519477 5.2847e-5 0.8920445 0.4518425 0 0.8920977 0.4520214 6.67486e-5 0.8920072 0.4518012 -1.30565e-4 0.8921186 0.4518246 -1.06344e-4 0.892107 0.4518114 -5.4765e-5 0.8921136 0.4519625 1.34406e-4 0.892037 0.4518893 0 0.8920741 0.4519 -4.47869e-5 0.8920686 0.4518101 -1.01975e-4 0.8921141 0.4519142 8.08825e-5 0.8920615 0.4518687 -4.81018e-5 0.8920846 0.4518479 -2.99952e-5 0.892095 0.4518846 0 0.8920764 0.451878 1.39799e-4 0.8920798 0.4519116 8.91224e-5 0.8920628 0.451889 1.18689e-4 0.8920742 0.4518861 -1.3326e-4 0.8920758 0.4518831 -1.32436e-4 0.8920773 0.4518461 3.13086e-5 0.8920959 0.4518898 3.57086e-6 0.8920738 0.4518821 -1.0027e-6 0.8920777 0.4518988 -7.87967e-5 0.8920693 0.4517149 0 0.8921623 0.4518803 -1.70137e-6 0.8920786 0.4518925 -3.64445e-6 0.8920724 0.4518827 -6.25981e-6 0.8920774 0.4518874 -9.16765e-6 0.892075 0.4518909 -5.83881e-6 0.8920732 0.4518882 -9.2457e-6 0.8920747 0.4518873 -9.29267e-6 0.8920751 0.4519293 7.82426e-5 0.8920539 0.451981 -5.78425e-5 0.8920276 0.4518824 -6.51104e-5 0.8920776 0.4518279 3.21496e-6 0.8921052 0.4518193 1.07627e-4 0.8921095 0.4518751 -1.14558e-4 0.8920813 0.4520176 -1.53887e-4 0.8920091 0.4519364 -1.51901e-4 0.8920502 0.4518064 8.30526e-5 0.892116 0.4519077 1.04576e-4 0.8920648 0.4518902 1.03939e-5 0.8920737 0.4518936 0 0.892072 0.4518852 -1.17409e-4 0.8920761 0.4518902 4.9582e-5 0.8920736 0.4518998 1.30919e-4 0.8920687 0.4518887 -8.69518e-6 0.8920745 0.4518761 1.50013e-5 0.8920807 0.4519529 0 0.8920418 0.4518888 0 0.8920744 0.4518878 0 0.8920749 0.4518965 1.53694e-5 0.8920704 0.45179 9.74946e-5 0.8921244 0.4519606 0 0.892038 0.4518905 -2.42958e-6 0.8920735 0.4517494 2.78593e-6 0.8921449 0.4518852 0 0.8920761 0.4517869 -1.04548e-4 0.8921259 0.4518913 4.88959e-6 0.892073 0.4518607 0 0.8920885 0.4519231 1.2529e-4 0.8920569 0.4519368 1.02202e-4 0.8920501 0.451847 -1.12107e-4 0.8920955 0.4518247 -1.07654e-4 0.8921068 0.4518552 3.87432e-5 0.8920913 0.4519278 -3.2701e-5 0.8920546 0.4519343 7.26051e-5 0.8920513 -0.8800117 -0.1639474 0.4457587 -0.8920711 3.0519e-5 0.4518952 -0.8920711 -6.1038e-5 0.4518952 -0.7041205 -0.6139958 0.356684 -0.7842597 -0.476562 0.3972724 -0.7842252 -0.4766206 0.3972703 -0.8799872 -0.1640706 0.4457617 -0.8436366 -0.3250273 0.4273575 -0.4872644 -0.8376516 0.2468061 -0.358812 -0.9155399 0.1817712 -0.4872768 -0.8376425 0.2468124 -0.7040578 -0.6140859 0.3566526 -0.6046098 -0.7352916 0.3062571 -0.6046506 -0.7352432 0.3062928 0.07358092 -0.9965928 -0.03726351 -0.2191302 -0.9693613 0.1109995 -0.3587874 -0.915555 0.1817437 -0.2190954 -0.9693728 0.1109668 0.4875747 -0.8374163 -0.2469918 0.3576506 -0.9161154 -0.18116 0.357626 -0.9161304 -0.1811324 0.2191302 -0.9693613 -0.1109995 0.7042272 -0.6138603 -0.3567067 0.7853299 -0.4743354 -0.3978227 0.7042745 -0.6137834 -0.3567457 0.4875426 -0.8374442 -0.2469605 0.6043688 -0.7355398 -0.3061366 0.6044426 -0.7354637 -0.3061736 0.8795567 -0.1669387 -0.4455464 0.8795521 -0.1669684 -0.4455441 0.8436706 -0.3249371 -0.4273592 0.7852823 -0.4744471 -0.3977835 0.8436394 -0.3250589 -0.4273284 0.7840847 0.4768722 -0.397246 0.8435829 0.3251217 -0.4273918 0.8436226 0.3249726 -0.4274269 0.8795273 0.1668474 -0.4456385 0.8799702 0.1642256 -0.445738 0.8920711 -3.0519e-5 -0.4518952 0.60321 0.7367311 -0.3055572 0.4887052 0.8365945 -0.2475419 0.6044404 0.7354915 -0.3061114 0.7853742 0.4742947 -0.3977838 0.7042976 0.6137768 -0.3567114 0.7042635 0.6138347 -0.3566791 0.2190032 0.9694007 -0.1109055 0.2188813 0.9694316 -0.110875 0.07434546 0.9965223 -0.03763049 0.3581998 0.9158403 -0.1814651 0.4871785 0.8376919 -0.2468395 0.3586038 0.9156451 -0.1816518 -0.07330584 0.9966177 0.0371412 -0.07391661 0.9965623 0.0374161 -0.2188529 0.9694415 0.1108456 -0.2194314 0.9692828 0.1110891 -0.3586589 0.9156302 0.1816184 -0.4885233 0.8367186 0.2474814 -0.3578077 0.9160354 0.1812538 -0.4876708 0.8373326 0.2470857 -0.6043188 0.7355532 0.3062033 -0.6044392 0.7354291 0.3062635 -0.7028661 0.6157327 0.3561636 -0.7842752 0.4764919 0.3973258 -0.7042042 0.6138668 0.356741 -0.7853032 0.4744293 0.3977637 -0.8436648 0.3249959 0.4273259 -0.8435909 0.3252163 0.4273042 -0.8800004 0.1639814 0.4457684 -0.879974 0.1641597 0.445755 0.8437586 0.3246305 -0.4274185 0.8799079 0.1645612 -0.4457374 0.8437612 0.324662 -0.4273893 0.8890235 0.08264589 -0.4503409 0.879899 0.1646205 -0.4457329 0.8890257 0.08261555 -0.450342 0.7039896 0.6142017 -0.356588 0.6041687 0.7357394 -0.3060519 0.6043688 0.7355398 -0.3061366 0.704115 0.6140215 -0.3566507 0.7846285 0.4758006 -0.3974568 0.7845576 0.4759472 -0.3974213 0.2192804 0.9693203 -0.1110594 0.3583242 0.9157853 -0.1814968 0.2189742 0.9694072 -0.1109062 0.3586304 0.9156351 -0.1816499 0.4881812 0.8369823 -0.2472645 0.4879119 0.8371746 -0.2471452 -0.2189742 0.9694072 0.1109062 -0.2187026 0.9694822 0.1107857 -0.07367187 0.996585 0.03729373 0.07364153 0.9965873 -0.03729379 -0.07333618 0.9966155 0.03714114 0.07397717 0.9965556 -0.03747683 -0.4879119 0.8371746 0.2471452 -0.6041687 0.7357394 0.3060519 -0.6040403 0.7358843 0.3059571 -0.3580793 0.9159054 0.1813743 -0.3583242 0.9157853 0.1814968 -0.4876977 0.8373264 0.2470534 -0.703961 0.6142339 0.3565889 -0.7845094 0.4760466 0.3973973 -0.7038983 0.614324 0.3565576 -0.8437101 0.324788 0.4273943 -0.7845576 0.4759472 0.3974213 -0.8437612 0.324662 0.4273893 -0.8799066 0.1646525 0.4457062 -0.8799148 0.1645568 0.4457254 -0.8890257 0.08261555 0.450342 -0.8890235 0.08264589 0.4503409 0 1 0 0 1 0 0 1 0 0 1 0 0.4518877 -5.32094e-6 0.892075 0.4518874 3.5208e-6 0.892075 0.4518879 0 0.8920748 0.4518878 0 0.8920748 0 1 0 0 1 0 -0.4518879 7.89945e-6 -0.8920747 -0.4518876 0 -0.8920749 -0.4518875 8.33384e-7 -0.892075 -0.4518876 -5.32094e-6 -0.892075 -2.65846e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.66239e-6 1 5.11829e-7 0 1 0 0 1 0 0 1 0 -2.76936e-7 1 1.21265e-7 0 1 0 -1.63453e-7 1 0 0 1 0 -1.24869e-7 1 0 -0.4518867 1.38104e-6 -0.8920754 -0.4518783 0 -0.8920797 -0.451879 7.13275e-6 -0.8920793 -0.451875 1.56775e-5 -0.8920812 -0.4518924 9.34328e-6 -0.8920725 -0.4518905 5.80295e-6 -0.8920735 -0.4518935 1.25465e-5 -0.8920719 -0.4518838 -1.84971e-5 -0.8920769 -0.4518845 -1.0325e-5 -0.8920764 -0.4518967 1.1643e-5 -0.8920703 -0.45189 -5.98023e-6 -0.8920737 -0.4518958 -8.60033e-6 -0.8920707 -0.4518826 1.47203e-6 -0.8920774 -0.4518903 -1.16545e-5 -0.8920736 -0.4518837 -1.24751e-5 -0.8920769 -0.451883 1.64806e-5 -0.8920773 -0.4518897 -1.81515e-6 -0.8920739 -0.451894 -3.59468e-6 -0.8920717 -0.4518884 2.4264e-6 -0.8920746 -0.4518832 -5.56397e-6 -0.8920772 -0.4518896 1.79534e-5 -0.8920739 -0.4518898 -1.01738e-5 -0.8920739 -0.4518887 1.62984e-5 -0.8920744 -0.4518813 -1.50501e-5 -0.8920781 -0.4518896 -1.45147e-6 -0.8920738 -0.4518831 0 -0.8920772 -0.4518782 -7.70733e-6 -0.8920797 -0.4518914 2.28507e-6 -0.892073 -0.4518957 -1.21758e-6 -0.8920708 -0.4518809 -1.02786e-5 -0.8920783 -0.4518872 1.089e-5 -0.8920751 -0.4518879 -1.64362e-5 -0.8920748 -0.4518849 -1.47125e-6 -0.8920763 -0.4518832 -1.06095e-5 -0.8920772 -0.4518834 -1.13356e-5 -0.8920771 -0.4518834 1.28946e-5 -0.8920772 -0.4518848 1.82432e-5 -0.8920763 -0.4518821 -1.19781e-6 -0.8920777 -0.4518969 -4.85278e-6 -0.8920702 -0.4518938 -1.81101e-5 -0.8920718 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.4518925 0 0.8920724 0.4518899 0 0.8920738 -0.892075 0 0.4518877 -0.8920753 0 0.4518869 -0.4518908 0 -0.8920733 -0.4518944 0 -0.8920714 -0.8920748 0 0.4518879 -0.8920756 0 0.4518862 0.4518938 0 0.8920719 0.4518936 0 0.8920719 -0.8920745 -1.54821e-6 0.4518883 -0.8920745 0 0.4518884 -0.8920745 3.00832e-7 0.4518884 -0.8920747 1.16189e-6 0.4518881 0.4518877 0 0.8920749 0.4518887 0 0.8920744 -0.8920746 0 0.4518882 -0.8920739 0 0.4518895 -0.8920744 0 0.4518887 -0.8920745 4.00608e-7 0.4518884 -0.8920746 0 0.4518883 -0.4518899 0 -0.8920738 -0.4518893 3.90226e-6 -0.8920741 -0.4518871 -4.86503e-7 -0.8920753 -0.4518808 5.30152e-6 -0.8920783 -0.4518866 0 -0.8920754 -0.4518914 -4.50369e-6 -0.8920731 -0.4518845 -4.34053e-6 -0.8920766 -0.4518784 2.68829e-6 -0.8920797 -0.4518891 0 -0.8920742 -0.4519029 0 -0.8920672 -0.4518706 -4.26744e-6 -0.8920835 -0.4518988 -2.65479e-6 -0.8920693 -0.4518843 0 -0.8920767 -0.4518762 3.64311e-6 -0.8920808 -0.4518866 9.24199e-7 -0.8920754 -0.4518929 0 -0.8920723 -0.4518875 2.08351e-7 -0.892075 -0.4518859 -1.79599e-6 -0.8920758 -0.4518824 -5.58696e-7 -0.8920776 -0.4519003 4.19175e-6 -0.8920685 -0.4518824 4.36703e-6 -0.8920776 -0.4518843 0 -0.8920765 -0.4518807 3.97209e-6 -0.8920784 -0.4518885 -2.56252e-7 -0.8920744 -0.4518873 9.14592e-7 -0.8920751 0.8920746 0 -0.4518883 0.8920745 0 -0.4518884 -0.4518878 0 -0.8920748 0.8920746 0 -0.4518884 0.8920745 0 -0.4518885 0.4518877 0 0.8920749 0.4518876 0 0.892075 0.8920747 4.10422e-6 -0.451888 0.8920746 -9.6471e-7 -0.4518884 0.8920745 7.53832e-7 -0.4518883 0.4518933 0 0.892072 0.4518935 -3.63311e-6 0.892072 0.4518702 -1.54367e-5 0.8920838 0.4518787 3.93643e-6 0.8920794 0.4518418 1.9183e-5 0.8920981 0.4519296 1.10811e-5 0.8920537 0.4518899 -4.01823e-5 0.8920737 0.4518978 3.40759e-5 0.8920698 0.4518909 4.83611e-6 0.8920733 0.4518905 0 0.8920734 0.4518659 3.21414e-5 0.8920859 0.4518849 -9.9657e-6 0.8920763 0.451923 -1.79249e-5 0.892057 0.4519037 8.62807e-6 0.8920667 0.4518864 0 0.8920755 0.4519035 -2.01204e-5 0.8920668 0.4518846 -4.5915e-6 0.8920764 0.4518887 -1.31915e-5 0.8920744 0.4518966 -6.40599e-6 0.8920703 0.4518854 -1.70381e-5 0.8920761 0.4518631 -4.01835e-5 0.8920874 0.4518862 1.47351e-5 0.8920757 0.4518898 0 0.8920738 0.4518951 0 0.8920711 -0.8920748 0 0.4518879 -0.8920741 0 0.4518893 -0.8920746 -1.90331e-6 0.4518882 -0.8920747 5.18042e-7 0.4518882 -0.8920745 0 0.4518883 -0.4518895 0 -0.892074 -0.4519006 0 -0.8920683 -0.8920732 0 0.4518911 -0.8920677 0 0.4519019 -0.8836813 0.1366952 0.4476851 -0.8586744 0.2708535 0.4351053 -0.8821741 0.1490839 0.4467024 0.4460077 0.8660435 -0.2259336 0.325793 0.9309287 -0.1650176 -0.8038994 0.4336436 0.4070616 -0.8211495 0.3907067 0.4160072 -0.8211612 0.3907733 0.4159215 0.5561529 0.7818735 -0.2817234 -0.8526008 0.2945465 0.4316414 -0.8896269 0.07480186 0.4505205 -0.8899716 0.06857669 0.4508302 -0.5563018 0.7817462 0.2817826 -0.6537835 0.6803657 0.3311644 -0.7372322 0.5630567 0.3734382 -0.8035468 0.4342614 0.4070991 -0.19874 0.9748701 0.1006518 -0.06695878 0.9971795 0.03390663 -0.4460439 0.8660241 0.2259365 -0.3259795 0.9308469 0.1651108 0.06695878 0.9971795 -0.03390663 0.1982516 0.9749916 -0.1004381 0.06631737 0.9972327 -0.03360116 0.6541016 0.6799824 -0.3313235 0.6537835 0.6803657 -0.3311644 0.8525399 0.2945665 -0.4317481 0.8821365 0.1490879 -0.4467753 0.8587053 0.2708536 -0.4350444 0.73688 0.563624 -0.3732773 0.7372322 0.5630567 -0.3734382 0.8034217 0.4343513 -0.4072501 0.8211206 0.3907991 -0.4159774 0.8211532 0.3908916 -0.415826 0.8038799 0.4335885 -0.4071587 0.858847 0.2708293 -0.4347797 0.85221 0.2949348 -0.4321478 0.883743 0.1366952 -0.4475633 0.8819782 0.1491174 -0.4470777 0.889489 0.07474207 -0.4508026 0.8899716 0.06857669 -0.4508302 0.8895941 0.0748322 -0.4505804 0.8836897 0.1367269 -0.4476588 -0.654088 0.6799988 0.3313167 -0.8523369 0.2949669 0.4318755 -0.8587589 0.2708609 0.434934 -0.8837085 0.1367251 0.4476223 -0.8820667 0.1491474 0.446893 -0.8895568 0.07483422 0.4506534 0.4518873 0 0.892075 0.4518885 7.90304e-6 0.8920745 0.4518879 -1.80504e-6 0.8920748 0.4518878 -6.28838e-6 0.8920749 -0.8920747 0 0.4518882 -0.8920747 0 0.4518881 -0.4518879 6.35357e-6 -0.8920748 -0.4518876 -8.6395e-6 -0.8920749 -0.4518874 1.6764e-6 -0.8920751 -0.4518874 0 -0.892075 -0.008857727 -0.999858 0.0143404 0.01254326 -0.9998927 -0.007568657 -0.006592035 -0.9999759 0.002197325 -0.00439471 -0.9999813 0.004272639 0.025972 -0.9996327 -0.007751882 0.04684686 -0.9982505 -0.03607362 0.006805658 -0.9974476 -0.07107836 -0.007722079 -0.9998701 0.01415026 0.5156204 -0.8180255 -0.2548922 -0.01959335 -0.9997494 0.01083433 -0.0855748 -0.994609 0.05856561 -0.09988808 -0.9937236 0.05035603 0.02542221 -0.999676 -0.001312255 0.03201389 -0.9994514 -0.008484125 -0.005218684 -0.9999752 0.004730343 -0.01880586 -0.9997755 0.009766221 -0.002685129 -0.9999926 0.002768099 -0.01922672 -0.999791 0.006958246 -0.01434385 -0.9998915 0.003357052 -0.01120042 -0.9999248 0.005005061 -0.01878386 -0.999776 0.009749472 -0.004652798 -0.999985 0.002895414 -0.004789531 -0.9999843 0.002925097 0.04080408 -0.9990746 -0.01361149 -0.01068174 -0.9999073 0.008453845 0.05118 -0.9986667 -0.006744623 0.006683588 -0.9999777 0 -0.01025432 -0.9999226 0.007049858 -0.03225874 -0.9993502 0.01608359 -0.02127158 -0.9996435 0.01614439 0.01535236 -0.9998336 -0.009860873 -0.03628712 -0.9991635 0.01886075 -0.003055632 -0.9999938 0.00180763 -0.01217705 -0.9998958 0.007751822 0.02548319 -0.9996748 0.00100708 0.02066147 -0.9997792 0.003845393 0.03344887 -0.9994392 -0.001556456 0.01858597 -0.9997987 0.007568657 -0.01339763 -0.9997867 0.01571702 0.02145504 -0.9997201 0.009979784 -0.008331716 -0.9998432 0.01562589 0.002655088 -0.9999507 0.009582877 -0.04577851 -0.998491 0.0303359 4.27267e-4 -0.9999889 -0.004699885 -0.03631812 -0.9991759 0.01812851 -0.003396332 -0.9999912 0.002468645 -0.002639353 -0.9999953 0.001599133 -0.003647685 -0.9999911 0.002145111 -0.002055704 -0.9999963 0.001819312 0.001861631 -0.9999983 0 0.002014279 -0.999998 -1.83116e-4 0.001220762 -0.9999992 5.49349e-4 -0.002067625 -0.999997 0.001356363 -0.002334833 -0.9999963 0.001462757 -0.001709342 -0.9999973 0.001582741 -0.001819729 -0.9999976 0.001262187 -0.001857876 -0.9999976 0.001278817 -0.001556456 -0.9999975 0.001617491 0.001831114 -0.999998 -8.85062e-4 9.76621e-4 -0.9999993 -7.93505e-4 0.01034599 -0.999902 -0.009430408 0.00238049 -0.9999969 -7.32464e-4 0.001831114 -0.999998 -9.15581e-4 -0.001686573 -0.9999974 0.001554608 -0.00183326 -0.999997 0.001663327 -0.00276196 -0.9999938 0.002200365 -0.00232762 -0.9999954 0.001976728 -0.005956649 -0.9999776 0.003087222 -0.005171418 -0.9999822 0.002988934 0.02334707 -0.9995625 -0.01815885 0.01263475 -0.9997957 -0.01577818 0.02090555 -0.9997747 0.003692805 0.04446667 -0.9987766 -0.02163821 0.01333689 -0.9999011 0.004486322 -0.1877059 -0.9775899 0.09531319 0.006378531 -0.9998756 -0.01443564 0.003692805 -0.9999267 -0.01153618 -0.006390929 -0.9999703 0.004324495 -0.007115244 -0.9999623 0.004992842 -0.005326092 -0.9999801 0.003394305 -0.004340946 -0.9999873 0.002605199 -0.004742085 -0.9999846 0.002909421 -0.004091084 -0.9999887 0.002428233 0.01757913 -0.9998164 0.007629811 0.04373306 -0.9987803 -0.02291941 0.02905404 -0.9994656 -0.01498478 -0.008697807 -0.999947 0.00552386 0.1537857 -0.9819783 -0.1098577 -0.05601519 -0.9953588 -0.07825124 -0.002471983 -0.9997056 0.02414035 -0.004666805 -0.999985 0.002899348 0.06293332 -0.9974239 -0.03442484 -0.001861631 -0.9999932 0.003204464 -0.04211598 -0.9988204 0.02417087 -0.02587985 -0.9994578 0.02035593 2.74669e-4 -0.9999484 0.01016271 0.01336729 -0.9998946 0.005676507 -5.79865e-4 -0.9999013 0.0140388 0.0114445 -0.9999166 0.006012141 0 1 0 0 1 -1.50624e-6 -2.90981e-7 1 2.57199e-6 0 1 0 0 1 0 -2.22977e-7 1 0 0 1 4.69287e-7 0 1 0 1.28702e-7 1 0 -1.24098e-7 1 0 0 1 -3.29257e-7 -1.88674e-7 1 -1.1688e-6 -1.4704e-7 1 7.49826e-7 -1.5702e-7 1 0 0 1 0 -4.77696e-7 1 -2.14494e-7 0 1 -2.34643e-7 0 1 0 0 1 0 0 1 0 -1.44838e-7 1 0 0 1 8.04097e-7 0 1 0 0 1 -5.9585e-7 0 1 -2.23734e-7 0 1 0 0 1 0 0 1 0 0 1 0 -8.3833e-7 1 -5.85383e-7 0 1 -2.10303e-7 0 1 0 0 1 4.02054e-7 0 1 -2.17137e-6 0.926297 -8.24026e-4 -0.3767936 0.8516709 -4.57789e-4 -0.5240769 0.9177804 1.83117e-4 -0.3970884 0.7655756 3.66231e-4 -0.643346 0.852646 2.74673e-4 -0.5224891 0.6571423 4.27271e-4 -0.7537665 0.7538796 -5.7986e-4 -0.6570124 0.6354471 -8.85066e-4 -0.772144 0.5384819 6.71424e-4 -0.8426368 0.4997169 -0.00112915 -0.8661881 0.4098671 8.54525e-4 -0.912145 0.2734833 9.76617e-4 -0.9618763 0.3502635 -0.001220703 -0.9366504 0.1912657 -0.001190245 -0.9815376 0.1289424 9.46087e-4 -0.9916517 0.0270707 -0.001098692 -0.999633 -0.02063113 7.62986e-4 -0.999787 -0.1694102 5.18821e-4 -0.9855455 -0.1377629 -9.15571e-4 -0.9904648 -0.298963 -6.10378e-4 -0.9542646 -0.3143136 1.83113e-4 -0.9493193 -0.3769721 -4.27268e-4 -0.9262246 -0.3839327 0 -0.9233612 0.9650007 5.18818e-4 -0.262247 0.9757101 -0.001190185 -0.2190625 0.9927551 8.24015e-4 -0.1201536 0.999378 0.001098632 0.03524953 0.9984605 -0.001312315 -0.05545306 0.9813527 0.001281797 0.1922115 0.9939658 -0.001190185 0.1096844 0.9623949 -0.001129209 0.2716521 0.9395468 0.00112915 0.3424191 0.8758932 9.15568e-4 0.4825043 0.9044983 -0.001220762 0.4264757 0.7941167 7.62987e-4 0.6077648 0.8219763 -0.001098692 0.5695207 0.717046 -8.85054e-4 0.6970255 0.6946849 5.18831e-4 0.719314 0.5796521 1.83116e-4 0.814864 0.5924929 -5.79858e-4 0.8055755 0.5237381 -3.96748e-4 0.8518793 0.5173876 0 0.8557512 -0.6002832 0 -0.7997876 -0.5281899 0 -0.8491263 -0.5279591 0 -0.8492699 -0.9195408 6.10382e-5 -0.3929945 -0.837341 6.10374e-5 -0.5466811 -0.837415 3.05192e-5 -0.5465675 -0.7298027 3.05191e-5 -0.6836578 -0.5998829 3.05191e-5 -0.8000879 -0.7297143 3.05192e-5 -0.6837524 -0.9985017 3.05194e-5 -0.05472117 -0.9928803 6.10383e-5 0.1191163 -0.9984884 6.10379e-5 -0.0549646 -0.9195944 3.05189e-5 -0.3928693 -0.9738374 3.05192e-5 -0.227246 -0.9737953 6.10377e-5 -0.2274264 -0.8921513 0 0.4517369 -0.8003881 0 0.5994823 -0.9571593 3.05187e-5 0.2895618 -0.9928289 3.05195e-5 0.1195448 -0.9569832 0 0.2901438 -0.3929319 -3.0519e-5 0.9195676 -0.5466243 -3.05189e-5 0.837378 -0.5465675 -3.05192e-5 0.837415 -0.6837524 -3.05192e-5 0.7297143 -0.6842091 0 0.729286 -0.8000879 0 0.5998829 -0.05481243 -3.05192e-5 0.9984967 -0.227275 -3.0519e-5 0.9738307 -0.227246 -3.05192e-5 0.9738374 -0.3928693 -3.05189e-5 0.9195944 -0.05472117 -3.05194e-5 0.9985017 0.1192668 -3.05186e-5 0.9928624 0.1195748 -3.05194e-5 0.9928252 0.2901717 -3.05187e-5 0.9569746 0.3729372 -3.05186e-5 0.9278567 0.2901438 0 0.9569832 0.3723639 0 0.9280869 -0.1200931 -0.9908976 0.06082475 0.02734506 -0.9995304 -0.01382511 0.02704018 -0.9995409 -0.01367264 -0.8908603 0.05227965 0.4512593 -0.8908588 0.05231004 0.4512585 -0.871021 0.2159851 0.4412176 0.1734409 -0.9809197 -0.08783441 0.173745 -0.9808523 -0.08798646 0.3153882 -0.9354218 -0.1597388 0.3150835 -0.9355453 -0.1596171 0.4484151 -0.8644801 -0.2271526 0.448152 -0.864655 -0.2270058 0.5690092 -0.7701645 -0.288228 0.5692188 -0.769976 -0.2883175 0.6744749 -0.6544848 -0.3416627 0.674332 -0.6546773 -0.341576 0.7613595 -0.5211438 -0.3856696 0.7612662 -0.5213258 -0.3856077 0.8274394 -0.3737394 -0.4191216 0.8274383 -0.3737084 -0.4191516 0.8710153 -0.2160142 -0.4412147 0.871021 -0.2159851 -0.4412176 0.8908574 -0.0523405 -0.4512578 0.8908588 -0.05231004 -0.4512585 -0.1197561 -0.9909478 0.0606715 -0.2639324 -0.9552291 0.1337058 -0.2636515 -0.9553284 0.1335501 -0.400592 -0.8935039 0.2029206 -0.4003533 -0.8936381 0.2028012 -0.5261192 -0.8075667 0.2665235 -0.5263257 -0.807403 0.2666115 -0.6377123 -0.6992709 0.3230221 -0.6375527 -0.6994463 0.3229575 -0.7316894 -0.5720758 0.3706209 -0.7315771 -0.5722361 0.3705953 -0.8056452 -0.4294048 0.4081024 -0.8057093 -0.4292538 0.4081345 -0.8577383 -0.2747631 0.4344999 -0.8577201 -0.2748586 0.4344756 -0.8863936 -0.1127371 0.4489954 -0.8863874 -0.1127974 0.4489923 -0.8274394 0.3737394 0.4191216 -0.5690298 0.7701511 0.288223 -0.674332 0.6546773 0.341576 -0.5690092 0.7701645 0.288228 -0.7612662 0.5213258 0.3856077 -0.3150835 0.9355453 0.1596171 -0.1734409 0.9809197 0.08783441 -0.448152 0.864655 0.2270058 0.2639324 0.9552291 -0.1337058 0.1200931 0.9908976 -0.06082475 -0.02704018 0.9995409 0.01367264 0.6377123 0.6992709 -0.3230221 0.5263257 0.807403 -0.2666115 0.400592 0.8935039 -0.2029206 0.8056987 0.4292787 -0.4081291 0.7316894 0.5720758 -0.3706209 0.7316753 0.5720887 -0.3706292 0.8577383 0.2747631 -0.4344999 0.8057093 0.4292538 -0.4081345 0.8577455 0.2747349 -0.4345036 0.8863936 0.1127371 -0.4489954 -0.4518821 1.28895e-5 -0.8920778 -0.4519019 5.52555e-6 -0.8920678 -0.4519035 7.36515e-6 -0.892067 -0.4518831 7.36551e-6 -0.8920772 -0.4518889 -3.68282e-6 -0.8920742 -0.4519031 2.20972e-5 -0.892067 -0.4518841 2.20977e-5 -0.8920767 -0.4518294 -3.68323e-5 -0.8921045 -0.4518909 -2.76339e-5 -0.8920733 -0.4519168 2.94658e-5 -0.8920602 -0.4518764 3.31636e-5 -0.8920806 -0.4518924 1.38102e-6 -0.8920725 -0.451863 -1.10511e-5 -0.8920874 -0.4518742 0 -0.8920817 -0.4518872 7.36753e-6 -0.8920751 -0.4518809 7.36766e-6 -0.8920783 -0.4518691 -7.36759e-6 -0.8920844 -0.4519232 7.36751e-6 -0.892057 -0.4518782 -3.3154e-5 -0.8920797 -0.4518936 7.36751e-6 -0.8920719 -0.451889 -5.52558e-6 -0.8920742 -0.4519016 5.52555e-6 -0.8920679 -0.4518628 -1.47355e-5 -0.8920874 -0.4519148 1.47348e-5 -0.8920612 -0.4518617 0 -0.892088 -0.4518855 5.52562e-6 -0.892076 -0.451884 0 -0.8920768 -0.4518815 1.10484e-5 -0.892078 -0.4518879 7.36742e-6 -0.8920748 -0.4519181 5.52548e-6 -0.8920596 -0.4518772 -7.37686e-6 -0.8920801 -0.4518893 -2.21027e-5 -0.8920742 -0.4519008 3.31543e-5 -0.8920682 -0.4518885 -8.28525e-6 -0.8920745 -0.4518778 0 -0.8920798 -0.4518942 -5.53249e-6 -0.8920716 -0.4518892 2.5319e-6 -0.8920741 -0.4518861 2.76207e-6 -0.8920757 -0.4519107 1.47413e-5 -0.8920633 -0.45187 -9.66644e-6 -0.8920838 -0.451844 -3.68527e-5 -0.892097 -0.4518846 1.93368e-5 -0.8920764 -0.4518671 2.76256e-6 -0.8920853 -0.4518932 -1.38133e-5 -0.892072 -0.4519035 3.31543e-5 -0.8920669 -0.4518821 2.21049e-5 -0.8920777 -0.4518912 5.52648e-6 -0.8920732 -0.4518932 5.52681e-6 -0.8920722 -0.4518964 1.65813e-5 -0.8920705 -0.4518658 0 -0.892086 -0.4518902 -8.29177e-6 -0.8920736 -0.4519068 1.4735e-5 -0.8920652 -0.4518938 -2.21018e-5 -0.8920717 -0.4518788 3.68339e-5 -0.8920794 -0.45189 -7.36553e-6 -0.8920738 -0.4518863 -7.36553e-6 -0.8920757 -0.4519113 2.21021e-5 -0.8920629 -0.4518716 -2.94705e-5 -0.8920831 -0.4518951 2.21026e-5 -0.8920711 -0.4518589 0 -0.8920894 -0.4518665 5.52566e-6 -0.8920856 -0.4518715 0 -0.8920831 -0.4518797 0 -0.892079 -0.4519014 1.65766e-5 -0.8920679 -0.4518681 5.52571e-6 -0.8920849 -0.4519219 5.5256e-6 -0.8920575 -0.4518676 -1.65774e-5 -0.8920851 -0.4519273 -1.10512e-5 -0.8920549 -0.4518683 2.21027e-5 -0.8920847 -0.4518768 3.68374e-5 -0.8920803 -0.4518864 -3.68382e-5 -0.8920756 -0.4518958 5.52561e-6 -0.8920708 -0.451895 1.10513e-5 -0.8920713 -0.4518834 2.11818e-5 -0.892077 -0.4518907 -1.47349e-5 -0.8920733 0.4519724 -1.47349e-5 0.892032 0.4519017 -5.52555e-6 0.8920677 0.4517588 0 0.8921402 0.4517302 1.47379e-5 0.8921546 0.4519303 0 0.8920533 0.4518975 1.65792e-5 0.8920699 0.4519 -2.21021e-5 0.8920687 0.4518313 -3.86804e-5 0.8921034 0.4518278 1.47343e-5 0.8921052 0.4518678 2.76284e-5 0.892085 0.451906 2.9467e-5 0.8920657 0.4519125 2.94646e-5 0.8920623 0.451884 -2.94656e-5 0.8920767 0.4518846 1.10482e-5 0.8920764 0.4518978 -2.2102e-5 0.8920698 0.4518326 9.67013e-6 0.8921028 0.4519446 -2.76277e-6 0.8920461 0.4518911 -2.94699e-5 0.8920732 0.4518984 0 0.8920695 0.4519405 -1.65765e-5 0.8920481 0.4518528 -1.47356e-5 0.8920925 0.4518396 1.47357e-5 0.8920993 0.4519006 7.36738e-6 0.8920683 0.4518914 -1.47349e-5 0.892073 0.4519082 -2.21025e-5 0.8920645 0.4518957 -1.47351e-5 0.8920708 0.4519046 6.07815e-5 0.8920663 0.4519257 0 0.8920557 0.4518878 2.94697e-5 0.8920748 0.4519004 -2.21021e-5 0.8920685 0.4518693 -1.10514e-5 0.8920842 0.4518367 2.21033e-5 0.8921008 0.4518761 5.52578e-6 0.8920808 0.4518681 -1.10514e-5 0.8920848 0.4518938 -2.21024e-5 0.8920719 0.4518787 1.10511e-5 0.8920794 0.4518364 2.21033e-5 0.8921008 0.4518691 2.94704e-5 0.8920843 0.4518686 -2.94607e-5 0.8920846 0.4519208 2.76289e-6 0.8920581 0.4518299 -1.4731e-5 0.8921042 0.4518809 -5.5253e-6 0.8920783 0.4518848 0 0.8920764 0.4518708 1.10503e-5 0.8920835 0.4518934 -3.31495e-5 0.892072 0.4518634 -1.10499e-5 0.8920872 0.4519535 -1.10493e-5 0.8920415 0.4518836 0 0.892077 0.451965 0 0.8920357 0.4519189 1.10494e-5 0.892059 0.4519356 -4.42034e-5 0.8920506 0.4519185 0 0.8920593 0.4519079 -2.94748e-5 0.8920646 0.4518993 4.42171e-5 0.8920691 0.4518691 -5.90139e-5 0.8920844 0.4519037 2.94618e-5 0.8920668 0.4519144 0 0.8920614 0.451895 4.42052e-5 0.8920711 0.4517779 -1.47361e-5 0.8921306 0.4518003 0 0.8921192 0.4518666 -3.3154e-5 0.8920856 0.4518627 -2.21025e-5 0.8920875 0.4518576 0 0.8920901 0.4518843 -2.21024e-5 0.8920767 0.451879 0 0.8920792 0.4519482 0 0.8920443 0.4518478 1.10514e-5 0.8920952 0.4518849 2.2103e-5 0.8920763 0.4519447 1.10511e-5 0.892046 0.4518331 -2.7629e-5 0.8921026 0.4518885 -5.89394e-5 0.8920745 0.4518513 2.94711e-5 0.8920933 0.4519045 0 0.8920663 0.4518929 -2.21026e-5 0.8920723 0.4519422 -4.32831e-5 0.8920474 0.4518439 1.10515e-5 0.892097 -0.8908574 0.0523405 0.4512578 -0.7316753 -0.5720887 0.3706292 -0.8577455 -0.2747349 0.4345036 -0.5263387 -0.8073925 0.266618 -0.6376987 -0.6992865 0.3230152 -0.120063 -0.9909013 0.06082499 -0.2639335 -0.955233 0.1336758 0.4481763 -0.8646431 -0.2270027 0.1734114 -0.9809249 -0.08783489 0.8710267 -0.215956 -0.4412205 0.82743 -0.3737657 -0.4191168 0.8057734 0.4291028 -0.4081665 0.8577608 0.2746995 -0.4344959 0.8577272 0.2748304 -0.4344792 0.8863905 0.1127672 -0.4489938 0.6375527 0.6994463 -0.3229575 0.5265538 0.8072116 -0.2667409 0.6378837 0.6990749 -0.3231077 0.8056452 0.4294048 -0.4081024 0.7316041 0.5722028 -0.3705936 0.731819 0.5718681 -0.3706857 0.2642341 0.9551246 -0.1338566 0.2636515 0.9553284 -0.1335501 0.1203663 0.9908552 -0.06097662 0.4008673 0.8933527 -0.203043 0.5261235 0.8075731 -0.2664952 0.4003533 0.8936381 -0.2028012 -0.02673441 0.9995512 0.01351982 -0.02734506 0.9995304 0.01382511 -0.1731364 0.9809844 0.08771264 0.1197561 0.9909478 -0.0606715 -0.173745 0.9808523 0.08798646 -0.3148353 0.9356552 0.1594624 -0.4479558 0.8647824 0.2269077 -0.3153882 0.9354218 0.1597388 -0.4484182 0.8644861 0.2271236 -0.5688492 0.770307 0.2881632 -0.5692188 0.769976 0.2883175 -0.6742287 0.6548185 0.3415091 -0.761201 0.521445 0.3855751 -0.6744749 0.6544848 0.3416627 -0.7613595 0.5211438 0.3856696 -0.8274015 0.3738276 0.4191179 -0.8274383 0.3737084 0.4191516 -0.8710153 0.2160142 0.4412147 + + + + + + + + + + + + + + +

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

+
+ + + +

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

+
+ + + +

376 236 377 237 378 238 379 239 380 239 381 240 382 241 378 238 383 242 377 237 383 242 378 238 384 243 385 244 382 241 382 241 383 242 384 243 385 244 386 245 387 246 386 245 385 244 384 243 388 247 387 246 389 248 386 245 389 248 387 246 390 249 391 250 388 247 388 247 389 248 390 249 391 250 392 251 393 252 392 251 391 250 390 249 394 253 393 252 395 254 392 251 395 254 393 252 396 255 397 256 394 253 394 253 395 254 396 255 398 257 397 256 396 255 398 257 399 258 397 256 377 237 376 236 400 259 401 260 402 261 400 259 400 259 376 236 401 260 402 261 403 262 404 263 403 262 402 261 401 260 405 264 404 263 406 265 403 262 406 265 404 263 407 266 408 267 405 264 405 264 406 265 407 266 408 267 409 268 410 269 409 268 408 267 407 266 411 270 410 269 412 271 409 268 412 271 410 269 413 272 414 273 411 270 411 270 412 271 413 272 414 273 415 274 416 275 415 274 414 273 413 272 415 274 380 239 416 275 417 276 418 240 419 277 416 275 380 239 379 239 420 278 421 279 422 280 423 281 424 281 425 279 426 282 427 283 428 283 429 284 430 282 431 285 432 286 433 287 434 288 435 289 436 290 437 290 438 291 439 292 440 293 441 294 442 294 443 292 444 295 445 296 446 296 438 291 446 296 445 296 444 295 447 297 448 295 448 295 445 296 444 295 449 297 447 297 450 298 447 297 449 297 448 295 399 258 451 298 450 298 449 297 450 298 451 298 398 257 451 298 399 258 439 292 443 292 440 293 438 291 440 293 446 296 441 294 433 287 442 294 439 292 441 294 443 292 432 286 434 288 435 289 442 294 433 287 432 286 437 290 436 290 428 283 435 289 434 288 436 290 430 282 427 283 426 282 427 283 437 290 428 283 420 278 429 284 431 285 431 285 430 282 426 282 421 279 425 279 422 280 420 278 422 280 429 284 423 281 417 276 424 281 421 279 423 281 425 279 419 277 418 240 381 240 424 281 417 276 419 277 379 239 381 240 418 240 452 299 453 299 454 299 455 300 456 300 457 300 458 301 454 301 459 301 452 302 460 302 461 302 462 303 458 303 463 303 464 304 465 304 460 304 466 305 467 305 464 305 468 306 469 306 466 306 470 307 462 307 471 307 472 308 468 308 473 308 474 309 475 309 471 309 476 310 477 310 478 310 473 311 479 311 480 311 481 312 482 312 457 312 483 313 484 313 485 313 486 314 487 314 488 314 455 315 489 315 490 315 491 316 492 316 493 316 494 317 495 317 496 317 493 318 497 318 498 318 499 319 500 319 501 319 502 320 503 320 504 320 501 321 505 321 506 321 486 322 507 322 508 322 491 323 508 323 509 323 510 324 511 324 512 324 513 325 514 325 515 325 485 326 516 326 517 326 518 327 487 327 490 327 519 328 520 328 482 328 517 329 483 329 485 329 521 330 478 330 520 330 522 331 479 331 523 331 498 332 500 332 499 332 524 333 474 333 525 333 477 334 526 334 525 334 516 335 527 335 517 335 527 336 516 336 512 336 523 337 479 337 484 337 523 338 484 338 483 338 480 339 479 339 522 339 472 340 473 340 480 340 469 341 468 341 472 341 467 342 466 342 469 342 465 343 464 343 467 343 461 344 460 344 465 344 453 345 452 345 461 345 459 346 454 346 453 346 463 347 458 347 459 347 471 348 462 348 463 348 471 349 475 349 470 349 474 350 524 350 475 350 525 351 526 351 524 351 477 352 476 352 526 352 478 353 521 353 476 353 520 354 519 354 521 354 482 355 481 355 519 355 457 356 456 356 481 356 455 357 490 357 456 357 518 358 490 358 489 358 488 359 487 359 518 359 507 360 486 360 488 360 509 361 508 361 507 361 492 362 491 362 509 362 497 363 493 363 492 363 500 364 498 364 497 364 506 365 499 365 501 365 502 366 506 366 505 366 503 367 496 367 504 367 503 368 502 368 505 368 494 369 513 369 495 369 503 370 494 370 496 370 515 371 514 371 510 371 495 372 513 372 515 372 512 373 511 373 527 373 510 374 514 374 511 374 528 375 529 375 530 375 531 376 532 376 533 376 534 377 530 377 535 377 536 378 537 378 528 378 538 379 539 379 534 379 536 380 540 380 541 380 542 381 543 381 540 381 543 382 544 382 545 382 539 383 546 383 547 383 545 384 548 384 549 384 550 385 547 385 551 385 552 386 553 386 554 386 555 387 552 387 550 387 556 388 557 388 558 388 559 389 560 389 561 389 562 390 563 390 564 390 565 391 566 391 567 391 568 392 569 392 570 392 571 393 572 393 573 393 574 394 575 394 576 394 577 395 575 395 578 395 579 396 580 396 568 396 581 397 582 397 576 397 572 398 583 398 584 398 577 399 585 399 583 399 586 400 587 400 588 400 589 401 590 401 591 401 592 402 533 402 567 402 593 403 531 403 571 403 594 404 565 404 595 404 596 405 556 405 558 405 597 406 595 406 561 406 580 407 579 407 581 407 557 408 556 408 598 408 599 409 600 409 549 409 559 410 600 410 601 410 596 411 558 411 602 411 602 412 564 412 596 412 554 413 598 413 552 413 554 414 557 414 598 414 555 415 553 415 552 415 551 416 555 416 550 416 546 417 551 417 547 417 538 418 546 418 539 418 535 419 538 419 534 419 529 420 535 420 530 420 537 421 529 421 528 421 541 422 537 422 536 422 543 423 541 423 540 423 543 424 542 424 544 424 545 425 544 425 548 425 549 426 548 426 599 426 600 427 599 427 601 427 559 428 601 428 560 428 561 429 560 429 597 429 595 430 597 430 594 430 565 431 594 431 566 431 567 432 566 432 592 432 533 433 592 433 531 433 593 434 532 434 531 434 573 435 593 435 571 435 584 436 573 436 572 436 585 437 584 437 583 437 578 438 585 438 577 438 574 439 578 439 575 439 582 440 574 440 576 440 579 441 582 441 581 441 603 442 568 442 580 442 570 443 569 443 590 443 568 444 603 444 569 444 589 445 591 445 586 445 570 446 590 446 589 446 587 447 563 447 588 447 591 448 587 448 586 448 564 449 602 449 562 449 563 450 562 450 588 450 604 274 605 451 606 451 607 268 608 271 609 271 610 272 611 274 612 452 613 265 614 453 615 265 616 268 617 454 618 454 619 455 620 455 621 456 622 260 623 262 624 260 625 457 626 244 627 244 628 241 629 241 630 238 631 250 632 252 633 458 634 457 635 459 636 247 637 256 638 256 639 257 640 460 641 461 642 460 643 462 644 463 645 464 646 465 647 466 648 258 649 467 650 468 651 469 652 470 653 471 654 472 655 473 656 474 657 475 658 476 659 477 660 478 661 479 662 480 663 481 662 480 661 479 664 482 665 483 666 484 663 481 663 481 662 480 665 483 667 485 666 484 668 486 665 483 668 486 666 484 667 485 669 487 670 488 669 487 667 485 668 486 671 489 672 490 670 488 670 488 669 487 671 489 673 491 672 490 674 492 671 489 674 492 672 490 673 491 675 493 676 494 675 493 673 491 674 492 677 495 678 496 676 494 676 494 675 493 677 495 605 451 678 496 679 496 677 495 679 496 678 496 606 451 605 451 679 496 664 482 657 475 656 474 661 479 657 475 664 482 658 476 660 478 655 473 655 473 660 478 656 474 649 467 659 477 650 468 650 468 659 477 658 476 653 471 651 469 654 472 653 471 649 467 651 469 652 470 643 462 645 464 652 470 654 472 643 462 644 463 647 466 646 465 645 464 644 463 646 465 639 257 638 256 648 258 647 466 639 257 648 258 640 460 642 460 637 256 637 256 642 460 638 256 631 250 641 461 632 252 632 252 641 461 640 460 635 459 631 250 633 458 634 457 636 247 625 457 635 459 633 458 636 247 627 244 626 244 628 241 634 457 625 457 627 244 629 241 621 456 630 238 626 244 629 241 628 241 619 455 624 260 620 455 621 456 620 455 630 238 614 453 623 262 622 260 622 260 624 260 619 455 617 454 613 265 615 265 613 265 623 262 614 453 616 268 618 454 607 268 617 454 615 265 618 454 609 271 608 271 612 452 616 268 607 268 609 271 610 272 604 274 611 274 608 271 610 272 612 452 606 451 611 274 604 274 2548 1847 2549 1847 2550 1847 2551 1848 2552 1848 2553 1848 2554 1849 2555 1849 2556 1849 2557 1850 2558 1850 2559 1850 2560 1851 2561 1851 2562 1851 2563 1852 2564 1852 2565 1852 2563 1853 2559 1853 2558 1853 2566 1854 2567 1854 2568 1854 2567 1855 2569 1855 2565 1855 2568 1856 2570 1856 2566 1856 2571 1857 2572 1857 2573 1857 2570 1858 2568 1858 2571 1858 2574 1859 2575 1859 2576 1859 2577 1860 2572 1860 2574 1860 2555 1861 2578 1861 2579 1861 2578 1862 2580 1862 2581 1862 2582 1863 2583 1863 2584 1863 2554 1864 2585 1864 2583 1864 2586 1865 2587 1865 2582 1865 2582 1866 2584 1866 2586 1866 2588 1867 2587 1867 2586 1867 2583 1868 2585 1868 2584 1868 2554 1869 2556 1869 2585 1869 2555 1870 2579 1870 2556 1870 2578 1871 2581 1871 2579 1871 2580 1872 2575 1872 2581 1872 2576 1873 2577 1873 2574 1873 2580 1874 2576 1874 2575 1874 2572 1875 2571 1875 2574 1875 2570 1876 2571 1876 2573 1876 2569 1877 2567 1877 2566 1877 2564 1878 2563 1878 2558 1878 2565 1879 2564 1879 2567 1879 2560 1880 2557 1880 2559 1880 2589 1881 2562 1881 2561 1881 2562 1882 2557 1882 2560 1882 2589 1883 2552 1883 2551 1883 2552 1884 2589 1884 2561 1884 2549 1885 2548 1885 2553 1885 2548 1886 2551 1886 2553 1886 2590 1887 2591 1887 2592 1887 2593 1888 2594 1888 2595 1888 2595 1889 2596 1889 2593 1889 2594 1890 2597 1890 2598 1890 2597 1891 2594 1891 2593 1891 2599 1892 2598 1892 2600 1892 2597 1893 2600 1893 2598 1893 2601 1894 2602 1894 2599 1894 2599 1895 2600 1895 2601 1895 2602 1896 2591 1896 2590 1896 2591 1897 2602 1897 2601 1897 2603 1898 2604 1898 2605 1898 2592 1899 2606 1899 2607 1899 2608 1900 2609 1900 2610 1900 2611 1901 2612 1901 2613 1901 2614 1902 2615 1902 2616 1902 2617 1903 2618 1903 2619 1903 2620 1904 2621 1904 2622 1904 2623 1905 2624 1905 2625 1905 2625 1906 2626 1906 2627 1906 2618 1907 2627 1907 2626 1907 2627 1908 2623 1908 2625 1908 2619 1909 2618 1909 2626 1909 2620 1910 2617 1910 2621 1910 2621 1911 2617 1911 2619 1911 2611 1912 2613 1912 2622 1912 2622 1913 2613 1913 2620 1913 2616 1914 2615 1914 2612 1914 2611 1915 2616 1915 2612 1915 2614 1916 2610 1916 2609 1916 2615 1917 2614 1917 2609 1917 2608 1918 2603 1918 2605 1918 2608 1919 2610 1919 2603 1919 2606 1920 2604 1920 2607 1920 2606 1921 2605 1921 2604 1921 2607 1922 2590 1922 2592 1922 2628 1923 2629 1923 2630 1923 2631 1924 2632 1924 2633 1924 2632 1925 2634 1925 2635 1925 2631 1926 2634 1926 2632 1926 2636 1927 2632 1927 2637 1927 2632 1928 2635 1928 2637 1928 2638 1929 2639 1929 2632 1929 2638 1930 2632 1930 2636 1930 2632 1931 2640 1931 2641 1931 2639 1932 2640 1932 2632 1932 2642 1933 2632 1933 2641 1933 2643 1934 2644 1934 2642 1934 2645 1935 2642 1935 2646 1935 2647 1936 2642 1936 2648 1936 2647 1937 2646 1937 2642 1937 2648 1938 2642 1938 2649 1938 2642 1939 2644 1939 2650 1939 2649 1940 2642 1940 2650 1940 2651 1941 2642 1941 2630 1941 2642 1942 2651 1942 2643 1942 2630 938 2642 938 2641 938 2641 1943 2628 1943 2630 1943 2652 1944 2653 1944 2654 1944 2655 1945 2656 1945 2654 1945 2655 1946 2654 1946 2653 1946 2654 1947 2657 1947 2658 1947 2656 1948 2657 1948 2654 1948 2654 1949 2658 1949 2659 1949 2660 1950 2629 1950 2654 1950 2660 1951 2654 1951 2659 1951 2654 1952 2629 1952 2661 1952 2662 1953 2663 1953 2661 1953 2629 1954 2628 1954 2661 1954 2661 1955 2664 1955 2665 1955 2662 1956 2661 1956 2665 1956 2661 1957 2666 1957 2667 1957 2664 1958 2661 1958 2667 1958 2661 1959 2668 1959 2669 1959 2666 1960 2661 1960 2669 1960 2628 1961 2670 1961 2661 1961 2668 315 2661 315 2670 315 2671 1962 2672 1962 2673 1962 2674 1963 2675 1963 2676 1963 2675 1964 2677 1964 2678 1964 2674 1965 2677 1965 2675 1965 2679 1966 2675 1966 2680 1966 2675 1967 2678 1967 2680 1967 2681 1968 2682 1968 2675 1968 2681 1969 2675 1969 2679 1969 2675 1970 2683 1970 2673 1970 2682 1971 2683 1971 2675 1971 2672 1972 2675 1972 2673 1972 2684 1973 2685 1973 2672 1973 2686 1974 2672 1974 2687 1974 2688 1975 2672 1975 2689 1975 2688 1976 2687 1976 2672 1976 2689 1977 2672 1977 2690 1977 2691 1978 2684 1978 2672 1978 2690 1979 2672 1979 2685 1979 2692 1980 2672 1980 2671 1980 2692 1981 2691 1981 2672 1981 2671 1328 2673 1328 2693 1328 2671 1943 2693 1943 2694 1943 2695 1982 2696 1982 2697 1982 2698 1983 2696 1983 2695 1983 2699 1984 2695 1984 2700 1984 2695 1985 2697 1985 2700 1985 2701 1986 2702 1986 2695 1986 2701 1987 2695 1987 2699 1987 2702 1988 2703 1988 2695 1988 2695 1989 2703 1989 2694 1989 2695 1990 2694 1990 2704 1990 2705 1991 2706 1991 2704 1991 2694 1992 2693 1992 2704 1992 2704 1993 2707 1993 2708 1993 2705 1994 2704 1994 2708 1994 2704 1995 2709 1995 2710 1995 2707 1996 2704 1996 2710 1996 2704 1997 2711 1997 2712 1997 2709 1998 2704 1998 2712 1998 2693 1999 2713 1999 2704 1999 2711 2000 2704 2000 2713 2000 2714 2001 2715 2001 2716 2001 2717 2002 2718 2002 2719 2002 2720 2003 2716 2003 2721 2003 2720 2004 2714 2004 2716 2004 2722 2005 2716 2005 2723 2005 2722 2006 2721 2006 2716 2006 2724 2007 2716 2007 2725 2007 2724 2008 2723 2008 2716 2008 2726 2009 2716 2009 2727 2009 2726 2010 2725 2010 2716 2010 2727 2011 2716 2011 2728 2011 2729 2012 2727 2012 2730 2012 2717 2013 2731 2013 2718 2013 2717 2014 2719 2014 2732 2014 2733 2015 2734 2015 2718 2015 2733 2016 2718 2016 2731 2016 2718 2017 2735 2017 2736 2017 2734 2018 2735 2018 2718 2018 2737 2019 2718 2019 2738 2019 2718 2020 2736 2020 2738 2020 2718 2021 2729 2021 2730 2021 2729 2022 2718 2022 2737 2022 2728 2023 2730 2023 2727 2023 2730 2024 2739 2024 2740 2024 2730 2025 2740 2025 2741 2025 2730 2026 2742 2026 2743 2026 2739 2027 2730 2027 2743 2027 2730 2028 2744 2028 2745 2028 2742 2029 2730 2029 2745 2029 2746 2030 2744 2030 2728 2030 2730 2031 2728 2031 2744 2031 2747 2032 2748 2032 2728 2032 2728 2033 2748 2033 2746 2033 2749 2034 2750 2034 2728 2034 2728 2035 2750 2035 2747 2035 2751 2036 2752 2036 2728 2036 2728 2037 2752 2037 2749 2037 2753 2038 2754 2038 2728 2038 2728 2039 2754 2039 2751 2039 2755 2040 2756 2040 2757 2040 2758 2041 2759 2041 2760 2041 2755 2042 2758 2042 2761 2042 2755 2043 2757 2043 2759 2043 2755 2044 2759 2044 2758 2044 2758 2045 2762 2045 2761 2045 2763 2046 2764 2046 2765 2046 2765 2047 2766 2047 2763 2047 2767 2048 2768 2049 2769 2048 2770 2050 2771 2049 2772 2051 2773 2052 2774 2053 2775 523 2776 2052 2777 518 2778 2054 2779 526 2780 521 2781 526 2782 521 2783 2055 2784 522 2785 527 2786 527 2787 2056 2788 2057 2789 524 2790 525 2791 2058 2792 2059 2793 2059 2794 528 2795 528 2796 529 2797 2060 2798 532 2799 2060 2799 2060 2792 2059 2797 2060 2800 2061 2798 532 2801 532 2797 2060 2801 532 2798 532 2800 2061 2802 2061 2803 534 2802 2061 2800 2061 2801 532 2804 2062 2805 2063 2803 534 2803 534 2802 2061 2804 2062 2792 2059 2799 2060 2793 2059 2804 2062 2806 2064 2805 2063 2791 2058 2793 2059 2796 529 2795 528 2794 528 2785 527 2791 2058 2796 529 2795 528 2786 527 2789 524 2787 2056 2794 528 2786 527 2785 527 2790 525 2781 526 2788 2057 2789 524 2788 2057 2787 2056 2782 521 2780 521 2779 526 2779 526 2781 526 2790 525 2774 2053 2784 522 2783 2055 2784 522 2780 521 2782 521 2773 2052 2775 523 2776 2052 2774 2053 2783 2055 2775 523 2778 2054 2777 518 2769 2048 2773 2052 2776 2052 2778 2054 2767 2048 2771 2049 2768 2049 2777 518 2767 2048 2769 2048 2770 2050 2768 2049 2771 2049 2809 2065 2808 2065 2807 2065 2810 2066 2811 2066 2812 2066 2808 2067 2809 2067 2813 2067 2814 2068 2815 2068 2812 2068 2812 2069 2815 2069 2809 2069 2810 2070 2812 2070 2809 2070 2812 2071 2811 2071 2816 2071 2807 2072 2810 2072 2809 2072 2817 2073 2818 2074 2819 2073 2820 2075 2821 2074 2822 2075 2823 791 2824 2076 2825 2076 2826 791 2827 2077 2828 2077 2829 782 2830 2078 2831 782 2832 2078 2833 2079 2834 2079 2835 780 2836 780 2837 777 2838 781 2839 777 2840 781 2841 770 2842 2080 2843 2080 2844 778 2845 778 2846 770 2847 712 2848 712 2849 2081 2847 712 2850 2082 2851 2082 2852 2081 2853 2083 2849 2081 2849 2081 2848 712 2852 2081 2854 2084 2853 2083 2855 2083 2852 2081 2855 2083 2853 2083 2854 2084 2856 2084 2857 2085 2856 2084 2854 2084 2855 2083 2858 2085 2859 2086 2857 2085 2857 2085 2856 2084 2858 2085 2847 712 2851 2082 2848 712 2858 2085 2860 2086 2859 2086 2842 2080 2851 2082 2850 2082 2841 770 2843 2080 2846 770 2842 2080 2850 2082 2843 2080 2845 778 2844 778 2835 780 2841 770 2846 770 2845 778 2836 780 2839 777 2837 777 2844 778 2836 780 2835 780 2840 781 2831 782 2838 781 2839 777 2838 781 2837 777 2832 2078 2830 2078 2829 782 2829 782 2831 782 2840 781 2824 2076 2834 2079 2833 2079 2834 2079 2830 2078 2832 2078 2823 791 2825 2076 2826 791 2824 2076 2833 2079 2825 2076 2828 2077 2827 2077 2819 2073 2823 791 2826 791 2828 2077 2817 2073 2821 2074 2818 2074 2827 2077 2817 2073 2819 2073 2820 2075 2818 2074 2821 2074 2861 2087 2862 2087 2863 2087 2862 2088 2864 2088 2865 2088 2862 2089 2861 2089 2866 2089 2864 2090 2862 2090 2867 2090 2868 2091 2866 2091 2869 2091 2862 2092 2866 2092 2867 2092 2866 2093 2861 2093 2869 2093 2870 2094 2861 2094 2863 2094 2871 2095 2872 2096 2873 2097 2874 499 2875 2098 2876 499 2877 2099 2878 2100 2879 2101 2880 2102 2881 2103 2882 2104 2883 2105 2884 2106 2885 2107 2886 2108 2887 2109 2888 2110 2889 2111 2890 2112 2891 2113 2892 2114 2893 2115 2894 2116 2895 2117 2896 2118 2897 2119 2898 2120 2899 2121 2900 2122 2901 2123 2902 2124 2903 2125 2904 2126 2905 2127 2906 2128 2907 2129 2908 2130 2909 516 2910 2131 2911 516 2912 2132 2913 2133 2914 2134 2915 2134 2916 2135 2917 2135 2918 2054 2919 2136 2920 2137 2921 2136 2922 2137 2923 2138 2924 2138 2925 2139 2926 2140 2927 2141 2928 2142 2929 2143 2930 2142 2931 2144 2926 2140 2925 2139 2931 2144 2932 2145 2933 2146 2932 2145 2931 2144 2925 2139 2934 2146 2935 2147 2933 2146 2933 2146 2932 2145 2934 2146 2936 2148 2935 2147 2937 2147 2934 2146 2937 2147 2935 2147 2936 2148 2938 2148 2939 2149 2938 2148 2936 2148 2937 2147 2940 2149 2941 2150 2939 2149 2939 2149 2938 2148 2940 2149 2942 2151 2941 2150 2943 2152 2940 2149 2943 2152 2941 2150 2942 2151 2944 2151 2945 2153 2944 2151 2942 2151 2943 2152 2946 2153 2876 499 2945 2153 2945 2153 2944 2151 2946 2153 2927 2141 2929 2143 2928 2142 2946 2153 2874 499 2876 499 2926 2140 2929 2143 2927 2141 2919 2136 2921 2136 2930 2142 2930 2142 2921 2136 2928 2142 2924 2138 2920 2137 2922 2137 2922 2137 2920 2137 2919 2136 2914 2134 2923 2138 2915 2134 2914 2134 2924 2138 2923 2138 2913 2133 2918 2054 2917 2135 2913 2133 2915 2134 2918 2054 2916 2135 2908 2130 2907 2129 2917 2135 2916 2135 2907 2129 2911 516 2910 2131 2909 516 2908 2130 2911 516 2909 516 2901 2123 2903 2125 2912 2132 2912 2132 2903 2125 2910 2131 2906 2128 2902 2124 2904 2126 2904 2126 2902 2124 2901 2123 2896 2118 2906 2128 2905 2127 2895 2117 2897 2119 2900 2122 2896 2118 2905 2127 2897 2119 2899 2121 2898 2120 2889 2111 2895 2117 2900 2122 2899 2121 2890 2112 2893 2115 2891 2113 2898 2120 2890 2112 2889 2111 2894 2116 2885 2107 2892 2114 2893 2115 2892 2114 2891 2113 2886 2108 2884 2106 2883 2105 2883 2105 2885 2107 2894 2116 2878 2100 2888 2110 2887 2109 2888 2110 2884 2106 2886 2108 2877 2099 2879 2101 2880 2102 2878 2100 2887 2109 2879 2101 2882 2104 2881 2103 2873 2097 2877 2099 2880 2102 2882 2104 2871 2095 2875 2098 2872 2096 2881 2103 2871 2095 2873 2097 2874 499 2872 2096 2875 2098 2949 2154 2950 2155 2951 2156 2953 2157 2954 2158 2947 2159 2955 2160 2956 2161 2957 2162 2959 2163 2956 2161 2960 2164 2955 2160 2960 2164 2956 2161 2958 2165 2955 2160 2957 2162 2952 2166 2958 2165 2957 2162 2952 2166 2953 2157 2958 2165 2954 2158 2948 2167 2947 2159 2952 2166 2954 2158 2953 2157 2947 2159 2948 2167 2951 2156 2949 2154 2951 2156 2948 2167 2961 2168 2962 2168 2963 2168 2961 2169 2964 2169 2962 2169 2965 2170 2966 2171 2967 2172 2968 2173 2969 2174 2970 2175 2971 2176 2972 2177 2973 2178 2974 2179 2975 2180 2976 2181 2977 2182 2978 2183 2979 2184 2977 2182 2980 2185 2981 2185 2982 2186 2978 2183 2983 2187 2978 2183 2982 2186 2979 2184 2977 2182 2979 2184 2980 2185 2982 2186 2983 2187 2984 2188 2973 2178 2981 2185 2980 2185 2971 2176 2974 2179 2972 2177 2973 2178 2972 2177 2981 2185 2975 2180 2966 2171 2976 2181 2971 2176 2975 2180 2974 2179 2965 2170 2967 2172 2970 2175 2976 2181 2966 2171 2965 2170 2968 2173 2970 2175 2967 2172 2985 2189 2986 2189 2987 2189 2985 2190 2988 2190 2986 2190 2989 2191 2990 2192 2991 2193 2992 2194 2993 2195 2994 2196 2995 2197 2996 2198 2997 2199 2996 2198 2990 2192 2989 2191 2998 2200 2997 2199 3000 2201 2999 2202 3001 2203 3002 2204 3001 2203 2999 2202 2998 2200 3003 2205 3002 2204 3004 2205 3001 2203 3004 2205 3002 2204 2997 2199 2998 2200 2999 2202 2997 2199 2996 2198 3000 2201 2995 2197 2990 2192 2996 2198 2989 2191 2991 2193 2994 2196 2992 2194 2994 2196 2991 2193 3005 2206 3006 2206 3007 2206 3005 2207 3008 2207 3006 2207 3011 2208 3012 2209 3009 2210 3014 2211 3015 2212 3016 2213 3017 2214 3018 2215 3019 2216 3021 2217 3018 2215 3022 2218 3017 2214 3022 2218 3018 2215 3020 2219 3017 2214 3019 2216 3013 2220 3020 2219 3019 2216 3013 2220 3014 2211 3020 2219 3015 2212 3010 2221 3016 2213 3013 2220 3015 2212 3014 2211 3016 2213 3010 2221 3009 2210 3011 2208 3009 2210 3010 2221 3023 2222 3024 2222 3025 2222 3023 2223 3026 2223 3024 2223 3029 2224 3030 2225 3027 2226 3031 2227 3032 2228 3033 2229 3035 2230 3036 2231 3037 2232 3038 2233 3033 2229 3032 2228 3039 2163 3036 2231 3040 2234 3035 2230 3040 2234 3036 2231 3038 2233 3035 2230 3037 2232 3033 2229 3038 2233 3037 2232 3031 2227 3034 2235 3032 2228 3031 2227 3028 2236 3034 2235 3034 2235 3028 2236 3027 2226 3029 2224 3027 2226 3028 2236 3041 2237 3042 2237 3043 2237 3041 2238 3044 2238 3042 2238 3045 2239 3046 2240 3047 2241 3048 2242 3049 2243 3050 2244 3051 2245 3052 2246 3053 2247 3054 2248 3055 2249 3056 2250 3057 2251 3058 2252 3059 2253 3057 2251 3060 2254 3061 2255 3062 2256 3058 2252 3063 2257 3058 2252 3062 2256 3059 2253 3057 2251 3059 2253 3060 2254 3062 2256 3063 2257 3064 2258 3053 2247 3061 2255 3060 2254 3051 2245 3054 2248 3052 2246 3053 2247 3052 2246 3061 2255 3055 2249 3046 2240 3056 2250 3051 2245 3055 2249 3054 2248 3045 2239 3047 2241 3050 2244 3056 2250 3046 2240 3045 2239 3048 2242 3050 2244 3047 2241 3065 2259 3066 2259 3067 2259 3065 2260 3068 2260 3066 2260 3071 2261 3072 2262 3069 2263 3073 2264 3074 2265 3075 2266 3077 2267 3078 2268 3079 2269 3080 2270 3075 2266 3074 2265 3081 2271 3078 2268 3082 2272 3077 2267 3082 2272 3078 2268 3080 2270 3077 2267 3079 2269 3075 2266 3080 2270 3079 2269 3073 2264 3076 2273 3074 2265 3073 2264 3070 2274 3076 2273 3076 2273 3070 2274 3069 2263 3071 2261 3069 2263 3070 2274 3083 2275 3084 2275 3085 2275 3083 2276 3086 2276 3084 2276 3089 2277 3090 2209 3087 2210 3092 2211 3093 2278 3094 2213 3095 2279 3096 2280 3097 2281 3099 2282 3096 2280 3100 2283 3095 2279 3100 2283 3096 2280 3098 2219 3095 2279 3097 2281 3091 2220 3098 2219 3097 2281 3091 2220 3092 2211 3098 2219 3093 2278 3088 2284 3094 2213 3091 2220 3093 2278 3092 2211 3094 2213 3088 2284 3087 2210 3089 2277 3087 2210 3088 2284 3101 2285 3102 2285 3103 2285 3101 2286 3104 2286 3102 2286 3105 2287 3106 2288 3107 2289 3108 2290 3109 2291 3110 2289 3111 2292 3112 2293 3113 2294 3114 2292 3115 2295 3116 2296 3117 2297 3118 2298 3119 2299 3120 2300 3121 2301 3122 2302 3123 2303 3124 2304 3125 2305 3126 2306 3127 2307 3128 2308 3129 2309 3130 2310 3131 2311 3132 2312 3130 2310 3133 2313 3134 2314 3135 2315 3131 2311 3129 2309 3131 2311 3135 2315 3134 2314 3136 2316 3137 2317 3137 2317 3135 2315 3134 2314 3138 2318 3136 2316 3139 2319 3136 2316 3138 2318 3137 2317 3130 2310 3129 2309 3133 2313 3138 2318 3139 2319 3140 2319 3133 2313 3123 2303 3132 2312 3125 2305 3124 2304 3128 2308 3132 2312 3123 2303 3125 2305 3127 2307 3126 2306 3118 2298 3128 2308 3124 2304 3126 2306 3120 2300 3117 2297 3119 2299 3117 2297 3127 2307 3118 2298 3113 2294 3122 2302 3121 2301 3121 2301 3120 2300 3119 2299 3111 2292 3114 2292 3112 2293 3113 2294 3112 2293 3122 2302 3115 2295 3106 2288 3116 2296 3111 2292 3115 2295 3114 2292 3105 2287 3107 2289 3110 2289 3116 2296 3106 2288 3105 2287 3108 2290 3110 2289 3107 2289 3141 2320 3142 2320 3143 2320 3141 2321 3144 2321 3142 2321 3145 2322 3146 2323 3147 2324 3148 2325 3149 2326 3150 2324 3151 2327 3152 2328 3153 2329 3154 2330 3155 2331 3156 2332 3157 2333 3158 2334 3159 2335 3160 2336 3161 2337 3162 2338 3163 2097 3164 2339 3165 2340 3165 2340 3158 2334 3163 2097 3166 2341 3164 2339 3167 2342 3164 2339 3166 2341 3165 2340 3158 2334 3157 2333 3163 2097 3166 2341 3167 2342 3168 2343 3160 2336 3157 2333 3159 2335 3153 2329 3162 2338 3161 2337 3161 2337 3160 2336 3159 2335 3151 2327 3154 2330 3152 2328 3153 2329 3152 2328 3162 2338 3155 2331 3146 2323 3156 2332 3151 2327 3155 2331 3154 2330 3145 2322 3147 2324 3150 2324 3156 2332 3146 2323 3145 2322 3148 2325 3150 2324 3147 2324 3169 2344 3170 2344 3171 2344 3169 2345 3172 2345 3170 2345 3173 2346 3174 1137 3175 2347 3176 2348 3177 2349 3178 2350 3179 2351 3180 2352 3181 2353 3182 2354 3183 2355 3184 2356 3185 2357 3186 2358 3187 2359 3188 2360 3189 2361 3190 2362 3186 2358 3191 2363 3192 2363 3191 2363 3186 2358 3185 2357 3193 2364 3192 2363 3194 2365 3191 2363 3194 2365 3192 2363 3188 2360 3185 2357 3187 2359 3181 2353 3190 2362 3189 2361 3189 2361 3188 2360 3187 2359 3179 2351 3182 2354 3180 2352 3181 2353 3180 2352 3190 2362 3183 2355 3174 1137 3184 2356 3179 2351 3183 2355 3182 2354 3173 2346 3175 2347 3178 2350 3184 2356 3174 1137 3173 2346 3176 2348 3178 2350 3175 2347 3195 2366 3196 2366 3197 2366 3197 2367 3198 2367 3195 2367 3199 2368 3200 2368 3201 2368 3199 1181 3202 1181 3200 1181 3201 2369 3200 2369 3203 2369 3204 2370 3205 2370 3203 2370 3203 2371 3200 2371 3204 2371 3205 2223 3204 2223 3206 2223 3207 2372 3208 2372 3209 2372 3209 2373 3210 2373 3207 2373 3211 2374 3212 2374 3213 2374 3213 2375 3214 2375 3211 2375 3213 2376 3212 2376 3215 2376 3215 2377 3212 2377 3216 2377 3217 2378 3218 2378 3219 2378 3219 2379 3220 2379 3217 2379 3221 2380 3223 2380 3222 2380 3224 2381 3222 2381 3225 2381 3224 2382 3221 2382 3222 2382 3222 2383 3226 2383 3225 2383 3226 2384 3227 2384 3228 2384 3225 2385 3226 2385 3228 2385 3226 2386 3229 2386 3227 2386 3229 2387 3226 2387 3230 2387 3226 2388 3231 2388 3230 2388 3232 2389 3233 2389 3234 2389 3235 2390 3236 2390 3234 2390 3232 2391 3237 2391 3233 2391 3238 2392 3236 2392 3235 2392 3232 2393 3234 2393 3236 2393 3239 2394 3240 2394 3241 2394 3242 2395 3243 2395 3239 2395 3241 2396 3242 2396 3239 2396 3244 2397 3245 2397 3246 2397 3245 2398 3244 2398 3247 2398 3248 2399 3249 2399 3250 2399 3249 2400 3248 2400 3251 2400 3252 2401 3253 2401 3254 2401 3253 2402 3252 2402 3255 2402 3256 2403 3257 2403 3258 2403 3257 2404 3256 2404 3259 2404 3260 2405 3261 2405 3262 2405 3263 2406 3264 2406 3262 2406 3260 2407 3265 2407 3261 2407 3266 2408 3264 2408 3263 2408 3260 2409 3262 2409 3264 2409 3267 2410 3268 2410 3269 2410 3268 2411 3267 2411 3270 2411 3267 2412 3269 2412 3271 2412 3272 2413 3273 2413 3274 2413 3270 2414 3267 2414 3272 2414 3275 2415 3273 2415 3276 2415 3275 2416 3274 2416 3273 2416 3272 2375 3267 2375 3273 2375 3277 2417 3278 2417 3279 2417 3280 2418 3281 2418 3282 2418 3283 2419 3284 2419 3285 2419 3286 2420 3287 2420 3288 2420 3287 2421 3289 2421 3288 2421 3286 2422 3290 2422 3291 2422 3291 2423 3287 2423 3286 2423 3292 2424 3290 2424 3284 2424 3290 2425 3292 2425 3291 2425 3283 2426 3285 2426 3293 2426 3292 2427 3284 2427 3283 2427 3294 2428 3295 2428 3293 2428 3293 2429 3285 2429 3294 2429 3296 2430 3295 2430 3294 2430 3297 2431 3298 2431 3296 2431 3295 2432 3296 2432 3298 2432 3297 2433 3299 2433 3300 2433 3300 1284 3298 1284 3297 1284 3281 2434 3299 2434 3278 2434 3299 2435 3281 2435 3300 2435 3279 2436 3301 2436 3277 2436 3277 2437 3302 2437 3278 2437 3281 2438 3278 2438 3302 2438 3280 2439 3282 2439 3303 2439 3302 2440 3282 2440 3281 2440 3304 2441 3305 2441 3306 2441 3307 2442 3305 2442 3304 2442 3305 2443 3308 2443 3306 2443 3309 2444 3305 2444 3307 2444 3310 2445 3308 2445 3305 2445 3305 2446 3309 2446 3311 2446 3310 2447 3305 2447 3312 2447 3311 2448 3313 2448 3305 2448 3305 2449 3314 2449 3312 2449 3315 2450 3305 2450 3313 2450 3316 2189 3314 2189 3305 2189 3305 2451 3315 2451 3317 2451 3316 2452 3305 2452 3318 2452 3317 2453 3319 2453 3305 2453 3320 2454 3305 2454 3321 2454 3321 2455 3305 2455 3319 2455 3305 2456 3322 2456 3323 2456 3322 2457 3305 2457 3320 2457 3324 2458 3323 2458 3325 2458 3323 2459 3322 2459 3325 2459 3326 2460 3327 2460 3323 2460 3326 2461 3323 2461 3324 2461 3327 2462 3328 2462 3323 2462 3329 2463 3323 2463 3328 2463 3329 2464 3330 2464 3323 2464 3331 2465 3332 2465 3333 2465 3333 2466 3334 2466 3331 2466 3335 2467 3336 2467 3337 2467 3337 2468 3338 2468 3335 2468 3337 2469 3336 2469 3339 2469 3340 2470 3341 2470 3342 2470 3342 2471 3343 2471 3340 2471 3344 2472 3346 2472 3345 2472 3347 2473 3344 2473 3345 2473 3348 2474 3349 2474 3347 2474 3347 2475 3345 2475 3348 2475 3349 2476 3348 2476 3350 2476 3351 2477 3352 2477 3353 2477 3354 2478 3355 2478 3356 2478 3357 2479 3358 2479 3353 2479 3353 2480 3358 2480 3351 2480 3359 2481 3360 2481 3353 2481 3353 2482 3360 2482 3357 2482 3361 2031 3362 2031 3363 2031 3364 2408 3359 2408 3353 2408 3366 2483 3367 2483 3368 2483 3369 2484 3370 2484 3371 2484 3372 971 3365 971 3373 971 3374 2485 3375 2485 3376 2485 3375 2486 3374 2486 3377 2486 3378 2487 3379 2487 3380 2487 3381 2488 3382 2488 3383 2488 3386 2489 3380 2489 3379 2489 3386 2490 3379 2490 3387 2490 3388 2491 3389 2491 3390 2491 3391 2492 3392 2492 3393 2492 3396 2493 3397 2493 3398 2493 3399 2494 3400 2494 3401 2494 3402 2495 3353 2495 3393 2495 3403 2496 3397 2496 3404 2496 3387 2497 3405 2497 3406 2497 3407 2379 3387 2379 3406 2379 3408 2498 3409 2498 3410 2498 3411 2499 3412 2499 3413 2499 3414 2500 3415 2500 3416 2500 3353 2501 3402 2501 3417 2501 3418 2502 3419 2502 3420 2502 3421 2503 3422 2503 3423 2503 3424 2504 3425 2504 3426 2504 3427 2505 3428 2505 3429 2505 3430 2506 3431 2506 3432 2506 3433 2507 3434 2507 3435 2507 3436 2508 3437 2508 3438 2508 3439 2509 3440 2509 3441 2509 3442 2510 3443 2510 3444 2510 3445 2511 3386 2511 3446 2511 3447 2512 3448 2512 3449 2512 3452 909 3450 909 3453 909 3454 2513 3455 2513 3456 2513 3457 2379 3458 2379 3459 2379 3458 2514 3460 2514 3461 2514 3462 2515 3408 2515 3463 2515 3464 2516 3465 2516 3466 2516 3467 2517 3468 2517 3469 2517 3464 2518 3466 2518 3470 2518 3473 2519 3408 2519 3474 2519 3408 2520 3475 2520 3476 2520 3478 2521 3475 2521 3408 2521 3450 2522 3479 2522 3480 2522 3481 2523 3482 2523 3408 2523 3408 2524 3483 2524 3484 2524 3463 2525 3408 2525 3485 2525 3486 2526 3408 2526 3450 2526 3487 2527 3488 2527 3408 2527 3489 2528 3408 2528 3462 2528 3490 2529 3408 2529 3488 2529 3408 2530 3489 2530 3487 2530 3491 2531 3485 2531 3408 2531 3408 2532 3490 2532 3492 2532 3493 2533 3408 2533 3494 2533 3491 2534 3408 2534 3486 2534 3452 2535 3495 2535 3450 2535 3450 2536 3495 2536 3486 2536 3408 2537 3496 2537 3478 2537 3451 2538 3453 2538 3450 2538 3451 2539 3450 2539 3480 2539 3450 2540 3497 2540 3479 2540 3477 2541 3408 2541 3498 2541 3499 2542 3497 2542 3450 2542 3408 2543 3477 2543 3472 2543 3450 2544 3469 2544 3499 2544 3469 2545 3468 2545 3499 2545 3472 2546 3474 2546 3408 2546 3473 2547 3471 2547 3408 2547 3408 2548 3410 2548 3500 2548 3408 2549 3471 2549 3409 2549 3467 2550 3469 2550 3501 2550 3502 2551 3408 2551 3503 2551 3408 2552 3500 2552 3503 2552 3454 2553 3467 2553 3455 2553 3455 2554 3467 2554 3501 2554 3504 2555 3505 2555 3454 2555 3454 2556 3456 2556 3504 2556 3505 2557 3506 2557 3460 2557 3460 2558 3506 2558 3507 2558 3507 2559 3461 2559 3460 2559 3508 2560 3509 2560 3458 2560 3460 2561 3458 2561 3509 2561 3510 2562 3511 2562 3458 2562 3458 2563 3511 2563 3508 2563 3457 2564 3512 2564 3458 2564 3458 2565 3512 2565 3510 2565 3513 2566 3457 2566 3459 2566 3459 2567 3514 2567 3515 2567 3459 2568 3515 2568 3513 2568 3514 2569 3459 2569 3516 2569 3517 2570 3518 2570 3466 2570 3519 2571 3520 2571 3521 2571 3466 2572 3465 2572 3517 2572 3519 2573 3521 2573 3522 2573 3523 2574 3519 2574 3522 2574 3524 2575 3523 2575 3522 2575 3525 2576 3526 2576 3527 2576 3528 2577 3524 2577 3529 2577 3525 2578 3527 2578 3530 2578 3531 2579 3532 2579 3527 2579 3527 2580 3532 2580 3530 2580 3449 2581 3448 2581 3527 2581 3529 2582 3443 2582 3533 2582 3534 2583 3535 2583 3529 2583 3536 2584 3444 2584 3443 2584 3533 2585 3443 2585 3442 2585 3537 2586 3443 2586 3538 2586 3537 2587 3536 2587 3443 2587 3539 2588 3443 2588 3540 2588 3539 2589 3538 2589 3443 2589 3386 2590 3541 2590 3540 2590 3540 2591 3443 2591 3386 2591 3386 2592 3445 2592 3542 2592 3541 2593 3386 2593 3542 2593 3543 2594 3386 2594 3544 2594 3386 2595 3543 2595 3446 2595 3545 2596 3546 2596 3387 2596 3546 2597 3544 2597 3386 2597 3407 2598 3547 2598 3387 2598 3387 2599 3547 2599 3545 2599 3420 2600 3419 2600 3548 2600 3415 2601 3414 2601 3421 2601 3549 2602 3550 2602 3424 2602 3551 2603 3429 2603 3428 2603 3434 2604 3433 2604 3552 2604 3553 2605 3554 2605 3555 2605 3556 2606 3557 2606 3431 2606 3441 2607 3558 2607 3559 2607 3440 2608 3439 2608 3432 2608 3560 2609 3436 2609 3438 2609 3561 2610 3436 2610 3562 2610 3563 2611 3560 2611 3438 2611 3436 2612 3560 2612 3564 2612 3561 2613 3562 2613 3559 2613 3561 2614 3437 2614 3436 2614 3558 2615 3441 2615 3440 2615 3562 2616 3441 2616 3559 2616 3431 2617 3430 2617 3556 2617 3439 2618 3430 2618 3432 2618 3355 2619 3354 2619 3557 2619 3355 2620 3557 2620 3556 2620 3434 2621 3565 2621 3356 2621 3565 2622 3354 2622 3356 2622 3433 2623 3435 2623 3555 2623 3434 2624 3552 2624 3565 2624 3553 2625 3566 2625 3554 2625 3435 2626 3553 2626 3555 2626 3549 2627 3566 2627 3550 2627 3566 2628 3549 2628 3554 2628 3429 2629 3426 2629 3425 2629 3550 2630 3425 2630 3424 2630 3427 2631 3567 2631 3428 2631 3551 2632 3426 2632 3429 2632 3567 2633 3418 2633 3420 2633 3418 2634 3567 2634 3427 2634 3548 2635 3568 2635 3569 2635 3548 2636 3419 2636 3568 2636 3568 1283 3423 1283 3422 1283 3422 2637 3569 2637 3568 2637 3570 2638 3414 2638 3416 2638 3415 2639 3421 2639 3423 2639 3571 2640 3413 2640 3570 2640 3570 2641 3416 2641 3571 2641 3411 2642 3406 2642 3412 2642 3571 2643 3411 2643 3413 2643 3387 2644 3572 2644 3405 2644 3406 2645 3405 2645 3412 2645 3573 2646 3387 2646 3574 2646 3575 2647 3572 2647 3387 2647 3576 2648 3577 2648 3403 2648 3403 2649 3578 2649 3387 2649 3579 2650 3398 2650 3580 2650 3581 2402 3403 2402 3582 2402 3398 2651 3401 2651 3400 2651 3400 2652 3399 2652 3583 2652 3576 2653 3403 2653 3581 2653 3584 2654 3388 2654 3583 2654 3399 2655 3584 2655 3583 2655 3585 2656 3586 2656 3395 2656 3587 2657 3388 2657 3584 2657 3388 2658 3587 2658 3389 2658 3395 2659 3586 2659 3400 2659 3589 2660 3590 2660 3591 2660 3592 971 3593 971 3594 971 3597 2661 3589 2661 3588 2661 3596 2662 3597 2662 3598 2662 3599 2663 3600 2663 3601 2663 3602 2664 3596 2664 3598 2664 3595 2665 3596 2665 3603 2665 3601 2666 3602 2666 3598 2666 3605 2667 3606 2667 3382 2667 3607 2668 3608 2668 3609 2668 3610 2669 3611 2669 3612 2669 3613 2670 3614 2670 3615 2670 3616 2671 3617 2671 3611 2671 3606 2672 3605 2672 3618 2672 3619 2408 3620 2408 3621 2408 3619 2673 3622 2673 3383 2673 3623 2674 3624 2674 3625 2674 3626 2675 3627 2675 3628 2675 3629 2676 3619 2676 3621 2676 3630 2677 3631 2677 3619 2677 3624 2678 3632 2678 3625 2678 3633 2679 3634 2679 3635 2679 3632 2680 3624 2680 3636 2680 3636 2681 3637 2681 3632 2681 3629 2682 3630 2682 3619 2682 3637 2683 3638 2683 3632 2683 3633 2684 3639 2684 3638 2684 3625 2685 3640 2685 3641 2685 3639 2466 3632 2466 3638 2466 3625 2686 3642 2686 3643 2686 3643 2687 3640 2687 3625 2687 3643 2688 3642 2688 3644 2688 3645 2465 3646 2465 3642 2465 3642 2689 3646 2689 3644 2689 3369 2690 3647 2690 3370 2690 3648 2691 3649 2691 3391 2691 3375 2692 3650 2692 3651 2692 3588 2465 3589 2465 3591 2465 3375 2693 3651 2693 3652 2693 3653 2694 3654 2694 3655 2694 3384 2695 3656 2695 3590 2695 3590 2696 3589 2696 3384 2696 3657 2697 3594 2697 3593 2697 3656 2698 3384 2698 3385 2698 3394 2699 3395 2699 3385 2699 3384 2700 3394 2700 3385 2700 3585 2701 3395 2701 3394 2701 3594 2702 3388 2702 3390 2702 3580 2703 3400 2703 3586 2703 3592 2678 3594 2678 3390 2678 3649 2704 3658 2704 3391 2704 3375 2705 3377 2705 3650 2705 3392 2706 3391 2706 3658 2706 3353 2707 3391 2707 3393 2707 3659 2708 3660 2708 3661 2708 3662 2707 3383 2707 3382 2707 3352 1347 3391 1347 3353 1347 3663 2709 3611 2709 3610 2709 3372 2710 3373 2710 3664 2710 3641 2711 3665 2711 3625 2711 3663 2712 3616 2712 3611 2712 3611 2713 3617 2713 3666 2713 3626 2714 3628 2714 3667 2714 3668 2715 3669 2715 3670 2715 3634 2716 3671 2716 3635 2716 3639 2717 3633 2717 3635 2717 3641 2718 3672 2718 3665 2718 3613 2719 3615 2719 3673 2719 3604 2720 3603 2720 3674 2720 3675 2721 3608 2721 3607 2721 3676 2722 3375 2722 3652 2722 3383 2723 3662 2723 3677 2723 3353 2570 3361 2570 3678 2570 3678 2724 3364 2724 3353 2724 3679 2725 3361 2725 3363 2725 3678 2726 3361 2726 3679 2726 3362 2727 3367 2727 3363 2727 3366 2728 3363 2728 3367 2728 3366 2729 3368 2729 3365 2729 3366 2730 3365 2730 3372 2730 3372 2731 3664 2731 3617 2731 3617 2732 3664 2732 3666 2732 3383 2733 3369 2733 3381 2733 3619 2734 3383 2734 3677 2734 3647 2735 3369 2735 3383 2735 3371 2736 3680 2736 3369 2736 3681 2737 3376 2737 3369 2737 3681 2738 3369 2738 3680 2738 3376 2739 3375 2739 3369 2739 3657 2740 3593 2740 3375 2740 3676 2739 3657 2739 3375 2739 3398 2741 3579 2741 3396 2741 3580 2742 3398 2742 3400 2742 3398 2743 3397 2743 3403 2743 3404 2744 3582 2744 3403 2744 3682 2745 3378 2745 3380 2745 3403 2746 3577 2746 3578 2746 3387 2747 3578 2747 3683 2747 3683 2748 3574 2748 3387 2748 3573 2749 3575 2749 3387 2749 3546 2750 3386 2750 3387 2750 3682 2751 3684 2751 3685 2751 3378 2752 3682 2752 3685 2752 3655 2753 3654 2753 3682 2753 3684 2466 3682 2466 3654 2466 3653 2754 3655 2754 3686 2754 3648 2755 3687 2755 3655 2755 3686 2756 3655 2756 3687 2756 3391 2757 3688 2757 3648 2757 3648 2758 3688 2758 3687 2758 3517 2759 3465 2759 3689 2759 3690 2760 3691 2760 3692 2760 3693 2761 3505 2761 3504 2761 3506 2762 3505 2762 3693 2762 3694 2763 3695 2763 3696 2763 3408 2764 3697 2764 3483 2764 3698 2765 3408 2765 3493 2765 3494 2766 3408 2766 3492 2766 3698 2767 3481 2767 3408 2767 3697 2745 3408 2745 3482 2745 3408 2768 3484 2768 3496 2768 3476 2769 3498 2769 3408 2769 3502 2770 3695 2770 3408 2770 3699 2771 3700 2771 3695 2771 3695 2772 3700 2772 3408 2772 3695 2773 3694 2773 3699 2773 3701 2774 3696 2774 3466 2774 3695 2775 3466 2775 3696 2775 3702 2776 3703 2776 3466 2776 3466 2777 3703 2777 3701 2777 3518 2778 3704 2778 3466 2778 3466 2779 3704 2779 3702 2779 3526 2780 3525 2780 3517 2780 3689 2781 3526 2781 3517 2781 3705 2782 3528 2782 3529 2782 3527 2783 3448 2783 3531 2783 3706 2784 3707 2784 3449 2784 3449 2785 3707 2785 3447 2785 3533 2786 3705 2786 3529 2786 3706 2787 3708 2787 3534 2787 3708 2788 3706 2788 3449 2788 3529 2789 3535 2789 3709 2789 3534 2790 3708 2790 3535 2790 3709 2791 3443 2791 3529 2791 3524 2792 3522 2792 3529 2792 3710 2793 3521 2793 3520 2793 3520 2794 3711 2794 3712 2794 3710 2795 3520 2795 3712 2795 3713 2796 3711 2796 3691 2796 3520 2797 3691 2797 3711 2797 3714 2798 3715 2798 3691 2798 3691 2799 3715 2799 3713 2799 3691 2800 3516 2800 3692 2800 3691 2801 3690 2801 3714 2801 3459 2802 3692 2802 3516 2802 3627 2803 3671 2803 3634 2803 3619 2804 3631 2804 3622 2804 3623 2805 3625 2805 3665 2805 3641 2806 3660 2806 3716 2806 3716 2807 3672 2807 3641 2807 3660 2808 3659 2808 3717 2808 3716 2672 3660 2672 3717 2672 3661 2809 3660 2809 3718 2809 3621 2810 3620 2810 3719 2810 3718 2811 3720 2811 3721 2811 3661 2812 3718 2812 3721 2812 3613 2722 3673 2722 3718 2722 3720 2813 3718 2813 3673 2813 3620 2814 3722 2814 3719 2814 3723 2736 3674 2736 3613 2736 3614 2815 3613 2815 3674 2815 3723 2816 3604 2816 3674 2816 3620 2817 3724 2817 3725 2817 3604 2818 3595 2818 3603 2818 3599 2819 3601 2819 3608 2819 3597 2820 3596 2820 3589 2820 3595 2821 3589 2821 3596 2821 3601 2822 3600 2822 3602 2822 3599 2823 3608 2823 3675 2823 3609 2824 3608 2824 3726 2824 3726 2825 3725 2825 3727 2825 3725 2826 3726 2826 3608 2826 3728 2827 3620 2827 3725 2827 3724 2828 3727 2828 3725 2828 3620 2829 3728 2829 3729 2829 3729 2830 3722 2830 3620 2830 3662 1943 3382 1943 3606 1943 3605 2831 3612 2831 3618 2831 3611 2832 3730 2832 3618 2832 3618 2833 3612 2833 3611 2833 3668 346 3730 346 3669 346 3611 2834 3669 2834 3730 2834 3670 2835 3669 2835 3667 2835 3669 2836 3626 2836 3667 2836 3627 2837 3634 2837 3628 2837 3733 2838 3734 2838 3735 2838 3736 2839 3737 2839 3732 2839 3731 2840 3732 2840 3737 2840 3737 2841 3736 2841 3738 2841 3732 2842 3731 2842 3739 2842 3732 2843 3739 2843 3740 2843 3741 2844 3737 2844 3738 2844 3742 2845 3741 2845 3743 2845 3738 2846 3743 2846 3741 2846 3744 2847 3742 2847 3743 2847 3744 2848 3734 2848 3733 2848 3733 2849 3742 2849 3744 2849 3735 2850 3734 2850 3745 2850 3746 2851 3747 2851 3745 2851 3735 2852 3745 2852 3747 2852 3746 2853 3748 2853 3749 2853 3749 2854 3747 2854 3746 2854 3750 2855 3749 2855 3748 2855 3751 2856 3752 2856 3753 2856 3751 2857 3753 2857 3756 2857 3752 2858 3757 2858 3753 2858 3757 2859 3752 2859 3758 2859 3753 2860 3759 2860 3756 2860 3758 2861 3760 2861 3757 2861 3759 2862 3761 2862 3756 2862 3762 2863 3757 2863 3760 2863 3754 2864 3755 2864 3761 2864 3754 2865 3761 2865 3759 2865 3754 2866 3763 2866 3755 2866 3764 2867 3754 2867 3765 2867 3754 2868 3764 2868 3763 2868 3766 2869 3767 2869 3764 2869 3764 2870 3765 2870 3766 2870 3768 2871 3767 2871 3766 2871 3769 2872 3768 2872 3766 2872 3770 2873 3769 2873 3766 2873 3771 2874 3769 2874 3770 2874 3770 2875 3772 2875 3771 2875 3770 2876 3773 2876 3772 2876 3770 2877 3774 2877 3773 2877 3775 2878 3773 2878 3774 2878 3774 2879 3776 2879 3777 2879 3777 2880 3775 2880 3774 2880 3776 2881 3778 2881 3777 2881 3779 2882 3778 2882 3776 2882 3779 2883 3780 2883 3778 2883 3779 2884 3781 2884 3780 2884 3781 2885 3779 2885 3782 2885 3779 2886 3783 2886 3782 2886 3783 2887 3784 2887 3782 2887 3783 2888 3785 2888 3784 2888 3785 2889 3786 2889 3784 2889 3786 2890 3785 2890 3787 2890 3787 2891 3785 2891 3788 2891 3789 2892 3790 2893 3791 2894 3792 2895 3791 2894 3793 2896 3791 2894 3792 2895 3789 2892 3792 2895 3793 2896 3794 2897 3795 2898 3792 2895 3796 2899 3794 2897 3796 2899 3792 2895 3792 2895 3795 2898 3797 2900 3798 2901 3789 2892 3799 2902 3797 2900 3800 2903 3801 2904 3801 2904 3802 2905 3803 2906 3801 2904 3804 2907 3805 2908 3803 2906 3804 2907 3801 2904 3806 2909 3801 2904 3805 2908 3807 2910 3808 2911 3806 2909 3806 2909 3805 2908 3807 2910 3806 2909 3809 2912 3810 2913 3802 2905 3801 2904 3800 2903 3810 2913 3811 2914 3806 2909 3812 2915 3813 2916 3811 2914 3812 2915 3814 2917 3813 2916 3808 2911 3809 2912 3806 2909 3814 2917 3815 2918 3813 2916 3816 2919 3817 2920 3813 2916 3818 2921 3813 2916 3815 2918 3817 2920 3819 2922 3813 2916 3811 2914 3813 2916 3806 2909 3818 2921 3816 2919 3813 2916 3819 2922 3820 2923 3821 2924 3822 2925 3823 2926 3824 2927 3821 2924 3825 2928 3819 2922 3819 2922 3826 2929 3823 2926 3827 2930 3822 2925 3828 2931 3829 2932 3830 2933 3831 2934 3832 2935 3822 2925 3824 2927 3819 2922 3823 2926 3822 2925 3822 2925 3832 2935 3828 2931 3833 2936 3822 2925 3827 2930 3834 2937 3835 2938 3836 2939 3826 2929 3819 2922 3825 2928 3837 2940 3833 2936 3838 2941 3837 2940 3839 2942 3840 2943 3838 2941 3839 2942 3837 2940 3841 2944 3835 2938 3837 2940 3841 2944 3837 2940 3840 2943 3835 2938 3834 2937 3837 2940 3836 2939 3842 2945 3834 2937 3837 2940 3822 2925 3833 2936 3843 2946 3834 2937 3844 2947 3834 2937 3842 2945 3844 2947 3845 2948 3846 2949 3847 2950 3848 2951 3834 2937 3843 2946 3849 2952 3834 2937 3848 2951 3850 2953 3846 2949 3851 2954 3834 2937 3849 2952 3846 2949 3845 2948 3851 2954 3846 2949 3846 2949 3849 2952 3847 2950 3850 2953 3854 2955 3846 2949 3855 2956 3846 2949 3854 2955 3855 2956 3857 2957 3858 2958 3856 2959 3859 2960 3855 2956 3860 2961 3855 2956 3858 2958 3861 2962 3862 2963 3863 2964 3817 2920 3820 2923 3819 2922 3857 2957 3855 2956 3854 2955 3864 2965 3865 2966 3859 2960 3864 2965 3859 2960 3856 2959 3865 2966 3866 2967 3859 2960 3862 2963 3859 2960 3866 2967 3869 2968 3870 2969 3789 2892 3799 2902 3789 2892 3870 2969 3789 2892 3871 2970 3872 2971 3872 2971 3869 2968 3789 2892 3873 2972 3874 2973 3871 2970 3871 2970 3874 2973 3872 2971 3875 2974 3876 2975 3871 2970 3877 2976 3873 2972 3871 2970 3883 2977 3886 2977 3887 2977 3885 2978 3888 2978 3889 2978 3888 2979 3893 2979 3889 2979 3898 2980 3899 2980 3900 2980 3906 2981 3867 2982 3868 2983 3867 2982 3905 2984 3868 2983 3907 2985 3906 2981 3868 2983 3908 2986 3909 2987 3910 2988 3907 2985 3910 2988 3906 2981 3911 2989 3912 2990 3913 2991 3913 2991 3868 2983 3911 2989 3914 2992 3913 2991 3912 2990 3913 2991 3914 2992 3915 2993 3915 2993 3917 2994 3913 2991 3917 2994 3916 2995 3913 2991 3916 2995 3917 2994 3920 2996 3916 2995 3920 2996 3918 2997 3919 2998 3918 2997 3920 2996 3918 2997 3921 2999 3922 3000 3921 2999 3918 2997 3919 2998 3922 3000 3921 2999 3923 3001 3922 3000 3923 3001 3924 3002 3926 3003 3922 3000 3927 3004 3929 3005 3930 3005 3931 3005 3926 3003 3928 3006 3929 3007 3935 3008 3929 3007 3928 3006 3933 3009 3931 3009 3930 3009 3929 3007 3936 3010 3937 3011 3937 3011 3938 3012 3930 3013 3930 3013 3929 3007 3937 3011 3926 3003 3927 3004 3928 3006 3922 3000 3925 3014 3927 3004 3925 3014 3922 3000 3924 3002 3922 3015 3926 3015 3941 3015 3942 3016 3882 3016 3943 3016 3892 3017 3897 3017 3896 3017 3899 3018 3895 3018 3946 3018 3947 3019 3948 3019 3949 3019 3950 3020 3951 3020 3952 3020 3953 3021 3957 3021 3958 3021 3963 3022 3964 3022 3965 3022 3968 3023 3964 3023 3963 3023 3969 3024 3970 3025 3971 3026 3974 3027 3975 3027 3976 3027 3981 3028 3982 3029 3983 3030 3986 3031 3987 3031 3988 3031 3979 3032 3972 3033 3989 3034 3979 3032 3981 3028 3983 3030 3990 3035 3979 3032 3989 3034 3991 3036 3992 3036 3993 3036 3994 3037 3995 3037 3996 3037 3902 3038 3903 3038 3897 3038 3994 3039 3998 3039 3995 3039 3880 3040 3996 3040 3995 3040 3999 3041 4000 3042 3983 3030 4001 3043 4002 3043 4003 3043 4005 3044 4006 3044 4007 3044 4008 3045 4009 3045 4007 3045 4010 3046 4009 3046 4008 3046 4011 3047 4012 3047 4013 3047 4012 3048 4010 3048 4008 3048 4014 3049 4013 3049 4015 3049 4016 3050 4017 3051 4018 3052 4019 3053 3998 3053 4020 3053 4001 3054 4019 3054 4024 3054 4025 3055 4022 3055 4026 3055 4029 3056 4030 3056 4028 3056 4031 3057 4032 3057 4415 3057 4033 3058 4034 3058 4035 3058 4036 3059 4037 3059 4038 3059 4034 3060 4039 3060 4029 3060 4040 3061 4041 3062 4042 3063 4043 3064 4044 3065 4045 3066 4046 3067 4045 3066 4047 3068 4048 3069 4049 3070 4050 3071 4051 3072 4047 3068 4045 3066 4052 3073 4053 3074 4054 3075 4055 3076 3981 3028 4056 3077 4057 3078 3982 3029 3981 3028 4058 3079 4059 3080 3981 3028 4055 3076 4058 3079 3981 3028 4060 3081 4061 3082 4057 3078 4062 3083 4063 3084 4064 3085 4065 3086 4066 3087 4067 3088 4068 3089 4069 3090 4070 3091 4071 3092 4072 3093 4073 3094 4074 3095 4075 3096 4076 3097 4074 3095 4077 3098 4075 3096 4078 3099 4079 3100 4064 3085 4080 3101 3940 3101 3939 3101 4081 3102 4082 3103 4083 3104 3939 3105 3940 3106 3969 3024 3970 3025 3969 3024 3940 3106 4062 3107 4064 3107 4079 3107 4085 3108 4086 3108 4063 3108 3973 3109 3979 3032 4088 3110 3983 3030 3982 3029 3999 3041 3981 3028 4059 3080 4090 3111 4090 3111 4060 3081 3981 3028 4091 3112 4060 3081 4061 3082 4057 3078 3981 3028 4060 3081 4092 3113 4093 3114 4061 3082 4092 3113 4091 3112 4061 3082 4094 3115 4095 3116 4061 3082 4094 3115 4061 3082 4093 3114 4061 3082 4096 3117 4097 3118 4096 3117 4061 3082 4095 3116 4097 3118 4098 3119 4099 3120 4096 3117 4098 3119 4097 3118 4097 3118 4100 3121 4101 3122 4099 3120 4100 3121 4097 3118 4101 3122 4102 3123 4097 3118 3979 3032 3990 3035 3980 3124 4102 3123 4103 3125 4097 3118 4105 3126 3983 3030 4000 3042 3973 3109 4086 3127 4087 3128 4078 3099 4064 3085 4084 3129 4063 3084 4062 3083 4085 3130 4080 3131 4084 3129 3940 3106 4108 3132 4106 3133 4109 3134 4110 3135 3970 3025 4111 3136 4077 3098 4110 3135 4111 3136 4113 3137 4114 3138 4803 3139 4114 3138 4115 3140 4109 3134 4111 3136 4112 3141 4116 3142 4111 3136 4117 3143 4075 3096 4115 3140 4114 3138 4118 3144 4119 3145 4117 3143 4116 3142 4120 3146 4121 3147 4122 3148 4120 3146 4123 3149 4124 3150 4118 3144 4128 3151 4125 3152 4130 3153 4129 3154 4131 3155 4126 3156 4125 3152 4132 3157 4131 3155 4129 3154 4134 3158 4129 3154 4127 3159 4126 3156 4126 3156 4135 3160 4134 3158 4136 3161 4131 3155 4134 3158 4134 3158 4137 3162 4136 3161 4138 3163 4139 3164 4140 3165 4137 3162 4141 3166 4136 3161 4141 3166 4137 3162 4142 3167 4143 3168 4144 3169 4145 3170 4141 3166 4142 3167 4146 3171 4147 3172 4148 3173 4149 3174 4146 3171 4142 3167 4150 3175 4151 3176 4152 3177 4153 3178 4154 3179 4146 3171 4150 3175 4155 3180 4156 3181 4149 3174 4157 3182 4154 3179 4150 3175 4158 3183 4159 3184 4157 3182 4156 3181 4160 3185 4158 3183 4157 3182 4161 3186 4158 3183 4157 3187 4159 3187 4154 3187 4159 3184 4158 3183 4162 3188 4163 3189 4162 3188 4164 3190 4165 3191 4166 3192 4167 3193 4164 3190 4168 3194 4169 3195 4170 3196 4171 3197 4172 3198 4162 3188 4158 3183 4160 3185 4173 3199 4174 3200 4169 3195 4163 3189 4174 3200 4175 3201 4176 3202 4177 3203 4175 3201 4175 3201 4174 3200 4176 3202 4178 3204 4179 3205 4180 3206 4181 3207 4182 3208 4183 3209 4177 3203 4182 3208 4184 3210 4176 3202 4182 3208 4177 3203 4185 3211 4186 3212 4187 3213 4188 3214 4177 3203 4184 3210 4189 3215 4188 3214 4190 3216 4184 3210 4190 3216 4188 3214 4190 3216 4191 3217 4189 3215 4053 3074 4190 3216 4181 3207 4189 3215 4191 3217 4192 3218 4193 3219 4194 3220 4195 3221 4195 3221 4196 3222 4197 3223 4198 3224 4191 3217 4052 3073 4190 3216 4053 3074 4191 3217 4047 3068 4052 3073 4199 3225 4198 3224 4052 3073 4047 3068 4200 3226 4201 3227 4202 3228 4203 3229 4043 3064 4048 3069 4199 3225 4046 3067 4047 3068 4204 3230 4205 3231 4044 3065 4206 3232 4207 3233 4208 3234 4208 3234 4209 3235 4210 3236 4203 3229 4204 3230 4044 3065 4211 3237 4212 3238 4213 3239 4212 3238 4210 3236 4214 3240 4215 3241 4216 3242 4217 3243 4218 3244 4219 3245 4040 3061 4220 3246 4216 3242 4221 3247 4220 3246 4219 3245 4222 3248 4223 3249 4224 3250 4225 3251 4223 3249 4042 3063 4226 3252 4227 3253 4224 3250 4226 3252 4228 3254 4229 3255 4230 3256 4231 3257 4232 3258 4224 3250 4230 3256 4233 3259 4227 3253 4234 3260 4233 3259 4235 3261 4232 3258 4236 3262 4237 3263 4234 3260 4238 3264 4239 3265 4239 3265 4240 3266 4231 3257 4241 3267 4242 3268 4243 3269 4243 3269 4236 3262 4240 3266 4238 3264 4244 3270 4245 3271 4246 3272 4247 3272 4248 3272 4249 3273 4247 3274 4250 3275 4247 3276 4251 3276 4248 3276 4253 3277 4251 3278 4249 3273 4252 3279 4251 3279 4254 3279 4255 3280 4256 3281 4257 3282 4258 3283 4254 3284 4253 3277 4259 3285 4260 3286 4261 3287 4263 3288 4264 3289 4265 3290 4258 3283 4262 3291 4266 3292 4268 3293 4267 3294 4262 3291 4270 3295 4266 3292 4267 3294 4269 3296 4268 3293 4271 3297 4276 3298 4273 3299 4270 3295 4274 3300 4279 3301 4269 3296 4280 3302 3875 2974 3871 2970 3936 3010 3929 3007 3935 3008 3933 3303 3934 3304 3931 3305 3941 3306 3929 3306 3931 3306 4283 3307 3922 3307 3941 3307 4284 3308 3913 3308 4281 3308 3918 3309 4283 3309 4281 3309 3916 3310 3918 3310 4281 3310 3913 3311 3916 3311 4281 3311 3868 2983 3905 2984 3911 2989 4285 3312 3907 3312 3868 3312 4284 3313 4285 3313 3868 3313 3908 2986 3910 2988 3907 2985 4286 3314 3908 3314 3907 3314 4287 3315 3863 2964 4288 3316 3856 2959 3855 2956 3860 2961 3859 2960 3862 2963 3861 2962 4289 3317 4290 3318 3855 2956 4289 3319 3855 3319 3859 3319 4291 3320 3834 2937 3846 2949 4290 3318 3846 2949 3855 2956 3831 2934 3837 2940 4292 3321 3846 2949 4290 3318 4291 3320 4293 3322 3822 2925 3831 2934 3834 2937 4291 3320 4292 3321 3792 2895 3797 2900 3801 2904 3837 2940 3834 2937 4292 3321 3789 2892 3798 2901 3790 2893 3831 2934 3822 2925 3837 2940 3876 2975 3877 2976 3871 2970 3822 2925 4293 3322 3819 2922 4294 3323 3792 2895 3801 2904 4295 3324 3819 2922 4293 3322 3813 2916 4295 3324 4296 3325 4297 3326 3871 2970 4298 3327 4297 3326 4280 3302 3871 2970 4299 3328 3806 2909 4296 3325 3801 2904 4299 3328 4294 3323 4300 3329 3871 2970 4301 3330 4298 3327 3871 2970 4300 3329 4302 3331 3933 3303 4303 3332 4302 3331 3934 3304 3933 3303 3941 3333 3926 3333 3929 3333 3904 3334 3931 3305 3934 3304 4283 3335 3918 3335 3922 3335 3904 3334 4282 3336 3941 3337 4306 3338 4281 3339 4305 3340 4283 3341 4282 3336 4305 3340 4307 3342 4306 3338 4305 3340 4308 3343 4285 3344 4284 3345 4284 3345 4281 3339 4306 3338 3913 3346 4284 3346 3868 3346 4306 3338 4308 3343 4284 3345 3907 3347 4285 3347 4286 3347 4309 3348 4286 3349 4285 3344 4310 3350 4311 3351 4288 3316 3861 3352 4289 3352 3859 3352 3861 2962 3863 2964 4287 3315 4289 3317 4312 3353 4313 3354 4312 3353 4289 3317 3861 2962 4314 3355 4291 3320 4290 3318 4313 3354 4290 3318 4289 3317 3829 2932 4292 3321 4315 3356 4290 3318 4313 3354 4314 3355 3819 2922 4295 3324 3813 2916 4315 3356 4291 3320 4314 3355 3806 2909 3813 2916 4296 3325 4315 3356 4292 3321 4291 3320 3801 2904 3806 2909 4299 3328 4292 3321 3829 2932 3831 2934 4299 3328 4316 3357 4317 3358 3830 2933 4293 3322 3831 2934 4293 3322 3830 2933 4318 3359 3792 2895 4319 3360 3789 2892 4319 3360 3792 2895 4294 3323 4320 3361 4295 3324 4318 3359 4296 3325 4320 3361 4316 3357 3871 2970 3789 2892 4301 3330 4319 3360 4301 3330 3789 2892 4299 3328 4296 3325 4316 3357 4321 3362 4303 3362 4322 3362 4321 3363 4302 3363 4303 3363 3904 3334 3941 3337 3931 3305 4323 3364 3934 3304 4302 3331 4282 3336 4283 3341 3941 3337 4323 3364 3901 3365 3904 3334 4305 3340 4281 3339 4283 3341 3904 3334 3901 3365 4304 3366 4324 3367 4307 3342 4305 3340 4324 3367 4282 3336 4304 3366 4308 3343 4306 3338 4326 3368 4327 3369 4326 3368 4306 3338 4308 3343 4309 3348 4285 3344 4328 3370 4329 3371 4310 3350 4287 3315 4312 3353 3861 2962 4287 3315 4288 3316 4311 3351 4312 3353 4330 3372 4331 3373 4330 3372 4312 3353 4287 3315 4332 3374 4314 3355 4313 3354 4331 3373 4313 3354 4312 3353 4333 3375 4315 3356 4334 3376 4332 3374 4313 3354 4331 3373 4293 3322 4318 3359 4295 3324 4332 3374 4334 3376 4314 3355 4296 3325 4295 3324 4320 3361 4314 3355 4334 3376 4315 3356 4335 3377 4316 3357 4336 3378 4333 3375 3829 2932 4315 3356 3830 2933 3829 2932 4337 3379 4317 3358 4319 3360 4294 3323 4294 3323 4299 3328 4317 3358 4338 3380 3830 2933 4337 3379 4318 3359 4338 3380 4339 3381 4336 3378 4320 3361 4339 3381 4316 3357 4320 3361 4336 3378 4301 3330 4340 3382 4300 3329 4341 3383 4322 3383 4342 3383 4341 3384 4321 3384 4322 3384 4323 3364 3904 3334 3934 3304 4302 3385 4321 3385 4343 3385 4304 3366 4282 3336 3904 3334 3898 3386 4323 3386 4343 3386 3898 3387 3901 3387 4323 3387 4324 3367 4305 3340 4282 3336 3901 3388 3898 3388 4344 3388 4344 3389 4345 3389 4304 3389 4307 3342 4327 3369 4306 3338 4325 3390 4307 3390 4324 3390 4326 3391 4327 3391 4347 3391 4326 3368 4309 3348 4308 3343 4326 3392 4347 3392 4348 3392 4348 3393 4309 3393 4326 3393 4311 3351 4330 3372 4287 3315 4311 3351 4310 3350 4329 3371 4330 3372 4349 3394 3852 3395 4349 3396 4330 3396 4311 3396 3853 3397 4332 3374 4331 3373 3852 3395 4331 3373 4330 3372 4337 3379 3829 2932 4333 3375 3852 3395 3853 3397 4331 3373 3830 2933 4338 3380 4318 3359 4332 3374 3853 3397 4350 3398 4320 3361 4318 3359 4339 3381 4332 3374 4350 3398 4334 3376 4351 3399 4339 3381 4338 3380 4352 3400 4333 3375 4334 3376 4337 3379 4333 3375 4353 3401 4335 3377 4354 3402 4317 3358 4317 3358 4316 3357 4335 3377 4355 3403 4337 3379 4353 3401 4338 3380 4355 3403 4351 3399 4319 3360 4354 3402 4340 3382 4354 3402 4319 3360 4317 3358 4351 3399 4336 3378 4339 3381 4319 3360 4340 3382 4301 3330 4356 3404 4342 3404 4357 3404 4356 3405 4341 3405 4342 3405 4343 3406 4323 3406 4302 3406 4321 3407 4341 3407 4358 3407 4344 3408 4304 3408 3901 3408 3899 3409 4343 3409 4358 3409 3899 3410 3898 3410 4343 3410 4345 3411 4324 3411 4304 3411 4345 3412 4325 3412 4324 3412 4344 3413 3900 3413 3958 3413 4325 3414 4347 3414 4307 3414 4345 3415 4346 3415 4325 3415 4307 3416 4347 3416 4327 3416 4347 3417 4359 3417 4360 3417 4361 3418 4329 3371 4328 3370 4329 3419 4349 3419 4311 3419 4334 3376 4350 3398 4352 3400 4353 3401 4333 3375 4352 3400 4337 3379 4355 3403 4338 3380 4362 3420 4357 3420 4363 3420 4362 3421 4356 3421 4357 3421 4358 3422 4343 3422 4321 3422 4358 3423 4341 3423 4356 3423 3900 3424 4344 3424 3898 3424 3958 3425 4345 3425 4344 3425 3958 3426 4346 3426 4345 3426 4346 3427 4359 3427 4325 3427 4325 3428 4359 3428 4347 3428 4347 3429 4360 3429 4348 3429 4348 3430 4360 3430 4364 3430 4366 3431 4363 3431 4367 3431 4366 3432 4362 3432 4363 3432 4358 3433 4356 3433 4362 3433 3899 3434 3894 3434 3895 3434 3953 3435 3900 3435 3954 3435 3894 3436 3899 3436 4358 3436 3900 3437 3899 3437 3946 3437 3900 3438 3953 3438 3958 3438 3958 3439 3957 3439 3959 3439 4359 3440 4368 3440 4369 3440 4359 3441 4369 3441 4360 3441 4370 3442 4365 3443 4361 3418 4329 3371 4361 3418 4365 3443 4349 3444 4329 3444 4276 3444 4349 3394 4276 3298 4277 3445 4277 3445 4278 3446 3852 3395 4278 3446 3853 3397 3852 3395 4350 3398 3853 3397 4278 3446 4355 3403 4353 3401 4371 3447 4340 3382 4373 3448 4300 3329 4374 3449 4367 3449 4375 3449 4374 3450 4366 3450 4367 3450 3895 3451 3894 3451 3945 3451 3954 3452 3900 3452 3946 3452 3959 3453 4346 3453 3958 3453 3962 3454 4368 3454 4346 3454 3959 3455 3962 3455 4346 3455 4346 3456 4368 3456 4359 3456 4364 3457 4360 3457 3880 3457 3852 3395 4349 3394 4277 3445 4365 3458 4276 3458 4329 3458 4376 3459 4377 3460 4378 3461 4353 3401 4352 3400 4371 3447 4379 3462 4380 3463 4350 3398 4335 3377 4336 3378 4372 3464 4380 3463 4371 3447 4352 3400 4335 3377 4382 3465 4354 3402 4382 3465 4335 3377 4372 3464 4381 3466 4383 3467 4355 3403 4384 3468 4351 3399 4383 3467 4340 3382 4354 3402 4373 3448 4382 3465 4373 3448 4354 3402 4384 3468 4372 3464 4336 3378 4385 3469 4375 3469 4386 3469 4385 3470 4374 3470 4375 3470 4366 3471 4387 3471 4362 3471 4358 3472 3945 3472 3894 3472 3945 3473 4358 3473 4387 3473 4360 3474 3996 3474 3880 3474 3994 3475 4020 3475 3998 3475 4388 3476 3996 3476 4360 3476 4020 3477 4024 3477 4019 3477 4024 3478 4002 3478 4001 3478 4389 3479 4003 3479 4002 3479 4003 3480 4391 3480 4390 3480 4390 3481 4392 3481 4393 3481 4393 3482 4006 3482 4005 3482 4005 3483 4007 3483 4009 3483 4010 3484 4012 3484 4011 3484 4011 3485 4013 3485 4014 3485 4014 3486 4015 3487 4038 3488 4037 3489 4394 3490 4395 3491 4038 3492 4015 3492 4036 3492 4395 3491 4396 3493 4397 3494 4037 3489 4036 3495 4394 3490 4397 3494 4378 3461 4377 3460 4395 3491 4394 3490 4396 3493 4377 3460 4376 3459 4370 3442 4378 3461 4397 3494 4396 3493 4350 3398 4278 3446 4379 3462 4370 3442 4376 3459 4365 3443 4352 3400 4350 3398 4380 3463 4355 3403 4371 3447 4381 3466 4351 3399 4355 3403 4383 3467 4336 3378 4351 3399 4384 3468 4374 3496 4387 3496 4366 3496 4387 3497 4358 3497 4362 3497 4388 3498 4360 3498 4369 3498 4003 3499 4389 3499 4004 3499 4003 3500 4004 3500 4391 3500 4391 3501 4392 3501 4390 3501 4393 3502 4392 3502 4006 3502 4277 3445 4276 3298 4270 3295 4385 3503 4387 3503 4374 3503 4400 3504 4386 3504 4401 3504 4400 3505 4385 3505 4386 3505 4385 3506 3903 3506 4387 3506 4387 3507 3902 3507 3945 3507 3903 3508 3902 3508 4387 3508 3902 3509 4402 3509 3945 3509 3953 3510 4398 3510 4399 3510 3957 3511 4399 3511 4403 3511 3946 3512 4402 3512 4404 3512 3959 3513 4403 3513 3985 3513 3954 3514 3946 3514 4404 3514 3954 3515 4398 3515 3953 3515 3953 3516 4399 3516 3957 3516 4403 3517 3959 3517 3957 3517 3962 3518 3985 3518 3984 3518 4368 3519 3984 3519 4405 3519 4406 3520 3994 3520 3996 3520 4405 3521 4388 3521 4369 3521 4407 3522 4406 3522 3996 3522 4408 3523 4389 3523 4002 3523 4406 3524 4409 3524 4020 3524 4409 3525 4410 3525 4024 3525 4410 3526 4408 3526 4002 3526 4389 3527 4408 3527 4411 3527 4006 3528 4392 3528 4412 3528 4411 3529 4391 3529 4004 3529 4413 3530 4412 3530 4392 3530 4006 3531 4412 3532 4414 3533 4415 3534 4015 3534 4013 3534 4414 3533 4007 3535 4006 3531 4416 3536 4008 3536 4007 3536 4415 3537 4013 3537 4012 3537 4015 3487 4417 3538 4036 3495 4036 3495 4418 3539 4394 3490 4394 3490 4419 3540 4396 3493 4378 3461 4396 3493 4420 3541 4279 3301 4278 3446 4272 3542 4378 3461 4421 3543 4376 3459 4376 3459 4422 3544 4365 3443 4422 3545 4276 3545 4365 3545 4278 3446 4277 3445 4270 3295 4279 3301 4275 3546 4379 3462 4275 3546 4371 3447 4380 3463 4402 3547 3895 3547 3945 3547 4402 3548 3946 3548 3895 3548 3954 3549 4404 3549 4398 3549 3984 3550 4368 3550 3962 3550 3985 3551 3962 3551 3959 3551 4405 3552 4369 3552 4368 3552 4407 3553 3996 3553 4388 3553 4406 3554 4020 3554 3994 3554 4409 3555 4024 3555 4020 3555 4410 3556 4002 3556 4024 3556 4411 3557 4004 3557 4389 3557 4413 3558 4392 3558 4391 3558 4007 3559 4414 3559 4416 3559 4012 3560 4008 3560 4416 3560 4418 3539 4036 3495 4417 3538 4419 3540 4394 3490 4418 3539 4420 3541 4396 3493 4419 3540 4421 3543 4378 3461 4420 3541 4422 3544 4376 3459 4421 3543 4379 3462 4278 3446 4279 3301 4380 3463 4379 3462 4275 3546 4381 3466 4371 3447 4423 3561 4400 3562 3903 3562 4385 3562 4424 3563 4400 3563 4401 3563 3896 3564 3903 3564 4400 3564 3897 3565 3903 3565 3896 3565 3902 3566 3897 3566 4425 3566 4398 3567 4404 3567 4426 3567 4404 3568 4402 3568 4425 3568 4403 3569 4399 3569 3956 3569 4398 3570 4426 3570 4399 3570 3985 3571 4403 3571 3956 3571 3960 3572 3961 3572 4388 3572 3961 3573 4427 3573 4407 3573 4427 3574 4428 3574 4406 3574 4428 3575 4410 3575 4409 3575 4429 3576 4413 3576 4391 3576 4031 3577 4012 3577 4416 3577 4415 3578 4430 3578 4015 3578 4273 3579 4276 3579 4422 3579 4371 3447 4275 3546 4423 3561 4272 3542 4278 3446 4270 3295 4424 3580 4401 3580 4432 3580 3896 3581 4400 3581 4424 3581 4425 3582 4402 3582 3902 3582 3960 3583 4388 3583 4405 3583 3961 3584 4407 3584 4388 3584 4427 3585 4406 3585 4407 3585 4428 3586 4409 3586 4406 3586 4429 3587 4391 3587 4411 3587 4012 3588 4031 3588 4415 3588 4417 3538 4015 3487 4430 3589 4275 3546 4274 3300 4431 3590 3955 3591 4399 3591 4426 3591 3956 3592 4436 3592 3985 3592 4404 3593 4435 3593 4426 3593 3985 3594 4437 3594 3984 3594 3956 3595 4399 3595 3955 3595 4438 3596 4405 3596 3984 3596 4437 3597 3985 3597 4436 3597 4437 3598 4438 3598 3984 3598 4405 3599 4438 3599 3960 3599 4410 3600 4428 3600 4439 3600 4441 3601 4411 3601 4408 3601 4439 3602 4442 3602 4410 3602 4442 3603 4441 3603 4408 3603 4411 3604 4441 3604 4429 3604 4443 3605 4414 3533 4412 3532 4443 3606 4444 3606 4414 3606 4444 3607 4031 3607 4416 3607 4415 3608 4032 3608 4430 3608 4417 3538 4445 3609 4418 3539 4418 3539 4446 3610 4419 3540 4271 3297 4434 3611 4274 3300 4431 3590 4434 3611 4433 3612 4372 3464 4447 3613 4382 3465 4447 3613 4373 3448 4382 3465 4384 3468 4448 3614 4372 3464 4449 3615 4425 3615 3897 3615 3892 3616 3896 3616 4424 3616 4435 3617 4404 3617 4425 3617 3892 3618 4449 3618 3897 3618 4449 3619 4435 3619 4425 3619 4440 3620 4427 3620 3961 3620 4442 3621 4408 3621 4410 3621 4444 3622 4416 3622 4414 3622 4446 3610 4418 3539 4445 3609 4420 3541 4419 3540 4446 3610 4417 3538 4450 3623 4445 3609 4269 3296 4272 3542 4267 3294 4451 3624 4422 3544 4421 3543 4447 3613 4372 3464 4448 3614 4383 3467 4452 3625 4384 3468 4373 3448 4453 3626 4300 3329 4432 3627 3944 3627 3893 3627 4440 3628 4428 3628 4427 3628 4450 3623 4417 3538 4430 3589 4273 3629 4422 3629 4451 3629 4420 3541 4446 3610 4455 3630 4456 3631 4271 3297 4268 3293 4421 3543 4420 3541 4457 3632 4458 3633 4434 3611 4271 3297 4273 3299 4266 3292 4270 3295 4270 3295 4267 3294 4272 3542 4272 3542 4269 3296 4279 3301 4279 3301 4274 3300 4275 3546 4448 3614 4384 3468 4452 3625 4275 3546 4431 3590 4423 3561 4423 3561 4475 3634 4381 3466 4460 3635 4383 3467 4381 3466 4447 3613 4453 3626 4373 3448 3893 3636 3944 3636 3889 3636 4432 3637 4461 3637 4424 3637 4462 3638 3892 3638 4424 3638 4449 3639 4465 3639 4435 3639 4463 3640 3956 3640 3955 3640 4464 3641 4426 3641 4435 3641 4463 3642 4436 3642 3956 3642 4463 3643 3955 3643 4464 3643 4454 3644 3960 3644 4438 3644 4466 3645 3961 3645 3960 3645 4454 3646 4438 3646 4437 3646 4466 3647 3960 3647 4454 3647 4440 3648 3961 3648 3978 3648 4440 3649 4467 3649 4428 3649 4468 3650 4429 3650 4469 3650 4429 3651 4441 3651 4469 3651 4470 3652 4443 3605 4412 3532 4429 3653 4468 3653 4413 3653 4413 3654 4470 3654 4412 3654 4032 3655 4031 3655 4023 3655 4471 3656 4430 3656 4032 3656 4023 3657 4471 3657 4032 3657 4430 3589 4471 3658 4450 3623 4420 3541 4455 3630 4457 3632 4451 3624 4421 3543 4457 3632 4268 3293 4262 3291 4472 3659 4451 3660 4474 3660 4273 3660 4475 3634 4423 3561 4431 3590 4460 3635 4381 3466 4475 3634 4452 3625 4383 3467 4460 3635 3893 3661 4461 3661 4432 3661 4461 3662 4462 3662 4424 3662 4449 3663 3892 3663 4462 3663 4465 3664 4464 3664 4435 3664 3955 3665 4426 3665 4464 3665 3948 3666 4476 3666 4463 3666 3966 3667 3967 3667 4477 3667 4466 3668 3978 3668 3961 3668 3978 3669 4467 3669 4440 3669 4467 3670 4439 3670 4428 3670 4468 3671 4470 3671 4413 3671 4023 3672 4031 3672 4444 3672 4471 3673 4023 3673 4478 3673 4266 3292 4273 3299 4474 3674 4263 3288 4479 3675 4480 3676 4481 3677 4482 3678 4483 3679 4484 3680 4473 3681 4458 3633 3893 3682 3888 3682 4461 3682 4449 3683 4485 3683 4486 3683 4485 3684 4449 3684 4462 3684 4465 3685 4449 3685 4486 3685 3948 3686 4463 3686 4464 3686 4436 3687 4476 3687 4487 3687 4437 3688 4487 3688 4488 3688 4476 3689 4436 3689 4463 3689 4454 3690 4488 3690 4489 3690 4487 3691 4437 3691 4436 3691 4489 3692 3977 3692 4466 3692 4454 3693 4437 3693 4488 3693 4466 3694 4454 3694 4489 3694 3977 3695 3978 3695 4466 3695 4467 3696 3978 3696 3997 3696 4490 3697 4469 3697 4441 3697 4467 3698 4477 3698 4439 3698 4439 3699 4491 3699 4442 3699 4442 3700 4490 3700 4441 3700 4492 3701 4493 3702 4470 3652 4468 3703 4492 3703 4470 3703 4443 3605 4470 3652 4493 3702 4494 3704 4444 3704 4443 3704 4471 3658 4495 3705 4450 3623 4023 3706 4444 3706 4027 3706 4471 3658 4478 3707 4495 3705 4450 3623 4495 3705 4445 3609 4446 3610 4496 3708 4455 3630 4497 3709 4262 3291 4258 3283 4451 3624 4457 3632 4498 3710 4499 3711 4500 3712 4501 3713 3885 3714 3889 3714 3932 3714 3888 3715 4462 3715 4461 3715 3888 3716 3881 3716 4462 3716 4465 3717 3948 3717 4464 3717 4476 3718 3947 3718 4502 3718 3977 3719 3997 3719 3978 3719 3997 3720 4477 3720 4467 3720 4477 3721 4491 3721 4439 3721 4491 3722 4490 3722 4442 3722 4493 3723 4494 3723 4443 3723 4494 3724 4027 3724 4444 3724 4496 3708 4446 3610 4445 3609 4445 3609 4503 3725 4496 3708 4451 3726 4498 3726 4474 3726 4455 3630 4504 3727 4505 3728 4505 3728 4498 3710 4457 3632 4506 3729 4507 3730 4508 3731 4480 3676 4458 3633 4456 3631 4509 3732 4500 3712 4484 3680 4474 3674 4258 3283 4266 3292 4473 3681 4433 3612 4434 3611 4262 3291 4267 3294 4266 3292 4268 3293 4269 3296 4267 3294 4271 3297 4274 3300 4269 3296 4434 3611 4431 3590 4274 3300 4431 3590 4433 3612 4475 3634 4459 3733 4460 3635 4475 3634 4447 3613 4510 3734 4453 3626 4510 3734 4447 3613 4448 3614 3888 3735 3890 3735 3881 3735 3881 3736 4485 3736 4462 3736 4485 3737 4511 3737 4512 3737 3881 3738 4511 3738 4485 3738 4486 3739 3948 3739 4465 3739 4486 3740 4485 3740 4512 3740 4513 3741 3948 3741 4486 3741 4514 3742 4476 3742 4502 3742 4515 3743 4487 3743 4514 3743 3947 3744 4476 3744 3948 3744 4516 3745 4489 3745 4488 3745 4514 3746 4487 3746 4476 3746 4515 3747 4488 3747 4487 3747 4517 3748 3977 3748 4516 3748 3966 3749 3997 3749 4517 3749 3977 3750 4489 3750 4516 3750 3977 3751 4517 3751 3997 3751 3997 3752 3966 3752 4477 3752 4490 3753 4021 3753 4469 3753 4491 3754 3967 3754 4518 3754 4490 3755 4518 3755 4021 3755 4469 3756 4021 3756 4022 3756 4492 3757 4468 3757 4022 3757 4492 3758 4022 3758 4016 3758 4519 3759 4493 3702 4492 3701 4521 3760 4494 3760 4493 3760 4023 3761 4028 3761 4478 3761 4027 3762 4494 3762 4028 3762 4028 3763 4023 3763 4027 3763 4503 3725 4445 3609 4495 3705 4504 3727 4455 3630 4496 3708 4505 3728 4457 3632 4455 3630 4496 3708 4522 3764 4504 3727 4254 3284 4258 3283 4474 3674 4254 3765 4474 3765 4498 3765 4459 3733 4475 3634 4433 3612 4452 3625 4460 3635 4459 3733 4459 3733 4523 3766 4452 3625 4524 3767 4448 3614 4452 3625 3885 3768 3890 3768 3888 3768 3885 3769 3884 3769 3891 3769 3881 3770 3890 3770 4511 3770 4512 3771 4513 3771 4486 3771 4513 3772 3949 3772 3948 3772 4525 3773 3949 3773 4513 3773 4488 3774 4515 3774 4526 3774 4516 3775 4526 3775 4517 3775 4526 3776 4516 3776 4488 3776 3966 3777 4517 3777 3964 3777 4491 3778 4518 3778 4490 3778 4477 3779 3967 3779 4491 3779 4021 3780 4026 3780 4022 3780 4469 3781 4022 3781 4468 3781 4025 3782 4016 3782 4022 3782 4521 3783 4028 3783 4494 3783 4493 3784 4519 3784 4521 3784 4527 3785 4478 3707 4520 3786 4528 3787 4495 3705 4527 3785 4028 3788 4520 3788 4478 3788 4522 3764 4496 3708 4503 3725 4495 3705 4478 3707 4527 3785 4503 3725 4495 3705 4528 3787 4529 3789 4530 3790 4504 3727 4531 3791 4497 3709 4253 3277 4530 3790 4252 3792 4505 3728 4264 3289 4472 3659 4497 3709 4252 3793 4254 3793 4498 3793 4263 3288 4456 3631 4472 3659 4480 3676 4532 3794 4484 3680 4258 3283 4253 3277 4497 3709 4533 3795 4534 3796 4535 3797 4472 3659 4262 3291 4497 3709 4456 3631 4268 3293 4472 3659 4458 3633 4271 3297 4456 3631 4524 3767 4452 3625 4523 3766 4458 3633 4473 3681 4434 3611 4510 3734 4448 3614 4524 3767 4433 3612 4473 3681 4536 3798 4536 3798 4523 3766 4459 3733 3890 3799 3885 3799 3891 3799 3891 3800 3879 3800 4537 3800 4537 3801 3890 3801 3891 3801 4512 3802 4511 3802 4538 3802 4511 3803 4537 3803 4538 3803 4512 3804 4539 3804 4513 3804 4539 3805 4512 3805 4538 3805 3947 3806 3949 3806 4525 3806 4539 3807 4525 3807 4513 3807 3947 3808 4540 3808 4502 3808 4502 3809 4540 3809 4514 3809 4525 3810 4540 3810 3947 3810 4514 3811 4541 3811 4515 3811 4515 3812 4542 3812 4526 3812 4540 3813 4541 3813 4514 3813 4541 3814 4542 3814 4515 3814 4526 3815 4543 3815 4517 3815 3975 3816 3963 3816 3976 3816 4542 3817 4543 3817 4526 3817 3966 3818 3964 3818 3968 3818 3964 3819 4517 3819 4543 3819 4518 3820 4544 3820 4545 3820 3967 3821 3968 3821 4544 3821 4545 3822 4021 3822 4518 3822 4021 3823 4545 3823 4026 3823 4492 3701 4016 3050 4519 3759 4016 3050 4018 3052 4519 3759 4035 3824 4029 3824 4521 3824 4521 3825 4519 3825 4035 3825 4028 3826 4030 3826 4520 3826 4521 3827 4029 3827 4028 3827 4528 3787 4522 3764 4503 3725 4504 3727 4522 3764 4529 3789 4530 3790 4505 3728 4504 3727 4522 3764 4528 3787 4546 3828 4252 3792 4498 3710 4505 3728 4531 3791 4249 3273 4547 3829 4479 3675 4265 3290 4548 3830 4251 3278 4253 3277 4254 3284 4501 3713 4509 3732 4549 3831 4536 3798 4459 3733 4433 3612 4523 3766 4499 3711 4524 3767 3932 3832 3884 3832 3885 3832 3887 3833 3932 3833 4551 3833 3884 3834 3887 3834 3886 3834 3886 3835 3891 3835 3884 3835 3886 3836 3879 3836 3891 3836 3890 3837 4537 3837 4511 3837 4537 3838 4552 3838 4538 3838 4537 3839 3879 3839 4552 3839 4553 3840 4538 3840 4552 3840 4553 3841 4539 3841 4538 3841 4539 3842 4553 3842 3952 3842 4539 3843 3952 3843 3951 3843 4525 3844 4554 3844 4540 3844 4525 3845 3951 3845 4554 3845 4555 3846 4556 3846 4557 3846 4540 3847 4554 3847 4555 3847 4541 3848 4540 3848 4555 3848 4542 3849 4541 3849 4557 3849 4541 3850 4555 3850 4557 3850 4543 3851 4542 3851 4558 3851 4542 3852 4557 3852 4558 3852 3964 3853 4543 3853 3965 3853 4558 3854 3965 3854 4543 3854 4544 3855 3975 3855 4559 3855 3967 3856 4544 3856 4518 3856 3966 3857 3968 3857 3967 3857 3968 3858 3963 3858 3975 3858 4559 3859 4545 3859 4544 3859 4026 3860 4560 3860 4025 3860 4519 3861 4018 3861 4035 3861 4018 3862 4561 3862 4033 3862 4034 3863 4033 3863 4562 3863 4035 3864 4018 3864 4033 3864 4030 3865 4039 3865 4563 3865 4034 3866 4029 3866 4035 3866 4563 3867 4564 3868 4520 3786 4039 3869 4030 3869 4029 3869 4564 3868 4565 3870 4527 3785 4563 3871 4520 3871 4030 3871 4520 3786 4564 3868 4527 3785 4546 3828 4529 3789 4522 3764 4528 3787 4527 3785 4565 3870 4529 3789 4546 3828 4566 3872 4547 3829 4250 3275 4567 3873 4568 3874 4530 3790 4529 3789 4569 3875 4570 3876 4571 3877 4568 3874 4248 3878 4530 3790 4572 3879 4264 3289 4531 3791 4252 3880 4248 3880 4251 3880 4257 3282 4573 3881 4574 3882 4532 3794 4548 3830 4575 3883 4249 3273 4531 3791 4253 3277 4509 3732 4532 3794 4576 3884 4264 3289 4497 3709 4531 3791 4264 3289 4263 3288 4472 3659 4500 3712 4536 3798 4473 3681 4480 3676 4456 3631 4263 3288 4499 3711 4523 3766 4536 3798 4484 3680 4458 3633 4480 3676 4500 3712 4473 3681 4484 3680 4550 3885 4510 3734 4524 3767 4536 3798 4500 3712 4499 3711 4550 3885 4453 3626 4510 3734 3932 3886 3887 3886 3884 3886 4551 3887 3943 3887 3883 3887 3886 3888 4577 3888 3879 3888 3886 3889 3883 3889 4577 3889 3879 3890 4577 3890 3878 3890 3879 3891 3878 3891 4552 3891 4578 3892 4552 3892 3878 3892 4578 3893 4553 3893 4552 3893 4553 3894 4578 3894 3952 3894 3987 3895 3952 3895 3988 3895 4539 3896 3951 3896 4525 3896 3950 3897 3952 3897 3987 3897 4579 3898 3951 3898 3950 3898 4579 3899 4554 3899 3951 3899 4580 3900 4555 3900 4554 3900 4580 3901 4554 3901 4579 3901 4555 3902 4580 3902 4581 3902 4555 3903 4581 3903 4556 3903 4557 3904 4583 3904 4558 3904 4557 3905 4556 3905 4582 3905 4558 3906 4584 3906 3965 3906 4557 3907 4582 3907 4583 3907 3965 3908 4585 3908 3963 3908 4558 3909 4583 3909 4584 3909 3976 3910 4586 3911 3993 3912 4585 3913 3965 3913 4584 3913 3968 3914 3975 3914 4544 3914 4585 3915 3976 3915 3963 3915 3974 3916 4559 3916 3975 3916 4561 3917 4587 3917 4033 3917 4587 3918 4562 3918 4033 3918 4562 3919 4039 3919 4034 3919 4565 3870 4546 3828 4528 3787 4566 3872 4568 3874 4529 3789 4546 3828 4565 3870 4588 3920 4252 3792 4530 3790 4248 3878 4246 3921 4242 3268 4250 3275 4589 3922 4590 3923 4591 3924 4547 3829 4592 3925 4572 3879 4572 3879 4593 3926 4265 3290 4247 3274 4249 3273 4251 3278 4594 3927 4595 3928 4596 3929 4597 3930 4598 3931 4575 3883 4598 3931 4599 3932 4576 3884 4501 3713 4601 3933 4499 3711 4524 3767 4601 3933 4602 3934 4551 3935 3883 3935 3887 3935 3943 3936 3882 3936 3883 3936 4603 3937 3883 3937 3882 3937 3883 3938 4603 3938 4577 3938 4577 3939 4603 3939 3878 3939 3878 3940 4603 3940 4604 3940 3986 3941 3950 3941 3987 3941 3986 3942 4579 3942 3950 3942 4579 3943 3986 3943 4605 3943 4605 3944 4580 3944 4579 3944 4581 3945 4605 3945 4606 3945 4605 3946 4581 3946 4580 3946 4556 3947 4606 3947 4607 3947 4606 3948 4556 3948 4581 3948 4607 3949 4582 3949 4556 3949 4608 3950 4583 3950 4582 3950 4608 3951 4584 3951 4583 3951 4584 3952 4609 3952 4585 3952 4586 3953 3976 3953 4585 3953 4609 3954 4586 3954 4585 3954 3974 3955 3992 3955 4559 3955 3993 3912 3974 3956 3976 3910 4610 3957 4611 3957 4561 3957 4587 3958 4561 3958 4611 3958 4562 3959 4587 3959 4611 3959 4039 3960 4562 3960 4612 3960 4562 3961 4611 3961 4612 3961 4563 3962 4039 3962 4613 3962 4039 3963 4612 3964 4613 3965 4614 3966 4564 3868 4563 3867 4563 3867 4613 3965 4614 3966 4615 3967 4565 3870 4564 3868 4564 3868 4614 3966 4615 3967 4588 3920 4566 3872 4546 3828 4616 3968 4565 3870 4615 3967 4588 3920 4565 3870 4616 3968 4566 3872 4588 3920 4617 3969 4246 3970 4618 3970 4243 3970 4568 3874 4566 3872 4619 3971 4242 3268 4620 3972 4567 3873 4618 3973 4568 3874 4619 3971 4567 3873 4621 3974 4592 3925 4246 3975 4248 3975 4618 3975 4592 3925 4622 3976 4593 3926 4247 3274 4246 3921 4250 3275 4593 3926 4623 3977 4548 3830 4250 3275 4547 3829 4249 3273 4624 3978 4506 3729 4625 3979 4531 3791 4547 3829 4572 3879 4626 3980 4627 3981 4506 3729 4572 3879 4265 3290 4264 3289 4599 3932 4628 3982 4535 3797 4479 3675 4263 3288 4265 3290 4480 3676 4479 3675 4532 3794 4601 3933 4524 3767 4499 3711 4484 3680 4532 3794 4509 3732 4602 3934 4550 3885 4524 3767 4500 3712 4509 3732 4501 3713 4453 3626 4550 3885 4629 3983 4602 3934 4629 3983 4550 3885 4300 3329 4453 3626 4629 3983 4607 3984 4608 3984 4582 3984 4608 3985 4630 3985 4584 3985 4584 3986 4630 3987 4609 3988 4630 3989 4631 3989 4609 3989 4631 3990 4632 3990 4586 3990 4631 3991 4586 3991 4609 3991 3993 3992 3992 3992 3974 3992 4586 3993 4632 3993 3993 3993 3991 3994 3993 3994 4632 3994 4634 3995 4611 3996 4610 3997 4612 3998 4611 3998 4635 3998 4611 3999 4633 3999 4635 3999 4613 3965 4636 4000 4614 3966 4612 3964 4635 4001 4637 4002 4614 3966 4638 4003 4615 3967 4613 3965 4637 4002 4636 4000 4615 3967 4639 4004 4616 3968 4614 3966 4636 4000 4638 4003 4617 3969 4588 3920 4616 3968 4639 4004 4615 3967 4638 4003 4617 3969 4619 3971 4566 3872 4640 4005 4616 3968 4639 4004 4248 3878 4568 3874 4618 3973 4617 3969 4616 3968 4640 4005 4236 3262 4618 3973 4619 3971 4237 3263 4619 3971 4617 3969 4239 3265 4245 3271 4241 3267 4619 3971 4237 3263 4236 3262 4245 3271 4641 4006 4620 3972 4236 4007 4243 4007 4618 4007 4641 4006 4642 4008 4621 3974 4242 3268 4246 3921 4243 3269 4259 3285 4622 3976 4642 4008 4250 3275 4242 3268 4567 3873 4597 3930 4623 3977 4259 3285 4567 3873 4592 3925 4547 3829 4573 3881 4643 4009 4644 4010 4572 3879 4592 3925 4593 3926 4300 3329 4645 4011 4506 3729 4548 3830 4265 3290 4593 3926 4599 3932 4534 3796 4549 3831 4532 3794 4479 3675 4548 3830 4549 3831 4600 4012 4501 3713 4601 3933 4600 4012 4646 4013 4634 3995 4610 3997 4647 4014 4648 4015 4633 4015 4634 4015 4634 3995 4633 4016 4611 3996 4648 4017 4649 4017 4633 4017 4633 4018 4649 4018 4635 4018 4649 4019 4650 4019 4635 4019 4612 3964 4637 4002 4613 3965 4635 4001 4650 4020 4637 4002 4637 4002 4650 4020 4651 4021 4652 4022 4636 4000 4651 4021 4636 4000 4637 4002 4651 4021 4653 4023 4639 4004 4638 4003 4653 4023 4638 4003 4652 4022 4237 3263 4617 3969 4640 4005 4654 4024 4639 4004 4653 4023 4225 3251 4640 4005 4654 4024 4639 4004 4654 4024 4640 4005 4228 3254 4041 3062 4219 3245 4640 4005 4225 3251 4237 3263 4655 4025 4238 3264 4235 3261 4225 3251 4232 3258 4237 3263 4244 3270 4655 4025 4590 3923 4236 3262 4232 3258 4240 3266 4244 3270 4589 3922 4641 4006 4240 3266 4241 3267 4243 3269 4589 3922 4260 3286 4642 4008 4620 3972 4242 3268 4241 3267 4656 4026 4657 4027 4571 3877 4620 3972 4621 3974 4567 3873 4261 3287 4658 4028 4597 3930 4622 3976 4592 3925 4621 3974 4658 4028 4628 3982 4598 3931 4593 3926 4622 3976 4623 3977 4659 4029 4481 3677 4660 4030 4623 3977 4575 3883 4548 3830 4600 4012 4601 3933 4501 3713 4575 3883 4576 3884 4532 3794 4646 4013 4602 3934 4601 3933 4509 3732 4576 3884 4549 3831 4646 4013 4629 3983 4602 3934 4652 4022 4651 4021 4661 4031 4662 4032 4652 4022 4661 4031 4638 4003 4636 4000 4652 4022 4652 4022 4662 4032 4653 4023 4662 4032 4663 4033 4653 4023 4664 4034 4662 4032 4665 4035 4223 3249 4654 4024 4663 4033 4663 4033 4654 4024 4653 4023 4666 4036 4667 4037 4668 4038 4225 3251 4654 4024 4223 3249 4667 4037 4669 4039 4235 3261 4232 3258 4225 3251 4224 3250 4669 4039 4670 4040 4655 4025 4240 3266 4232 3258 4231 3257 4670 4040 4671 4041 4590 3923 4240 3266 4239 3265 4241 3267 4672 4042 4255 3280 4673 4043 4241 3267 4245 3271 4620 3972 4591 3924 4674 4044 4260 3286 4641 4006 4621 3974 4620 3972 4674 4044 4675 4045 4261 3287 4622 3976 4621 3974 4642 4008 4675 4045 4676 4046 4658 4028 4259 3285 4623 3977 4622 3976 4676 4046 4482 3678 4628 3982 4597 3930 4575 3883 4623 3977 4482 3678 4677 4047 4535 3797 4598 3931 4576 3884 4575 3883 4599 3932 4549 3831 4576 3884 4549 3831 4534 3796 4600 4012 4646 4013 4600 4012 4533 3795 4110 3135 4678 4048 3971 3026 4122 3148 4076 3097 4075 3096 4076 3097 4122 3148 4121 3147 4121 3147 4120 3146 4124 3150 4126 3156 4123 3149 4117 3143 4679 4049 4124 3150 4123 3149 4127 3159 4679 4049 4123 3149 4130 3153 4679 4049 4127 3159 4129 3154 4130 3153 4127 3159 4680 4050 4664 4034 4665 4035 4042 3063 4663 4033 4664 4034 4663 4033 4662 4032 4664 4034 4668 4038 4229 3255 4221 3247 4663 4033 4042 3063 4223 3249 4227 3253 4234 3260 4231 3257 4226 3252 4224 3250 4223 3249 4681 4051 4669 4039 4666 4036 4227 3253 4231 3257 4224 3250 4682 4052 4670 4040 4681 4051 4239 3265 4231 3257 4234 3260 4570 3876 4671 4041 4682 4052 4245 3271 4239 3265 4238 3264 4671 4041 4569 3875 4591 3924 4245 3271 4244 3270 4641 4006 4657 4027 4674 4044 4569 3875 4589 3922 4642 4008 4641 4006 4675 4045 4657 4027 4683 4053 4259 3285 4642 4008 4260 3286 4676 4046 4683 4053 4483 3679 4259 3285 4261 3287 4597 3930 4645 4011 4684 4054 4644 4010 4597 3930 4658 4028 4598 3931 4534 3796 4533 3795 4600 4012 4598 3931 4628 3982 4599 3932 4533 3795 4685 4055 4646 4013 4599 3932 4535 3797 4534 3796 4300 3329 4629 3983 4685 4055 4646 4013 4685 4055 4629 3983 4078 4056 4084 4056 4080 4056 4107 4057 3970 3025 3940 3106 3970 3025 4107 4057 4111 3136 4110 3135 3971 3026 3970 3025 4075 3096 4077 3098 4111 3136 4686 4058 4687 4059 4688 4060 4122 3148 4075 3096 4117 3143 4689 4061 4690 4062 4691 4063 4120 3146 4122 3148 4117 3143 4692 4064 4693 4065 4694 4066 4123 3149 4120 3146 4117 3143 4693 4065 4133 4067 4695 4068 4123 3149 4126 3156 4127 3159 4696 4069 4128 3151 4133 4067 4126 3156 4134 3158 4129 3154 4696 4069 4697 4070 4132 3157 4697 4070 4148 3173 4698 4071 4134 3158 4135 3160 4137 3162 4699 4072 4142 3167 4135 3160 4137 3162 4135 3160 4142 3167 4161 3186 4150 3175 4699 4072 4150 3175 4142 3167 4699 4072 4700 4073 4701 4074 4702 4075 4157 3182 4150 3175 4161 3186 4155 3180 4702 4075 4165 3191 4162 3188 4160 3185 4168 3194 4162 3188 4163 3189 4159 3184 4703 4076 4704 4077 4680 4050 4664 4034 4704 4077 4040 3061 4680 4050 4704 4077 4664 4034 4041 3062 4230 3256 4226 3252 4040 3061 4042 3063 4664 4034 4705 4078 4706 4079 4707 4080 4042 3063 4041 3062 4226 3252 4705 4078 4666 4036 4668 4038 4226 3252 4230 3256 4227 3253 4708 4081 4681 4051 4666 4036 4233 3259 4234 3260 4227 3253 4709 4082 4682 4052 4681 4051 4235 3261 4238 3264 4234 3260 4710 4083 4570 3876 4682 4052 4244 3270 4238 3264 4655 4025 4711 4084 4571 3877 4570 3876 4244 3270 4590 3923 4589 3922 4712 4085 4713 4086 4594 3927 4591 3924 4260 3286 4589 3922 4683 4053 4656 4026 4714 4087 4261 3287 4260 3286 4674 4044 4483 3679 4714 4087 4660 4030 4261 3287 4675 4045 4658 4028 4481 3677 4715 4088 4677 4047 4628 3982 4658 4028 4676 4046 4535 3797 4628 3982 4482 3678 4535 3797 4677 4047 4533 3795 4084 3129 4107 4057 3940 3106 4108 3132 4107 4057 4084 3129 4719 4089 4720 4090 4721 4091 4108 3132 4112 3141 4107 4057 4722 4092 4723 4093 4724 4094 4111 3136 4107 4057 4112 3141 4725 4095 4726 4096 4727 4097 4728 4098 4729 4099 4730 4100 4731 4101 4732 4102 4729 4099 4733 4103 4734 4104 4735 4105 4117 3143 4111 3136 4116 3142 4126 3156 4119 3145 4125 3152 4126 3156 4117 3143 4119 3145 4736 4106 4737 4107 4738 4108 4741 4109 4742 4110 4740 4111 4135 3160 4132 3157 4698 4071 4135 3160 4126 3156 4132 3157 4699 4072 4698 4071 4147 3172 4161 3186 4147 3172 4156 3181 4699 4072 4135 3160 4698 4071 4743 4112 4744 4113 4745 4114 4161 3186 4699 4072 4147 3172 4156 3181 4158 3183 4161 3186 4748 4115 4749 4116 4747 4117 4167 3193 4750 4118 4751 4119 4164 3190 4174 3200 4163 3189 4162 3188 4168 3194 4164 3190 4173 3199 4751 4119 4183 3209 4174 3200 4164 3190 4169 3195 4182 3208 4176 3202 4173 3199 4173 3199 4176 3202 4174 3200 4752 4120 4753 4121 4754 4122 4755 4123 4205 3231 4703 4076 4205 3231 4218 3244 4704 4077 4704 4077 4703 4076 4205 3231 4756 4124 4757 4125 4758 4126 4040 3061 4704 4077 4218 3244 4759 4127 4760 4128 4761 4129 4040 3061 4219 3245 4041 3062 4233 3259 4229 3255 4667 4037 4230 3256 4041 3062 4228 3254 4762 4130 4763 4131 4764 4132 4230 3256 4229 3255 4233 3259 4764 4132 4765 4133 4766 4134 4233 3259 4667 4037 4235 3261 4766 4134 4767 4135 4673 4043 4235 3261 4669 4039 4655 4025 4673 4043 4711 4084 4710 4083 4670 4040 4590 3923 4655 4025 4255 3280 4574 3882 4711 4084 4591 3924 4590 3923 4671 4041 4574 3882 4656 4026 4571 3877 4591 3924 4569 3875 4674 4044 4573 3881 4714 4087 4656 4026 4657 4027 4675 4045 4674 4044 4714 4087 4644 4010 4660 4030 4683 4053 4676 4046 4675 4045 4677 4047 4715 4088 4533 3795 4676 4046 4483 3679 4482 3678 4482 3678 4481 3677 4677 4047 4300 3329 4685 4055 4715 4088 4533 3795 4715 4088 4685 4055 4064 3085 4108 3132 4084 3129 4106 3133 4108 3132 4064 3085 4071 3092 4073 3094 4720 4090 4768 4136 4722 4092 4072 3093 4769 4137 4070 3091 4724 4094 4109 3134 4112 3141 4108 3132 4069 3090 4770 4138 4771 4139 4112 3141 4109 3134 4115 3140 4116 3142 4115 3140 4118 3144 4115 3140 4116 3142 4112 3141 4772 4140 4688 4060 4734 4104 4773 4141 4691 4063 4687 4059 4118 3144 4119 3145 4116 3142 4774 4142 4692 4064 4690 4062 4775 4143 4776 4144 4777 4145 4125 3152 4119 3145 4118 3144 4132 3157 4128 3151 4696 4069 4128 3151 4132 3157 4125 3152 4138 3163 4140 3165 4742 4110 4144 3169 4143 3168 4139 3164 4153 3178 4152 3177 4145 3170 4697 4070 4698 4071 4132 3157 4151 3176 4778 4146 4779 4147 4147 3172 4698 4071 4148 3173 4160 3185 4155 3180 4165 3191 4149 3174 4156 3181 4147 3172 4168 3194 4165 3191 4167 3193 4155 3180 4160 3185 4156 3181 4169 3195 4167 3193 4751 4119 4165 3191 4168 3194 4160 3185 4780 4148 4179 3205 4170 3196 4167 3193 4169 3195 4168 3194 4781 4149 4753 4121 4178 3204 4751 4119 4173 3199 4169 3195 4752 4120 4782 4150 4783 4151 4183 3209 4182 3208 4173 3199 4784 4152 4785 4153 4786 4154 4184 3210 4182 3208 4181 3207 4181 3207 4187 3213 4053 3074 4181 3207 4190 3216 4184 3210 4052 3073 4191 3217 4053 3074 4051 3072 4198 3224 4047 3068 4191 3217 4198 3224 4192 3218 4755 4123 4045 3066 4044 3065 4218 3244 4204 3230 4222 3248 4044 3065 4205 3231 4755 4123 4787 4155 4758 4126 4211 3237 4218 3244 4205 3231 4204 3230 4228 3254 4220 3246 4221 3247 4219 3245 4218 3244 4222 3248 4788 4156 4789 4157 4761 4129 4220 3246 4228 3254 4219 3245 4789 4157 4790 4158 4791 4159 4229 3255 4228 3254 4221 3247 4792 4160 4793 4161 4763 4131 4667 4037 4229 3255 4668 4038 4794 4162 4795 4163 4765 4133 4667 4037 4666 4036 4669 4039 4767 4135 4796 4164 4797 4165 4681 4051 4670 4040 4669 4039 4798 4166 4799 4167 4672 4042 4682 4052 4671 4041 4670 4040 4800 4168 4256 3281 4801 4169 4569 3875 4671 4041 4570 3876 4643 4009 4257 3282 4594 3927 4657 4027 4569 3875 4571 3877 4645 4011 4643 4009 4506 3729 4656 4026 4683 4053 4657 4027 4684 4054 4659 4029 4660 4030 4483 3679 4683 4053 4714 4087 4483 3679 4660 4030 4481 3677 3973 3109 4087 3128 3972 3033 4089 4170 4106 3133 4063 3084 4063 3084 4106 3133 4064 3085 4063 3084 3973 3109 4089 4170 4802 4171 4717 4172 4716 4173 4719 4089 4721 4091 4718 4174 4803 3139 4109 3134 4106 3133 4089 4170 4803 3139 4106 3133 4804 4175 4726 4096 4725 4095 4109 3134 4803 3139 4114 3138 4805 4176 4729 4099 4728 4098 4806 4177 4735 4105 4732 4102 4114 3138 4695 4068 4118 3144 4695 4068 4128 3151 4118 3144 4128 3151 4695 4068 4133 4067 4741 4109 4740 4111 4739 4178 4807 4179 4697 4070 4696 4069 4133 4067 4807 4179 4696 4069 4808 4180 4148 3173 4697 4070 4807 4179 4808 4180 4697 4070 4809 4181 4149 3174 4148 3173 4808 4180 4809 4181 4148 3173 4700 4073 4155 3180 4149 3174 4149 3174 4809 4181 4700 4073 4155 3180 4700 4073 4702 4075 4810 4182 4747 4117 4746 4183 4165 3191 4702 4075 4166 3192 4749 4116 4811 4184 4171 3197 4166 3192 4750 4118 4167 3193 4812 4185 4183 3209 4751 4119 4750 4118 4812 4185 4751 4119 4185 3211 4181 3207 4183 3209 4812 4185 4185 3211 4183 3209 4813 4186 4785 4153 4784 4152 4181 3207 4185 3211 4187 3213 4814 4187 4195 3221 4194 3220 4053 3074 4187 3213 4054 3075 4197 3223 4815 4188 4201 3227 4052 3073 4054 3075 4199 3225 4200 3226 4816 4189 4050 3071 4817 4190 4818 4191 4819 4192 4051 3072 4045 3066 4755 4123 4045 3066 4046 3067 4043 3064 4820 4193 4208 3234 4207 3233 4043 3064 4203 3229 4044 3065 4821 4194 4222 3248 4204 3230 4203 3229 4821 4194 4204 3230 4217 3243 4220 3246 4222 3248 4821 4194 4217 3243 4222 3248 4757 4125 4822 4195 4759 4127 4217 3243 4216 3242 4220 3246 4706 4079 4668 4038 4221 3247 4216 3242 4706 4079 4221 3247 4791 4159 4823 4196 4763 4131 4706 4079 4705 4078 4668 4038 4793 4161 4824 4197 4765 4133 4708 4081 4666 4036 4705 4078 4795 4163 4825 4198 4767 4135 4709 4082 4681 4051 4708 4081 4797 4165 4826 4199 4672 4042 4682 4052 4709 4082 4710 4083 4799 4167 4827 4200 4256 3281 4570 3876 4710 4083 4711 4084 4256 3281 4800 4168 4712 4085 4711 4084 4574 3882 4571 3877 4594 3927 4596 3929 4625 3979 4574 3882 4573 3881 4656 4026 4506 3729 4508 3731 4626 3980 4573 3881 4644 4010 4714 4087 4684 4054 4660 4030 4644 4010 4300 3329 4715 4088 4659 4029 4481 3677 4659 4029 4715 4088 3973 3109 4063 3084 4086 3127 4088 3110 4089 4170 3973 3109 4089 4170 4088 3110 4828 4201 4803 3139 4089 4170 4828 4201 4803 3139 4828 4201 4829 4202 4113 3137 4803 3139 4829 4202 4830 4203 4771 4139 4770 4138 4114 3138 4113 3137 4831 4204 4114 3138 4831 4204 4832 4205 4695 4068 4114 3138 4832 4205 4694 4066 4695 4068 4832 4205 4833 4206 4777 4145 4776 4144 4695 4068 4694 4066 4693 4065 4133 4067 4693 4065 4834 4207 4807 4179 4133 4067 4835 4208 4133 4067 4834 4207 4835 4208 4808 4180 4807 4179 4836 4209 4807 4179 4835 4208 4836 4209 4809 4181 4808 4180 4837 4210 4837 4210 4808 4180 4836 4209 4838 4211 4700 4073 4809 4181 4838 4211 4809 4181 4837 4210 4700 4073 4838 4211 4701 4074 4166 3192 4702 4075 4839 4212 4702 4075 4701 4074 4839 4212 4750 4118 4166 3192 4840 4213 4166 3192 4839 4212 4840 4213 4812 4185 4750 4118 4841 4214 4750 4118 4840 4213 4841 4214 4185 3211 4812 4185 4842 4215 4812 4185 4841 4214 4842 4215 4843 4216 4783 4151 4782 4150 4185 3211 4842 4215 4186 3212 4054 3075 4187 3213 4844 4217 4187 3213 4186 3212 4844 4217 4199 3225 4054 3075 4845 4218 4054 3075 4844 4217 4845 4218 4046 3067 4199 3225 4846 4219 4199 3225 4845 4218 4846 4219 4049 3070 4043 3064 4046 3067 4049 3070 4046 3067 4846 4219 4847 4220 4819 4192 4818 4191 4043 3064 4049 3070 4048 3069 4821 4194 4203 3229 4848 4221 4203 3229 4048 3069 4848 4221 4217 3243 4821 4194 4849 4222 4821 4194 4848 4221 4849 4222 4850 4223 4758 4126 4787 4155 4217 3243 4849 4222 4215 3241 4706 4079 4216 3242 4851 4224 4216 3242 4215 3241 4851 4224 4852 4225 4789 4157 4788 4156 4706 4079 4851 4224 4707 4080 4708 4081 4705 4078 4762 4130 4707 4080 4762 4130 4705 4078 4709 4082 4708 4081 4764 4132 4762 4130 4764 4132 4708 4081 4710 4083 4709 4082 4766 4134 4764 4132 4766 4134 4709 4082 4826 4199 4853 4226 4672 4042 4673 4043 4710 4083 4766 4134 4827 4200 4854 4227 4256 3281 4711 4084 4673 4043 4255 3280 4713 4086 4855 4228 4594 3927 4574 3882 4255 3280 4257 3282 4624 3978 4856 4229 4506 3729 4573 3881 4257 3282 4643 4009 4506 3729 4627 3981 4300 3329 4644 4010 4643 4009 4645 4011 4300 3329 4659 4029 4684 4054 3973 3109 3972 3033 3979 3032 4056 3077 3979 3032 3980 3124 4104 4230 4088 3110 3983 3030 4067 3088 4088 3110 4104 4230 4083 3104 4828 4201 4088 3110 4083 3104 4088 3110 4067 3088 4717 4172 4828 4201 4083 3104 4721 4091 4829 4202 4828 4201 4721 4091 4828 4201 4717 4172 4721 4091 4073 3094 4829 4202 4722 4092 4113 3137 4829 4202 4073 3094 4722 4092 4829 4202 4070 3091 4113 3137 4722 4092 4771 4139 4831 4204 4113 3137 4771 4139 4113 3137 4070 3091 4726 4096 4831 4204 4771 4139 4729 4099 4832 4205 4831 4204 4729 4099 4831 4204 4726 4096 4735 4105 4832 4205 4729 4099 4688 4060 4694 4066 4832 4205 4735 4105 4688 4060 4832 4205 4688 4060 4691 4063 4694 4066 4857 4231 4692 4064 4774 4142 4692 4064 4694 4066 4691 4063 4777 4145 4834 4207 4693 4065 4777 4145 4693 4065 4692 4064 4737 4107 4835 4208 4834 4207 4737 4107 4834 4207 4777 4145 4740 4111 4836 4209 4835 4208 4740 4111 4835 4208 4737 4107 4140 3165 4837 4210 4836 4209 4740 4111 4140 3165 4836 4209 4143 3168 4838 4211 4837 4210 4140 3165 4143 3168 4837 4210 4152 3177 4701 4074 4838 4211 4152 3177 4838 4211 4143 3168 4779 4147 4839 4212 4701 4074 4779 4147 4701 4074 4152 3177 4744 4113 4840 4213 4839 4212 4744 4113 4839 4212 4779 4147 4747 4117 4841 4214 4840 4213 4747 4117 4840 4213 4744 4113 4171 3197 4842 4215 4841 4214 4747 4117 4171 3197 4841 4214 4171 3197 4179 3205 4842 4215 4753 4121 4186 3212 4842 4215 4753 4121 4842 4215 4179 3205 4783 4151 4844 4217 4186 3212 4783 4151 4186 3212 4753 4121 4785 4153 4845 4218 4844 4217 4785 4153 4844 4217 4783 4151 4195 3221 4846 4219 4845 4218 4195 3221 4845 4218 4785 4153 4201 3227 4049 3070 4846 4219 4195 3221 4201 3227 4846 4219 4858 4232 4050 3071 4816 4189 4050 3071 4049 3070 4201 3227 4819 4192 4848 4221 4048 3069 4819 4192 4048 3069 4050 3071 4208 3234 4849 4222 4848 4221 4208 3234 4848 4221 4819 4192 4212 3238 4215 3241 4849 4222 4212 3238 4849 4222 4208 3234 4758 4126 4851 4224 4215 3241 4758 4126 4215 3241 4212 3238 4759 4127 4707 4080 4851 4224 4759 4127 4851 4224 4758 4126 4789 4157 4762 4130 4707 4080 4789 4157 4707 4080 4759 4127 4859 4233 4763 4131 4823 4196 4763 4131 4762 4130 4789 4157 4860 4234 4765 4133 4824 4197 4765 4133 4764 4132 4763 4131 4861 4235 4767 4135 4825 4198 4766 4134 4765 4133 4767 4135 4862 4236 4672 4042 4853 4226 4673 4043 4767 4135 4672 4042 4863 4237 4256 3281 4854 4227 4672 4042 4256 3281 4255 3280 4864 4238 4594 3927 4855 4228 4256 3281 4594 3927 4257 3282 4865 4239 4506 3729 4856 4229 4506 3729 4643 4009 4594 3927 4300 3329 4684 4054 4645 4011 3979 3032 4056 3077 3981 3028 3979 3032 3983 3030 4088 3110 4105 3126 4104 4230 3983 3030 4065 3086 4104 4230 4105 3126 4067 3088 4104 4230 4065 3086 4081 3102 4067 3088 4066 3087 4083 3104 4067 3088 4081 3102 4716 4173 4083 3104 4082 3103 4717 4172 4083 3104 4716 4173 4718 4174 4717 4172 4802 4171 4718 4174 4721 4091 4717 4172 4720 4090 4073 3094 4721 4091 4072 3093 4722 4092 4073 3094 4723 4093 4722 4092 4768 4136 4724 4094 4070 3091 4722 4092 4068 3089 4070 3091 4769 4137 4771 4139 4070 3091 4069 3090 4727 4097 4771 4139 4830 4203 4726 4096 4771 4139 4727 4097 4730 4100 4726 4096 4804 4175 4729 4099 4726 4096 4730 4100 4731 4101 4729 4099 4805 4176 4732 4102 4735 4105 4729 4099 4733 4103 4735 4105 4806 4177 4734 4104 4688 4060 4735 4105 4686 4058 4688 4060 4772 4140 4687 4059 4691 4063 4688 4060 4689 4061 4691 4063 4773 4141 4692 4064 4691 4063 4690 4062 4775 4143 4692 4064 4857 4231 4777 4145 4692 4064 4775 4143 4738 4108 4777 4145 4833 4206 4737 4107 4777 4145 4738 4108 4739 4178 4737 4107 4736 4106 4740 4111 4737 4107 4739 4178 4742 4110 4140 3165 4740 4111 4139 3164 4143 3168 4140 3165 4145 3170 4152 3177 4143 3168 4779 4147 4152 3177 4151 3176 4745 4114 4779 4147 4778 4146 4744 4113 4779 4147 4745 4114 4746 4183 4744 4113 4743 4112 4747 4117 4744 4113 4746 4183 4748 4115 4747 4117 4810 4182 4749 4116 4171 3197 4747 4117 4172 3198 4171 3197 4811 4184 4170 3196 4179 3205 4171 3197 4180 3206 4179 3205 4780 4148 4178 3204 4753 4121 4179 3205 4754 4122 4753 4121 4781 4149 4783 4151 4753 4121 4752 4120 4786 4154 4783 4151 4843 4216 4785 4153 4783 4151 4786 4154 4193 3219 4785 4153 4813 4186 4195 3221 4785 4153 4193 3219 4196 3222 4195 3221 4814 4187 4197 3223 4201 3227 4195 3221 4202 3228 4201 3227 4815 4188 4050 3071 4201 3227 4200 3226 4817 4190 4050 3071 4858 4232 4819 4192 4050 3071 4817 4190 4206 3232 4819 4192 4847 4220 4208 3234 4819 4192 4206 3232 4209 3235 4208 3234 4820 4193 4210 3236 4212 3238 4208 3234 4213 3239 4212 3238 4214 3240 4758 4126 4212 3238 4211 3237 4756 4124 4758 4126 4850 4223 4757 4125 4759 4127 4758 4126 4760 4128 4759 4127 4822 4195 4789 4157 4759 4127 4761 4129 4790 4158 4789 4157 4852 4225 4763 4131 4789 4157 4791 4159 4792 4160 4763 4131 4859 4233 4765 4133 4763 4131 4793 4161 4794 4162 4765 4133 4860 4234 4767 4135 4765 4133 4795 4163 4796 4164 4767 4135 4861 4235 4767 4135 4797 4165 4672 4042 4798 4166 4672 4042 4862 4236 4672 4042 4799 4167 4256 3281 4801 4169 4256 3281 4863 4237 4256 3281 4712 4085 4594 3927 4595 3928 4594 3927 4864 4238 4594 3927 4625 3979 4506 3729 4507 3730 4506 3729 4865 4239 5105 4240 4866 4241 4867 4242 7082 4243 7297 4244 4870 4245 7297 4244 7346 4246 4872 4247 4953 4248 4954 4249 6965 4250 4873 4251 5018 4252 4874 4253 4895 4254 4896 4255 4897 4256 4897 4256 4899 4257 4900 4258 4898 4259 4901 4260 4896 4255 4896 4255 4902 4261 4898 4259 4903 4262 4896 4255 4901 4260 4904 4263 4905 4264 4906 4265 4907 4266 4908 4267 4909 4268 4901 4260 4910 4269 4903 4262 4911 4270 4912 4271 4903 4262 4903 4262 4910 4269 4911 4270 4911 4270 4913 4272 4912 4271 4913 4272 4914 4273 4912 4271 4912 4271 4914 4273 4909 4268 4916 4274 4909 4268 4914 4273 4917 4275 4918 4276 4919 4277 4916 4274 4920 4278 4909 4268 4915 4279 4909 4268 4921 4280 4909 4268 4920 4278 4907 4266 4922 4281 4923 4282 4924 4283 4908 4267 4925 4284 4921 4280 4926 4285 4908 4267 4907 4266 4922 4281 4908 4267 4923 4282 4929 4286 4930 4287 4931 4288 4923 4282 4908 4267 4926 4285 4932 4289 4900 4258 4933 4290 4922 4281 4934 4291 4925 4284 4937 4292 4934 4291 4938 4293 4939 4294 4940 4295 4941 4296 4942 4297 4934 4291 4940 4295 4943 4298 4941 4296 4940 4295 4942 4297 4940 4295 4936 4299 4940 4295 4922 4281 4943 4298 4936 4299 4940 4295 4944 4300 4940 4295 4939 4294 4944 4300 4944 4300 4945 4301 4936 4299 4922 4281 4924 4283 4943 4298 4945 4301 4948 4302 4949 4303 4935 4304 4936 4299 4949 4303 4936 4299 4945 4301 4949 4303 4949 4303 4955 4305 4956 4306 4949 4303 4957 4307 4952 4308 4957 4307 4956 4306 4958 4309 4957 4307 4949 4303 4956 4306 4952 4308 4957 4307 4959 4310 4959 4310 4957 4307 4958 4309 4959 4310 4958 4309 4961 4311 4963 4312 4959 4310 4961 4311 4968 4313 4959 4310 4969 4314 4959 4310 4963 4312 4969 4314 4962 4315 4968 4313 4971 4316 4970 4317 4968 4313 4969 4314 4976 4318 4968 4313 4970 4317 4977 4319 4978 4320 4974 4321 4979 4322 4971 4316 4968 4313 4979 4322 4968 4313 4976 4318 4976 4318 4986 4323 4979 4322 4979 4322 4987 4324 4988 4325 4986 4323 4987 4324 4979 4322 4982 4326 4979 4322 4988 4325 4991 4327 4984 4328 4992 4329 4993 4330 4982 4326 4988 4325 5000 4331 4989 4332 4985 4333 4995 4334 4988 4325 4987 4324 4997 4335 4996 4336 4998 4337 4996 4336 4993 4330 4999 4338 5000 4331 4997 4335 5001 4339 4988 4325 4995 4334 5003 4340 5002 4341 5003 4340 5004 4342 4993 4330 5005 4343 5006 4344 4993 4330 5007 4345 5005 4343 5007 4345 5008 4346 5009 4347 5006 4344 4999 4338 4993 4330 5007 4345 5003 4340 5010 4348 5009 4347 5005 4343 5007 4345 5010 4348 5003 4340 5002 4341 5011 4349 5012 4350 4996 4336 5007 4345 5010 4348 5008 4346 4955 4305 4949 4303 4948 4302 7473 4351 5016 4351 7432 4351 7624 4352 5017 4352 7585 4352 5021 4353 5022 4353 5023 4353 5026 4354 5023 4354 5022 4354 5031 4355 5032 4355 5027 4355 5030 4356 4877 4356 5029 4356 5046 4357 5047 4358 5048 4359 5051 4360 5052 4360 5049 4360 5055 4361 5056 4362 5051 4363 5057 4364 5059 4365 5060 4366 5064 4367 5059 4365 5065 4368 5067 4369 5065 4368 5068 4370 5070 4371 5072 4372 5073 4373 5077 4374 5078 4375 5079 4376 5079 4376 5080 4377 5081 4378 5083 4379 5080 4377 5085 4380 5085 4380 5080 4377 5087 4381 5088 4382 5085 4380 5087 4381 5089 4383 5090 4384 5091 4385 5087 4381 5092 4386 5093 4387 5091 4385 5094 4388 5089 4383 5095 4389 5096 4390 5092 4386 5092 4386 5096 4390 5093 4387 5092 4386 5097 4391 5095 4389 5097 4391 5092 4386 5098 4392 5099 4393 5098 4392 5100 4394 5092 4386 5100 4394 5098 4392 5100 4394 5101 4395 5099 4393 5102 4396 5103 4397 5104 4398 5102 4396 5101 4395 5100 4394 5102 4396 5104 4398 5101 4395 5102 4396 5105 4240 5106 4399 5106 4399 5103 4397 5102 4396 5105 4240 5107 4400 5106 4399 5108 4401 5107 4400 5105 4240 5105 4240 5109 4402 5108 4401 5109 4402 5105 4240 4867 4242 4866 4241 5110 4403 4867 4242 5110 4403 4866 4241 5111 4404 4866 4241 5112 4405 5113 4406 5113 4406 5112 4405 5114 4407 5115 4408 5114 4407 5112 4405 5116 4409 5115 4408 5112 4405 5116 4409 5117 4410 5115 4408 5116 4409 5118 4411 5119 4412 5118 4411 5120 4413 5121 4414 5116 4409 5119 4412 5117 4410 5122 4415 5121 4414 5123 4416 5118 4411 5116 4409 5120 4413 5123 4416 5124 4417 5122 4415 5123 4416 5121 4414 5120 4413 5125 4418 5124 4417 5123 4416 5125 4418 5126 4419 5124 4417 5125 4418 5127 4420 5128 4421 5129 4422 5130 4423 5127 4420 5125 4418 5128 4421 5126 4419 5129 4422 5131 4424 5132 4425 5127 4420 5130 4423 5128 4421 5131 4424 5129 4422 5127 4420 5132 4425 5134 4426 5135 4427 5133 4428 5132 4425 5131 4424 5135 4427 5134 4426 5136 4429 5135 4427 5136 4429 5137 4430 5137 4430 5138 4431 5139 4432 5138 4431 5137 4430 5136 4429 5139 4432 5140 4433 5141 4434 5139 4432 5141 4434 5142 4435 5143 4436 5142 4435 5141 4434 5143 4436 5144 4437 5142 4435 5144 4437 5145 4438 5146 4439 5145 4438 5144 4437 5143 4436 5147 4440 5146 4439 5148 4441 5148 4441 5149 4442 5147 4440 5148 4441 5150 4443 5149 4442 5149 4442 5150 4443 5151 4444 5151 4444 5150 4443 5152 4445 5153 4446 5151 4444 5152 4445 5154 4447 5155 4448 5156 4449 5153 4446 5152 4445 5154 4447 5156 4449 5155 4448 5157 4450 5157 4450 5155 4448 5158 4451 5159 4452 5157 4450 5158 4451 5158 4451 5160 4453 5159 4452 5158 4451 5161 4454 5160 4453 5160 4453 5161 4454 5162 4455 5163 4456 5164 4457 5165 4458 5164 4457 5162 4455 5165 4458 5163 4456 5166 4459 5167 4460 5167 4460 5164 4457 5163 4456 5167 4460 5166 4459 5168 4461 5169 4462 5168 4461 5166 4459 5170 4463 5169 4462 5166 4459 5170 4463 5171 4464 5169 4462 5171 4464 5172 4465 5173 4466 5172 4465 5171 4464 5170 4463 5174 4467 5175 4468 5176 4469 5172 4465 5174 4467 5173 4466 5175 4468 5177 4470 5176 4469 5177 4470 5175 4468 5178 4471 5178 4471 5175 4468 5179 4472 5180 4473 5178 4471 5179 4472 5181 4474 5182 4475 5180 4473 5180 4473 5179 4472 5181 4474 5183 4476 5184 4477 5185 4478 5186 4479 5182 4475 5181 4474 5187 4480 5188 4481 5189 4482 5148 4441 5146 4439 5145 4438 5087 4381 5093 4387 5088 4382 5139 4432 5138 4431 5140 4433 5079 4376 5078 4375 5072 4372 5190 4483 5068 4370 5070 4371 5053 4484 5057 4364 5191 4485 5134 4426 5132 4425 5133 4428 5192 4486 5193 4487 5053 4484 5194 4488 5193 4487 5195 4489 5195 4489 5199 4490 5194 4488 5199 4490 4895 4254 5194 4488 5201 4491 5202 4492 4932 4289 5203 4493 4902 4261 4896 4255 4895 4254 5203 4493 4896 4255 5154 4447 5156 4449 5153 4446 5162 4455 5161 4454 5165 4458 5174 4467 5176 4469 5173 4466 5186 4479 5205 4494 5206 4495 5205 4494 5207 4496 5208 4497 5206 4495 5182 4475 5186 4479 5209 4498 5207 4496 5205 4494 5205 4494 5208 4497 5206 4495 5209 4498 5210 4499 5211 4500 5211 4500 5207 4496 5209 4498 5212 4501 5213 4502 5214 4503 5210 4499 5213 4502 5211 4500 5215 4504 5216 4505 5217 4506 5216 4505 5215 4504 5214 4503 5189 4482 5188 4481 5218 4507 5217 4506 5219 4508 5218 4507 5187 4480 5220 4509 5183 4476 5221 4510 5222 4511 5223 4512 5221 4510 5185 4478 5184 4477 5224 4513 5225 4514 5226 4515 5222 4511 5224 4513 5223 4512 5227 4516 5228 4517 5229 4518 5229 4518 5225 4514 5224 4513 5230 4519 5231 4520 5232 4521 5232 4521 5227 4516 5230 4519 5233 4522 5234 4523 5231 4520 5235 4524 5231 4520 5234 4523 5236 4525 5233 4522 5237 4526 5233 4522 5236 4525 5238 4527 5237 4526 5239 4528 5240 4529 5236 4525 5237 4526 5241 4530 5242 4531 5243 4532 5239 4528 5239 4528 5244 4533 5240 4529 5245 4534 5242 4531 5246 4535 5247 4536 5243 4532 5242 4531 5246 4535 5248 4537 5249 4538 5245 4534 5246 4535 5249 4538 5250 4539 5251 4540 5252 4541 5252 4541 5251 4540 5248 4537 5253 4542 5254 4543 5255 4544 5254 4543 5253 4542 5252 4541 5256 4545 5257 4546 5258 4547 5255 4544 5254 4543 5258 4547 5259 4548 5260 4549 5261 4550 5256 4545 5260 4549 5257 4546 5262 4551 5261 4550 5263 4552 5262 4551 5259 4548 5261 4550 5279 4553 5280 4554 5281 4555 5283 4556 5284 4557 5285 4558 5284 4557 5281 4555 5285 4558 5270 4559 5269 4560 5266 4561 5265 4562 5264 4563 5288 4564 7803 4565 5290 4566 5289 4567 5290 4566 5291 4568 5289 4567 5297 4569 5298 4570 5294 4571 5304 4572 5301 4573 5299 4574 5305 4575 5307 4576 5308 4577 5312 4578 5313 4579 5314 4580 5315 4581 5316 4582 5317 4583 5314 4580 5315 4581 5318 4584 5320 4585 5322 4586 5324 4587 5329 4588 5330 4589 5331 4590 5332 4591 5333 4592 5334 4593 5335 4594 5336 4595 5337 4596 5338 4597 5331 4590 5339 4598 5331 4590 5340 4599 5341 4600 5342 4601 5343 4602 5344 4603 5345 4604 5346 4605 5347 4606 5348 4607 5339 4598 5341 4600 5349 4608 5350 4609 5351 4610 5349 4608 5352 4611 5353 4612 5252 4541 5350 4609 5354 4613 5355 4614 5356 4615 5357 4616 5358 4617 5359 4618 5360 4619 5358 4617 5361 4620 5362 4621 5360 4619 5359 4618 5364 4622 5348 4607 5365 4623 5344 4603 5366 4624 5367 4625 5368 4626 5344 4603 5365 4623 5367 4625 5369 4627 5366 4624 5370 4628 5371 4629 5363 4630 5340 4599 5372 4631 5373 4632 5370 4628 5374 4633 5375 4634 5376 4635 5359 4618 5377 4636 5375 4634 5378 4637 5379 4638 5380 4639 5378 4637 5381 4640 5376 4635 5382 4641 5383 4642 5384 4643 5384 4643 5345 4604 5379 4638 5385 4644 5386 4645 5387 4646 5388 4647 5382 4641 5386 4645 5372 4631 5370 4628 5368 4626 4996 4336 5012 4350 4998 4337 5007 4345 4988 4325 5003 4340 4982 4326 4996 4336 5392 4648 4971 4316 4982 4326 5392 4648 4979 4322 4982 4326 4971 4316 5393 4649 4962 4315 4973 4650 4959 4310 4968 4313 4962 4315 4951 4651 4935 4304 4952 4308 4952 4308 4959 4310 4962 4315 4942 4297 4935 4304 4938 4293 4931 4288 4947 4652 4946 4653 4935 4304 4949 4303 4952 4308 4925 4284 4937 4292 5395 4654 4936 4299 4935 4304 4942 4297 5395 4654 4919 4277 4921 4280 4922 4281 4940 4295 4934 4291 4919 4277 5396 4655 4915 4279 4912 4271 4915 4279 5397 4656 4908 4267 4922 4281 4925 4284 4896 4255 4903 4262 4899 4257 4908 4267 4921 4280 4909 4268 5203 4493 4895 4254 5204 4657 4909 4268 4915 4279 4912 4271 5204 4657 4895 4254 5199 4490 4912 4271 5397 4656 4903 4262 5194 4488 5053 4484 5193 4487 5192 4486 5053 4484 5054 4658 4899 4257 4903 4262 5397 4656 5054 4658 5053 4484 5191 4485 5191 4485 5057 4364 5058 4659 4897 4256 4896 4255 4899 4257 5058 4659 5057 4364 5060 4366 5060 4366 5059 4365 5064 4367 5398 4660 4895 4254 4897 4256 5068 4370 5065 4368 5059 4365 5067 4369 5068 4370 5190 4483 5399 4661 5194 4488 5398 4660 5190 4483 5070 4371 5071 4662 5071 4662 5070 4371 5073 4373 5400 4663 5053 4484 5399 4661 5073 4373 5072 4372 5074 4664 5401 4665 5057 4364 5400 4663 5074 4664 5072 4372 5078 4375 5401 4665 5059 4365 5057 4364 5079 4376 5082 4666 5077 4374 5082 4666 5079 4376 5081 4378 5402 4667 5068 4370 5059 4365 5081 4378 5080 4377 5083 4379 5403 4668 5070 4371 5068 4370 5404 4669 5080 4377 5405 4670 5070 4371 5406 4671 5072 4372 5407 4672 5087 4381 5404 4669 5079 4376 5072 4372 5408 4673 5405 4670 5080 4377 5079 4376 5409 4674 5100 4394 5407 4672 5087 4381 5080 4377 5404 4669 5092 4386 5087 4381 5407 4672 5410 4675 5105 4240 5409 4674 5100 4394 5092 4386 5407 4672 4866 4241 5410 4675 5411 4676 5102 4396 5100 4394 5409 4674 5111 4404 4866 4241 5113 4406 5409 4674 5105 4240 5102 4396 5116 4409 5411 4676 5412 4677 5410 4675 4866 4241 5105 4240 5120 4413 5412 4677 5413 4678 5411 4676 5112 4405 4866 4241 5123 4416 5413 4678 5414 4679 5411 4676 5116 4409 5112 4405 5125 4418 5414 4679 5415 4680 5412 4677 5120 4413 5116 4409 5131 4424 5415 4680 5416 4681 5413 4678 5123 4416 5120 4413 5133 4428 5416 4681 5417 4682 5134 4426 5417 4682 5418 4683 5414 4679 5125 4418 5123 4416 5418 4683 5419 4684 5136 4429 5138 4431 5419 4684 5420 4685 5415 4680 5127 4420 5125 4418 5140 4433 5420 4685 5421 4686 5415 4680 5131 4424 5127 4420 5422 4687 5423 4688 5143 4436 5416 4681 5133 4428 5131 4424 5424 4689 5145 4438 5423 4688 5417 4682 5134 4426 5133 4428 5425 4690 5148 4441 5424 4689 5418 4683 5136 4429 5134 4426 5425 4690 5426 4691 5150 4443 5419 4684 5138 4431 5136 4429 5426 4691 5427 4692 5152 4445 5420 4685 5140 4433 5138 4431 5428 4693 5154 4447 5427 4692 5421 4686 5141 4434 5140 4433 5429 4694 5155 4448 5428 4693 5422 4687 5143 4436 5141 4434 5429 4694 5430 4695 5158 4451 5423 4688 5145 4438 5143 4436 5430 4695 5431 4696 5161 4454 5424 4689 5148 4441 5145 4438 5431 4696 5432 4697 5165 4458 5425 4690 5150 4443 5148 4441 5433 4698 5163 4456 5432 4697 5426 4691 5152 4445 5150 4443 5434 4699 5166 4459 5433 4698 5427 4692 5154 4447 5152 4445 5434 4699 5435 4700 5170 4463 5428 4693 5155 4448 5154 4447 5436 4701 5172 4465 5435 4700 5429 4694 5158 4451 5155 4448 5437 4702 5174 4467 5436 4701 5430 4695 5161 4454 5158 4451 5437 4702 5438 4703 5175 4468 5431 4696 5165 4458 5161 4454 5438 4703 5439 4704 5179 4472 5432 4697 5163 4456 5165 4458 5440 4705 5181 4474 5439 4704 5433 4698 5166 4459 5163 4456 5441 4706 5186 4479 5440 4705 5434 4699 5170 4463 5166 4459 5441 4706 5442 4707 5205 4494 5435 4700 5172 4465 5170 4463 5443 4708 5209 4498 5442 4707 5436 4701 5174 4467 5172 4465 5214 4503 5213 4502 5210 4499 5174 4467 5437 4702 5175 4468 5212 4501 5214 4503 5215 4504 5175 4468 5438 4703 5179 4472 5219 4508 5217 4506 5216 4505 5181 4474 5179 4472 5439 4704 5219 4508 5189 4482 5218 4507 5440 4705 5186 4479 5181 4474 5220 4509 5187 4480 5189 4482 5186 4479 5441 4706 5205 4494 5220 4509 5184 4477 5183 4476 5209 4498 5205 4494 5442 4707 5222 4511 5221 4510 5184 4477 5443 4708 5210 4499 5209 4498 5226 4515 5223 4512 5224 4513 5444 4709 5214 4503 5210 4499 5228 4517 5225 4514 5229 4518 5445 4710 5216 4505 5214 4503 5229 4518 5230 4519 5227 4516 5446 4711 5219 4508 5216 4505 5235 4524 5232 4521 5231 4520 5447 4712 5189 4482 5219 4508 5238 4527 5234 4523 5233 4522 5448 4713 5220 4509 5189 4482 5241 4530 5237 4526 5240 4529 5449 4714 5184 4477 5220 4509 5243 4532 5244 4533 5239 4528 5450 4715 5222 4511 5184 4477 5245 4534 5247 4536 5242 4531 5451 4716 5224 4513 5222 4511 5246 4535 5252 4541 5248 4537 5452 4717 5229 4518 5224 4513 5253 4542 5250 4539 5252 4541 5453 4718 5230 4519 5229 4518 5254 4543 5256 4545 5258 4547 5454 4719 5231 4520 5230 4519 5260 4549 5256 4545 5261 4550 5455 4720 5233 4522 5231 4520 5261 4550 5369 4627 5263 4552 5456 4721 5233 4522 5455 4720 5237 4526 5456 4721 5457 4722 5458 4723 5459 4724 5369 4627 5369 4627 5459 4724 5263 4552 5460 4725 5239 4528 5457 4722 5242 4531 5460 4725 5461 4726 5370 4628 5462 4727 5458 4723 5458 4723 5369 4627 5370 4628 5350 4609 5246 4535 5461 4726 5353 4612 5463 4728 5464 4729 5361 4620 5355 4614 5362 4621 5370 4628 5373 4632 5462 4727 5354 4613 5387 4646 5254 4543 5011 4349 4996 4336 4999 4338 5007 4345 4993 4330 4988 4325 4996 4336 4997 4335 4985 4333 4982 4326 4993 4330 4996 4336 4973 4650 5392 4648 4985 4333 4971 4316 5392 4648 4973 4650 5393 4649 4972 4730 5468 4731 4962 4315 4971 4316 4973 4650 4960 4732 5470 4733 5469 4734 4962 4315 5393 4649 4952 4308 4950 4735 4938 4293 4951 4651 5393 4649 4951 4651 4952 4308 4935 4304 4951 4651 4938 4293 4937 4292 5471 4736 4930 4287 4930 4287 4917 4275 5395 4654 4938 4293 4934 4291 4942 4297 4925 4284 4934 4291 4937 4292 5396 4655 4933 4290 5397 4656 4933 4290 4899 4257 5397 4656 4925 4284 5395 4654 4921 4280 5202 4492 5473 4737 4900 4258 4921 4280 4919 4277 4915 4279 4895 4254 5398 4660 5194 4488 4915 4279 5396 4655 5397 4656 5194 4488 5399 4661 5053 4484 4933 4290 4900 4258 4899 4257 5053 4484 5400 4663 5057 4364 5473 4737 4897 4256 4900 4258 5059 4365 5401 4665 5402 4667 5474 4738 5398 4660 5473 4737 5068 4370 5402 4667 5403 4668 5475 4739 5399 4661 5474 4738 5475 4739 5400 4663 5399 4661 5070 4371 5403 4668 5406 4671 5476 4740 5401 4665 5400 4663 5072 4372 5406 4671 5408 4673 5477 4741 5402 4667 5401 4665 5079 4376 5408 4673 5405 4670 5478 4742 5403 4668 5402 4667 5406 4671 5403 4668 5480 4743 5481 4744 5404 4669 5479 4745 5482 4746 5408 4673 5406 4671 5408 4673 5483 4747 5405 4670 5484 4748 5407 4672 5481 4744 5404 4669 5405 4670 5479 4745 5407 4672 5404 4669 5481 4744 5485 4749 5409 4674 5484 4748 5409 4674 5407 4672 5484 4748 5486 4750 5410 4675 5485 4749 5410 4675 5409 4674 5485 4749 5487 4751 5412 4677 5486 4750 5488 4752 5413 4678 5487 4751 5411 4676 5410 4675 5486 4750 5489 4753 5414 4679 5488 4752 5490 4754 5415 4680 5489 4753 5412 4677 5411 4676 5486 4750 5491 4755 5416 4681 5490 4754 5413 4678 5412 4677 5487 4751 5492 4756 5417 4682 5491 4755 5493 4757 5418 4683 5492 4756 5414 4679 5413 4678 5488 4752 5494 4758 5419 4684 5493 4757 5495 4759 5420 4685 5494 4758 5415 4680 5414 4679 5489 4753 5496 4760 5421 4686 5495 4759 5141 4434 5421 4686 5422 4687 5490 4754 5416 4681 5415 4680 5422 4687 5496 4760 5497 4761 5491 4755 5417 4682 5416 4681 5423 4688 5497 4761 5498 4762 5492 4756 5418 4683 5417 4682 5424 4689 5498 4762 5499 4763 5493 4757 5419 4684 5418 4683 5425 4690 5499 4763 5500 4764 5494 4758 5420 4685 5419 4684 5426 4691 5500 4764 5501 4765 5495 4759 5421 4686 5420 4685 5427 4692 5501 4765 5502 4766 5496 4760 5422 4687 5421 4686 5428 4693 5502 4766 5503 4767 5497 4761 5423 4688 5422 4687 5429 4694 5503 4767 5504 4768 5498 4762 5424 4689 5423 4688 5430 4695 5504 4768 5505 4769 5499 4763 5425 4690 5424 4689 5431 4696 5505 4769 5506 4770 5500 4764 5426 4691 5425 4690 5432 4697 5506 4770 5507 4771 5501 4765 5427 4692 5426 4691 5433 4698 5507 4771 5508 4772 5502 4766 5428 4693 5427 4692 5434 4699 5508 4772 5509 4773 5503 4767 5429 4694 5428 4693 5435 4700 5509 4773 5510 4774 5504 4768 5430 4695 5429 4694 5436 4701 5510 4774 5511 4775 5505 4769 5431 4696 5430 4695 5437 4702 5511 4775 5512 4776 5506 4770 5432 4697 5431 4696 5513 4777 5439 4704 5514 4778 5507 4771 5433 4698 5432 4697 5515 4779 5440 4705 5513 4777 5508 4772 5434 4699 5433 4698 5516 4780 5441 4706 5515 4779 5509 4773 5435 4700 5434 4699 5517 4781 5442 4707 5516 4780 5510 4774 5436 4701 5435 4700 5511 4775 5437 4702 5436 4701 5210 4499 5443 4708 5444 4709 5437 4702 5512 4776 5438 4703 5214 4503 5444 4709 5445 4710 5439 4704 5438 4703 5514 4778 5216 4505 5445 4710 5446 4711 5513 4777 5440 4705 5439 4704 5219 4508 5446 4711 5447 4712 5440 4705 5515 4779 5441 4706 5189 4482 5447 4712 5448 4713 5442 4707 5441 4706 5516 4780 5220 4509 5448 4713 5449 4714 5517 4781 5443 4708 5442 4707 5184 4477 5449 4714 5450 4715 5517 4781 5444 4709 5443 4708 5222 4511 5450 4715 5451 4716 5518 4782 5445 4710 5444 4709 5224 4513 5451 4716 5452 4717 5518 4782 5446 4711 5445 4710 5229 4518 5452 4717 5453 4718 5519 4783 5447 4712 5446 4711 5230 4519 5453 4718 5454 4719 5519 4783 5448 4713 5447 4712 5231 4520 5454 4719 5455 4720 5520 4784 5449 4714 5448 4713 5456 4721 5237 4526 5233 4522 5520 4784 5450 4715 5449 4714 5237 4526 5457 4722 5239 4528 5521 4785 5451 4716 5450 4715 5239 4528 5460 4725 5242 4531 5522 4786 5452 4717 5451 4716 5242 4531 5461 4726 5246 4535 5523 4787 5453 4718 5452 4717 5246 4535 5350 4609 5252 4541 5524 4788 5454 4719 5453 4718 5252 4541 5354 4613 5254 4543 5525 4789 5455 4720 5454 4719 5254 4543 5387 4646 5256 4545 5526 4790 5456 4721 5455 4720 5457 4722 5456 4721 5527 4791 5528 4792 5261 4550 5256 4545 5256 4545 5387 4646 5528 4792 5529 4793 5460 4725 5457 4722 5460 4725 5529 4793 5530 4794 5261 4550 5531 4795 5369 4627 5531 4795 5261 4550 5528 4792 5351 4610 5461 4726 5530 4794 5347 4606 5532 4796 5380 4639 5531 4795 5366 4624 5369 4627 5385 4644 5354 4613 5349 4608 5370 4628 5366 4624 5368 4626 5001 4339 4997 4335 4998 4337 5000 4331 5465 4797 5534 4798 5534 4798 5390 4799 5000 4331 4996 4336 4985 4333 5392 4648 4972 4730 4985 4333 4989 4332 4973 4650 4985 4333 4972 4730 5537 4800 5468 4731 5536 4801 4972 4730 5393 4649 4973 4650 5468 4731 5537 4800 4950 4735 5393 4649 5468 4731 4951 4651 5471 4736 4950 4735 4947 4652 4950 4735 4951 4651 5468 4731 5394 4802 5538 4803 4927 4804 4938 4293 4950 4735 5471 4736 5471 4736 4937 4292 4938 4293 4918 4276 5539 4805 5396 4655 4930 4287 5395 4654 4937 4292 4919 4277 5395 4654 4917 4275 5396 4655 4919 4277 4918 4276 4897 4256 5473 4737 5398 4660 5396 4655 5539 4805 4933 4290 5398 4660 5474 4738 5399 4661 4932 4289 4933 4290 5539 4805 5400 4663 5475 4739 5476 4740 5202 4492 4900 4258 4932 4289 5401 4665 5476 4740 5477 4741 5542 4806 5473 4737 5202 4492 5402 4667 5477 4741 5478 4742 5543 4807 5474 4738 5542 4806 5403 4668 5478 4742 5480 4743 5543 4807 5476 4740 5475 4739 5406 4671 5480 4743 5482 4746 5544 4808 5477 4741 5476 4740 5408 4673 5482 4746 5483 4747 5545 4809 5478 4742 5477 4741 5405 4670 5483 4747 5479 4745 5546 4810 5480 4743 5478 4742 5480 4743 5548 4811 5482 4746 5550 4812 5481 4744 5547 4813 5483 4747 5482 4746 5549 4814 5549 4814 5479 4745 5483 4747 5551 4815 5484 4748 5550 4812 5547 4813 5481 4744 5479 4745 5550 4812 5484 4748 5481 4744 5552 4816 5486 4750 5551 4815 5551 4815 5485 4749 5484 4748 5553 4817 5487 4751 5552 4816 5551 4815 5486 4750 5485 4749 5554 4818 5488 4752 5553 4817 5555 4819 5489 4753 5554 4818 5487 4751 5486 4750 5552 4816 5556 4820 5490 4754 5555 4819 5488 4752 5487 4751 5553 4817 5557 4821 5492 4756 5556 4820 5558 4822 5493 4757 5557 4821 5489 4753 5488 4752 5554 4818 5559 4823 5494 4758 5558 4822 5560 4824 5495 4759 5559 4823 5490 4754 5489 4753 5555 4819 5561 4825 5496 4760 5560 4824 5562 4826 5497 4761 5561 4825 5491 4755 5490 4754 5556 4820 5563 4827 5498 4762 5562 4826 5492 4756 5491 4755 5556 4820 5564 4828 5499 4763 5563 4827 5493 4757 5492 4756 5557 4821 5565 4829 5500 4764 5564 4828 5494 4758 5493 4757 5558 4822 5566 4830 5501 4765 5565 4829 5495 4759 5494 4758 5559 4823 5567 4831 5502 4766 5566 4830 5496 4760 5495 4759 5560 4824 5568 4832 5503 4767 5567 4831 5497 4761 5496 4760 5561 4825 5569 4833 5504 4768 5568 4832 5498 4762 5497 4761 5562 4826 5570 4834 5505 4769 5569 4833 5499 4763 5498 4762 5563 4827 5571 4835 5506 4770 5570 4834 5500 4764 5499 4763 5564 4828 5572 4836 5507 4771 5571 4835 5501 4765 5500 4764 5565 4829 5573 4837 5508 4772 5572 4836 5502 4766 5501 4765 5566 4830 5574 4838 5509 4773 5573 4837 5503 4767 5502 4766 5567 4831 5575 4839 5510 4774 5574 4838 5504 4768 5503 4767 5568 4832 5576 4840 5511 4775 5575 4839 5505 4769 5504 4768 5569 4833 5577 4841 5512 4776 5576 4840 5506 4770 5505 4769 5570 4834 5438 4703 5512 4776 5514 4778 5571 4835 5507 4771 5506 4770 5514 4778 5577 4841 5578 4842 5572 4836 5508 4772 5507 4771 5573 4837 5509 4773 5508 4772 5515 4779 5578 4842 5579 4843 5574 4838 5510 4774 5509 4773 5575 4839 5511 4775 5510 4774 5517 4781 5579 4843 5580 4844 5576 4840 5512 4776 5511 4775 5444 4709 5517 4781 5518 4782 5512 4776 5577 4841 5514 4778 5513 4777 5514 4778 5578 4842 5446 4711 5518 4782 5519 4783 5578 4842 5515 4779 5513 4777 5515 4779 5579 4843 5516 4780 5448 4713 5519 4783 5520 4784 5517 4781 5516 4780 5579 4843 5450 4715 5520 4784 5521 4785 5580 4844 5518 4782 5517 4781 5451 4716 5521 4785 5522 4786 5452 4717 5522 4786 5523 4787 5581 4845 5519 4783 5518 4782 5453 4718 5523 4787 5524 4788 5454 4719 5524 4788 5525 4789 5582 4846 5520 4784 5519 4783 5455 4720 5525 4789 5526 4790 5456 4721 5526 4790 5527 4791 5583 4847 5521 4785 5520 4784 5457 4722 5527 4791 5529 4793 5583 4847 5522 4786 5521 4785 5530 4794 5461 4726 5460 4725 5584 4848 5523 4787 5522 4786 5461 4726 5351 4610 5350 4609 5585 4849 5524 4788 5523 4787 5350 4609 5349 4608 5354 4613 5586 4850 5525 4789 5524 4788 5354 4613 5385 4644 5387 4646 5587 4851 5526 4790 5525 4789 5387 4646 5386 4645 5528 4792 5588 4852 5527 4791 5526 4790 5529 4793 5527 4791 5589 4853 5590 4854 5531 4795 5528 4792 5528 4792 5386 4645 5590 4854 5591 4855 5530 4794 5529 4793 5351 4610 5530 4794 5592 4856 5531 4795 5593 4857 5366 4624 5593 4857 5531 4795 5590 4854 5352 4611 5351 4610 5592 4856 5532 4796 5594 4858 5381 4640 5326 4859 5356 4615 5595 4860 5385 4644 5353 4612 5388 4647 5368 4626 5365 4623 5372 4631 5465 4797 5000 4331 5001 4339 5390 4799 5389 4861 5391 4862 5000 4331 4985 4333 4997 4335 5910 4863 5597 4864 5598 4865 5536 4801 4989 4332 5599 4866 5600 4867 5536 4801 5599 4866 4989 4332 5536 4801 4972 4730 5601 4868 5537 4800 5600 4867 5468 4731 4972 4730 5536 4801 5537 4800 5601 4868 4947 4652 5469 4734 5470 4733 5602 4869 5537 4800 4947 4652 4950 4735 5471 4736 4947 4652 4931 4288 4928 4870 5472 4871 4929 4286 4929 4286 5605 4872 4918 4276 4931 4288 4930 4287 5471 4736 5605 4872 5541 4873 5539 4805 4917 4275 4930 4287 4929 4286 5606 4874 5201 4491 4906 4265 4918 4276 4917 4275 4929 4286 5473 4737 5542 4806 5474 4738 4918 4276 5605 4872 5539 4805 5474 4738 5543 4807 5475 4739 4932 4289 5539 4805 5541 4873 5201 4491 4932 4289 5541 4873 5476 4740 5543 4807 5544 4808 5606 4874 5202 4492 5201 4491 5477 4741 5544 4808 5545 4809 5607 4875 5542 4806 5606 4874 5607 4875 5543 4807 5542 4806 5478 4742 5545 4809 5546 4810 5480 4743 5546 4810 5548 4811 5609 4876 5544 4808 5543 4807 5482 4746 5548 4811 5549 4814 5610 4877 5545 4809 5544 4808 5611 4878 5546 4810 5545 4809 5479 4745 5549 4814 5547 4813 5612 4879 5548 4811 5546 4810 5547 4813 5613 4880 5614 4881 5548 4811 5615 4882 5549 4814 5550 4812 5614 4881 5616 4883 5613 4880 5547 4813 5549 4814 5616 4883 5617 4884 5551 4815 5614 4881 5550 4812 5547 4813 5616 4883 5551 4815 5550 4812 5617 4884 5618 4885 5552 4816 5619 4886 5552 4816 5618 4885 5620 4887 5553 4817 5619 4886 5617 4884 5552 4816 5551 4815 5621 4888 5554 4818 5620 4887 5622 4889 5555 4819 5621 4888 5619 4886 5553 4817 5552 4816 5623 4890 5556 4820 5622 4889 5620 4887 5554 4818 5553 4817 5624 4891 5558 4822 5623 4890 5625 4892 5559 4823 5624 4891 5621 4888 5555 4819 5554 4818 5626 4893 5560 4824 5625 4892 5627 4894 5561 4825 5626 4893 5622 4889 5556 4820 5555 4819 5628 4895 5562 4826 5627 4894 5629 4896 5563 4827 5628 4895 5623 4890 5557 4821 5556 4820 5630 4897 5564 4828 5629 4896 5623 4890 5558 4822 5557 4821 5631 4898 5565 4829 5630 4897 5624 4891 5559 4823 5558 4822 5632 4899 5566 4830 5631 4898 5625 4892 5560 4824 5559 4823 5633 4900 5567 4831 5632 4899 5626 4893 5561 4825 5560 4824 5634 4901 5568 4832 5633 4900 5627 4894 5562 4826 5561 4825 5635 4902 5569 4833 5634 4901 5628 4895 5563 4827 5562 4826 5636 4903 5570 4834 5635 4902 5629 4896 5564 4828 5563 4827 5637 4904 5571 4835 5636 4903 5630 4897 5565 4829 5564 4828 5638 4905 5572 4836 5637 4904 5631 4898 5566 4830 5565 4829 5639 4906 5573 4837 5638 4905 5632 4899 5567 4831 5566 4830 5640 4907 5574 4838 5639 4906 5633 4900 5568 4832 5567 4831 5641 4908 5575 4839 5640 4907 5634 4901 5569 4833 5568 4832 5642 4909 5576 4840 5641 4908 5635 4902 5570 4834 5569 4833 5643 4910 5577 4841 5642 4909 5636 4903 5571 4835 5570 4834 5637 4904 5572 4836 5571 4835 5644 4911 5578 4842 5643 4910 5573 4837 5572 4836 5638 4905 5574 4838 5573 4837 5639 4906 5645 4912 5579 4843 5644 4911 5575 4839 5574 4838 5640 4907 5576 4840 5575 4839 5641 4908 5642 4909 5577 4841 5576 4840 5518 4782 5580 4844 5581 4845 5577 4841 5643 4910 5578 4842 5519 4783 5581 4845 5582 4846 5644 4911 5579 4843 5578 4842 5580 4844 5579 4843 5645 4912 5520 4784 5582 4846 5583 4847 5646 4913 5581 4845 5580 4844 5522 4786 5583 4847 5584 4848 5523 4787 5584 4848 5585 4849 5647 4914 5582 4846 5581 4845 5524 4788 5585 4849 5586 4850 5525 4789 5586 4850 5587 4851 5526 4790 5587 4851 5588 4852 5648 4915 5583 4847 5582 4846 5527 4791 5588 4852 5589 4853 5529 4793 5589 4853 5591 4855 5650 4916 5584 4848 5583 4847 5530 4794 5591 4855 5592 4856 5651 4917 5585 4849 5584 4848 5352 4611 5349 4608 5351 4610 5651 4917 5586 4850 5585 4849 5349 4608 5353 4612 5385 4644 5652 4918 5587 4851 5586 4850 5385 4644 5388 4647 5386 4645 5653 4919 5588 4852 5587 4851 5386 4645 5382 4641 5590 4854 5654 4920 5589 4853 5588 4852 5591 4855 5589 4853 5655 4921 5656 4922 5593 4857 5590 4854 5590 4854 5382 4641 5656 4922 5657 4923 5592 4856 5591 4855 5352 4611 5592 4856 5658 4924 5593 4857 5659 4925 5366 4624 5659 4925 5593 4857 5656 4922 5463 4728 5353 4612 5352 4611 5383 4642 5464 4729 5346 4605 5659 4925 5367 4625 5366 4624 5464 4729 5383 4642 5388 4647 5368 4626 5367 4625 5365 4623 5389 4861 5390 4799 5534 4798 5466 4926 5725 4927 5391 4862 5000 4331 5390 4799 4990 4928 4990 4928 4989 4332 5000 4331 4981 4929 4983 4930 5598 4865 5599 4866 4990 4928 4994 4931 5599 4866 4989 4332 4990 4928 5661 4932 5662 4933 5600 4867 5663 4934 5601 4868 5662 4933 5537 4800 5536 4801 5600 4867 5663 4934 4946 4653 5601 4868 5394 4802 4928 4870 4946 4653 4947 4652 5601 4868 4946 4653 5792 4935 5727 4936 5664 4937 4927 4804 5666 4938 5472 4871 4928 4870 4931 4288 4946 4653 4929 4286 4931 4288 4928 4870 5472 4871 5540 4939 5541 4873 5667 4940 5852 4941 4887 4942 5605 4872 4929 4286 5472 4871 5202 4492 5606 4874 5542 4806 5605 4872 5472 4871 5541 4873 5543 4807 5607 4875 5608 4943 5541 4873 5540 4939 5201 4491 5201 4491 5540 4939 4906 4265 5543 4807 5608 4943 5609 4876 4905 4264 5606 4874 4906 4265 5544 4808 5609 4876 5610 4877 4905 4264 5607 4875 5606 4874 5545 4809 5610 4877 5611 4878 5668 4944 5608 4943 5607 4875 5546 4810 5611 4878 5612 4879 5669 4945 5609 4876 5608 4943 5548 4811 5612 4879 5615 4882 5670 4946 5610 4877 5609 4876 5549 4814 5615 4882 5613 4880 5671 4947 5611 4878 5610 4877 5672 4948 5612 4879 5611 4878 5612 4879 5674 4949 5615 4882 5676 4950 5614 4881 5673 4951 5613 4880 5615 4882 5675 4952 5673 4951 5614 4881 5613 4880 5616 4883 5676 4950 5677 4953 5676 4950 5616 4883 5614 4881 5617 4884 5677 4953 5678 4954 5677 4953 5617 4884 5616 4883 5618 4885 5678 4954 5679 4955 5620 4887 5679 4955 5680 4956 5678 4954 5618 4885 5617 4884 5621 4888 5680 4956 5681 4957 5679 4955 5619 4886 5618 4885 5622 4889 5681 4957 5682 4958 5679 4955 5620 4887 5619 4886 5683 4959 5684 4960 5624 4891 5680 4956 5621 4888 5620 4887 5684 4960 5685 4961 5625 4892 5685 4961 5686 4962 5626 4893 5681 4957 5622 4889 5621 4888 5686 4962 5687 4963 5627 4894 5687 4963 5688 4964 5628 4895 5682 4958 5623 4890 5622 4889 5688 4964 5689 4965 5629 4896 5689 4965 5690 4966 5630 4897 5683 4959 5624 4891 5623 4890 5690 4966 5691 4967 5631 4898 5684 4960 5625 4892 5624 4891 5691 4967 5692 4968 5632 4899 5685 4961 5626 4893 5625 4892 5692 4968 5693 4969 5633 4900 5686 4962 5627 4894 5626 4893 5693 4969 5694 4970 5634 4901 5687 4963 5628 4895 5627 4894 5694 4970 5695 4971 5635 4902 5688 4964 5629 4896 5628 4895 5695 4971 5696 4972 5636 4903 5689 4965 5630 4897 5629 4896 5696 4972 5697 4973 5637 4904 5690 4966 5631 4898 5630 4897 5697 4973 5698 4974 5638 4905 5691 4967 5632 4899 5631 4898 5699 4975 5639 4906 5698 4974 5692 4968 5633 4900 5632 4899 5700 4976 5640 4907 5699 4975 5693 4969 5634 4901 5633 4900 5701 4977 5641 4908 5700 4976 5694 4970 5635 4902 5634 4901 5695 4971 5636 4903 5635 4902 5702 4978 5643 4910 5701 4977 5696 4972 5637 4904 5636 4903 5697 4973 5638 4905 5637 4904 5703 4979 5644 4911 5702 4978 5698 4974 5639 4906 5638 4905 5699 4975 5640 4907 5639 4906 5704 4980 5645 4912 5703 4979 5700 4976 5641 4908 5640 4907 5701 4977 5642 4909 5641 4908 5580 4844 5645 4912 5646 4913 5642 4909 5701 4977 5643 4910 5581 4845 5646 4913 5647 4914 5702 4978 5644 4911 5643 4910 5582 4846 5647 4914 5648 4915 5645 4912 5644 4911 5703 4979 5583 4847 5648 4915 5649 4981 5704 4980 5646 4913 5645 4912 5583 4847 5649 4981 5650 4916 5584 4848 5650 4916 5651 4917 5705 4982 5647 4914 5646 4913 5586 4850 5651 4917 5652 4918 5707 4983 5648 4915 5647 4914 5587 4851 5652 4918 5653 4919 5588 4852 5653 4919 5654 4920 5709 4984 5649 4981 5648 4915 5589 4853 5654 4920 5655 4921 5710 4985 5650 4916 5649 4981 5591 4855 5655 4921 5657 4923 5711 4986 5651 4917 5650 4916 5592 4856 5657 4923 5658 4924 5352 4611 5658 4924 5463 4728 5712 4987 5652 4918 5651 4917 5464 4729 5388 4647 5353 4612 5713 4988 5653 4919 5652 4918 5388 4647 5383 4642 5382 4641 5714 4989 5654 4920 5653 4919 5382 4641 5384 4643 5656 4922 5715 4990 5655 4921 5654 4920 5657 4923 5655 4921 5716 4991 5717 4992 5659 4925 5656 4922 5656 4922 5384 4643 5717 4992 5718 4993 5658 4924 5657 4923 5463 4728 5658 4924 5719 4994 5720 4995 5464 4729 5463 4728 5330 4589 5533 4996 5340 4599 5345 4604 5383 4642 5346 4605 5371 4629 5722 4997 5723 4998 5725 4927 5660 4999 5535 5000 4994 4931 5390 4799 5391 4862 5724 5001 4994 4931 5725 4927 5661 4932 4994 4931 5724 5001 5599 4866 4994 4931 5661 4932 5662 4933 5726 5002 5469 4734 5661 4932 5600 4867 5599 4866 5600 4867 5662 4933 5601 4868 5602 4869 5394 4802 5663 4934 5603 5003 5727 4936 5604 5004 5394 4802 4946 4653 5663 4934 4927 4804 5538 4803 5665 5005 5394 4802 4927 4804 4928 4870 5666 4938 5730 5006 5540 4939 5472 4871 4928 4870 4927 4804 5607 4875 4905 4264 5668 4944 5472 4871 5666 4938 5540 4939 5608 4943 5668 4944 5669 4945 5540 4939 5730 5006 4906 4265 4906 4265 5730 5006 4904 4263 5609 4876 5669 4945 5670 4946 5610 4877 5670 4946 5671 4947 5731 5007 5668 4944 4905 4264 5611 4878 5671 4947 5672 4948 5732 5008 5669 4945 5668 4944 5612 4879 5672 4948 5674 4949 5733 5009 5670 4946 5669 4945 5615 4882 5674 4949 5675 4952 5734 5010 5671 4947 5670 4946 5735 5011 5672 4948 5671 4947 5613 4880 5675 4952 5673 4951 5736 5012 5674 4949 5672 4948 5674 4949 5736 5012 5675 4952 5739 5013 5676 4950 5737 5014 5738 5015 5673 4951 5675 4952 5740 5016 5677 4953 5739 5013 5737 5014 5676 4950 5673 4951 5741 5017 5677 4953 5740 5016 5677 4953 5676 4950 5739 5013 5742 5018 5679 4955 5741 5017 5678 4954 5677 4953 5741 5017 5743 5019 5680 4956 5742 5018 5744 5020 5681 4957 5743 5019 5679 4955 5678 4954 5741 5017 5745 5021 5682 4958 5744 5020 5623 4890 5682 4958 5683 4959 5742 5018 5680 4956 5679 4955 5683 4959 5745 5021 5746 5022 5743 5019 5681 4957 5680 4956 5684 4960 5746 5022 5747 5023 5685 4961 5747 5023 5748 5024 5744 5020 5682 4958 5681 4957 5686 4962 5748 5024 5749 5025 5687 4963 5749 5025 5750 5026 5745 5021 5683 4959 5682 4958 5688 4964 5750 5026 5751 5027 5689 4965 5751 5027 5752 5028 5746 5022 5684 4960 5683 4959 5690 4966 5752 5028 5753 5029 5747 5023 5685 4961 5684 4960 5691 4967 5753 5029 5754 5030 5748 5024 5686 4962 5685 4961 5692 4968 5754 5030 5755 5031 5749 5025 5687 4963 5686 4962 5693 4969 5755 5031 5756 5032 5750 5026 5688 4964 5687 4963 5694 4970 5756 5032 5757 5033 5751 5027 5689 4965 5688 4964 5695 4971 5757 5033 5758 5034 5752 5028 5690 4966 5689 4965 5696 4972 5758 5034 5759 5035 5753 5029 5691 4967 5690 4966 5697 4973 5759 5035 5760 5036 5754 5030 5692 4968 5691 4967 5698 4974 5760 5036 5761 5037 5755 5031 5693 4969 5692 4968 5699 4975 5761 5037 5762 5038 5756 5032 5694 4970 5693 4969 5763 5039 5764 5040 5701 4977 5757 5033 5695 4971 5694 4970 5758 5034 5696 4972 5695 4971 5764 5040 5765 5041 5702 4978 5759 5035 5697 4973 5696 4972 5760 5036 5698 4974 5697 4973 5761 5037 5699 4975 5698 4974 5765 5041 5766 5042 5703 4979 5762 5038 5700 4976 5699 4975 5763 5039 5701 4977 5700 4976 5766 5042 5767 5043 5704 4980 5646 4913 5704 4980 5705 4982 5701 4977 5764 5040 5702 4978 5647 4914 5705 4982 5706 5044 5765 5041 5703 4979 5702 4978 5647 4914 5706 5044 5707 4983 5648 4915 5707 4983 5708 5045 5704 4980 5703 4979 5766 5042 5648 4915 5708 5045 5709 4984 5649 4981 5709 4984 5710 4985 5767 5043 5705 4982 5704 4980 5650 4916 5710 4985 5711 4986 5768 5046 5706 5044 5705 4982 5651 4917 5711 4986 5712 4987 5769 5047 5707 4983 5706 5044 5652 4918 5712 4987 5713 4988 5770 5048 5708 5045 5707 4983 5653 4919 5713 4988 5714 4989 5771 5049 5709 4984 5708 5045 5654 4920 5714 4989 5715 4990 5772 5050 5710 4985 5709 4984 5655 4921 5715 4990 5716 4991 5773 5051 5711 4986 5710 4985 5657 4923 5716 4991 5718 4993 5658 4924 5718 4993 5719 4994 5775 5052 5712 4987 5711 4986 5463 4728 5719 4994 5720 4995 5776 5053 5713 4988 5712 4987 5464 4729 5720 4995 5346 4605 5776 5053 5714 4989 5713 4988 5345 4604 5384 4643 5383 4642 5777 5054 5715 4990 5714 4989 5384 4643 5379 4638 5717 4992 5778 5055 5716 4991 5715 4990 5718 4993 5716 4991 5779 5056 5780 5057 5659 4925 5717 4992 5717 4992 5379 4638 5780 5057 5781 5058 5719 4994 5718 4993 5720 4995 5719 4994 5782 5059 5659 4925 5342 4601 5367 4625 5342 4601 5659 4925 5780 5057 5783 5060 5346 4605 5720 4995 5324 4587 5328 5061 5595 4860 5342 4601 5344 4603 5367 4625 5345 4604 5347 4606 5380 4639 5660 4999 5725 4927 5466 4926 5390 4799 4994 4931 4990 4928 5596 5062 4991 4327 5535 5000 5724 5001 5535 5000 4992 4329 5726 5002 5724 5001 5785 5063 5785 5063 4960 4732 5726 5002 5661 4932 5724 5001 5726 5002 5726 5002 5662 4933 5661 4932 4974 4321 4975 5064 5789 5065 5663 4934 5662 4933 5469 4734 5792 4935 5538 4803 5602 4869 5602 4869 5663 4934 5469 4734 5538 4803 5394 4802 5602 4869 5665 5005 5667 4940 5666 4938 5666 4938 4927 4804 5665 5005 4905 4264 4904 4263 5731 5007 5668 4944 5731 5007 5732 5008 5667 4940 5730 5006 5666 4938 5669 4945 5732 5008 5733 5009 4904 4263 5730 5006 5667 4940 4890 5066 4904 4263 5667 4940 5670 4946 5733 5009 5734 5010 4890 5066 5731 5007 4904 4263 5671 4947 5734 5010 5735 5011 5795 5067 5732 5008 5731 5007 5672 4948 5735 5011 5736 5012 5796 5068 5733 5009 5732 5008 5797 5069 5734 5010 5733 5009 5675 4952 5736 5012 5738 5015 5798 5070 5735 5011 5734 5010 5799 5071 5736 5012 5735 5011 5673 4951 5738 5015 5737 5014 5802 5072 5801 5073 5737 5014 5736 5012 5800 5074 5738 5015 5803 5075 5739 5013 5801 5073 5802 5072 5737 5014 5738 5015 5804 5076 5740 5016 5803 5075 5801 5073 5739 5013 5737 5014 5805 5077 5741 5017 5804 5076 5803 5075 5740 5016 5739 5013 5806 5078 5742 5018 5805 5077 5804 5076 5741 5017 5740 5016 5807 5079 5743 5019 5806 5078 5805 5077 5742 5018 5741 5017 5808 5080 5744 5020 5807 5079 5809 5081 5745 5021 5808 5080 5806 5078 5743 5019 5742 5018 5810 5082 5746 5022 5809 5081 5807 5079 5744 5020 5743 5019 5811 5083 5748 5024 5810 5082 5812 5084 5749 5025 5811 5083 5808 5080 5745 5021 5744 5020 5813 5085 5750 5026 5812 5084 5814 5086 5751 5027 5813 5085 5809 5081 5746 5022 5745 5021 5815 5087 5752 5028 5814 5086 5816 5088 5753 5029 5815 5087 5810 5082 5747 5023 5746 5022 5817 5089 5754 5030 5816 5088 5810 5082 5748 5024 5747 5023 5818 5090 5755 5031 5817 5089 5811 5083 5749 5025 5748 5024 5819 5091 5756 5032 5818 5090 5812 5084 5750 5026 5749 5025 5820 5092 5757 5033 5819 5091 5813 5085 5751 5027 5750 5026 5821 5093 5758 5034 5820 5092 5814 5086 5752 5028 5751 5027 5822 5094 5759 5035 5821 5093 5815 5087 5753 5029 5752 5028 5823 5095 5760 5036 5822 5094 5754 5030 5753 5029 5816 5088 5824 5096 5761 5037 5823 5095 5755 5031 5754 5030 5817 5089 5825 5097 5762 5038 5824 5096 5756 5032 5755 5031 5818 5090 5700 4976 5762 5038 5763 5039 5819 5091 5757 5033 5756 5032 5763 5039 5825 5097 5826 5098 5820 5092 5758 5034 5757 5033 5821 5093 5759 5035 5758 5034 5764 5040 5826 5098 5827 5099 5822 5094 5760 5036 5759 5035 5823 5095 5761 5037 5760 5036 5765 5041 5827 5099 5828 5100 5824 5096 5762 5038 5761 5037 5825 5097 5763 5039 5762 5038 5826 5098 5764 5040 5763 5039 5766 5042 5828 5100 5829 5101 5764 5040 5827 5099 5765 5041 5705 4982 5767 5043 5768 5046 5706 5044 5768 5046 5769 5047 5707 4983 5769 5047 5770 5048 5765 5041 5828 5100 5766 5042 5708 5045 5770 5048 5771 5049 5709 4984 5771 5049 5772 5050 5829 5101 5767 5043 5766 5042 5710 4985 5772 5050 5773 5051 5711 4986 5773 5051 5774 5102 5830 5103 5768 5046 5767 5043 5711 4986 5774 5102 5775 5052 5831 5104 5769 5047 5768 5046 5712 4987 5775 5052 5776 5053 5832 5105 5770 5048 5769 5047 5833 5106 5771 5049 5770 5048 5714 4989 5776 5053 5777 5054 5834 5107 5772 5050 5771 5049 5715 4990 5777 5054 5778 5055 5835 5108 5773 5051 5772 5050 5716 4991 5778 5055 5779 5056 5836 5109 5774 5102 5773 5051 5718 4993 5779 5056 5781 5058 5837 5110 5775 5052 5774 5102 5719 4994 5781 5058 5782 5059 5838 5111 5776 5053 5775 5052 5720 4995 5782 5059 5783 5060 5346 4605 5783 5060 5347 4606 5839 5112 5777 5054 5776 5053 5380 4639 5379 4638 5345 4604 5840 5113 5778 5055 5777 5054 5379 4638 5378 4637 5780 5057 5841 5114 5779 5056 5778 5055 5781 5058 5779 5056 5842 5115 5843 5116 5342 4601 5780 5057 5780 5057 5378 4637 5843 5116 5844 5117 5782 5059 5781 5058 5783 5060 5782 5059 5845 5118 5846 5119 5347 4606 5783 5060 5378 4637 5380 4639 5381 4640 5365 4623 5363 4630 5372 4631 5725 4927 4994 4931 5391 4862 4991 4327 5784 5120 5910 4863 5535 5000 5724 5001 5725 4927 5785 5063 4992 4329 4984 4328 5785 5063 5724 5001 4992 4329 5850 5121 4960 4732 4965 5122 5604 5004 5470 4733 5850 5121 5469 4734 5726 5002 4960 4732 5604 5004 5792 4935 5470 4733 5792 4935 5602 4869 5470 4733 5664 4937 5852 4941 5665 5005 5792 4935 5664 4937 5538 4803 5664 4937 5665 5005 5538 4803 4893 5123 5853 5124 6042 5125 5731 5007 4890 5066 5795 5067 5852 4941 5667 4940 5665 5005 5732 5008 5795 5067 5796 5068 5733 5009 5796 5068 5797 5069 4890 5066 5667 4940 4887 4942 5734 5010 5797 5069 5798 5070 4887 4942 5795 5067 4890 5066 5854 5126 5796 5068 5795 5067 5735 5011 5798 5070 5799 5071 5855 5127 5797 5069 5796 5068 5736 5012 5799 5071 5800 5074 5856 5128 5798 5070 5797 5069 5738 5015 5800 5074 5802 5072 5857 5129 5799 5071 5798 5070 5858 5130 5800 5074 5799 5071 5860 5131 5802 5072 5800 5074 5859 5132 5861 5133 5803 5075 5859 5132 5801 5073 5802 5072 5861 5133 5862 5134 5804 5076 5859 5132 5803 5075 5801 5073 5862 5134 5863 5135 5805 5077 5861 5133 5804 5076 5803 5075 5863 5135 5864 5136 5806 5078 5862 5134 5805 5077 5804 5076 5864 5136 5865 5137 5807 5079 5865 5137 5866 5138 5808 5080 5863 5135 5806 5078 5805 5077 5866 5138 5867 5139 5809 5081 5867 5139 5868 5140 5810 5082 5864 5136 5807 5079 5806 5078 5868 5140 5869 5141 5811 5083 5865 5137 5808 5080 5807 5079 5869 5141 5870 5142 5812 5084 5870 5142 5871 5143 5813 5085 5866 5138 5809 5081 5808 5080 5871 5143 5872 5144 5814 5086 5872 5144 5873 5145 5815 5087 5867 5139 5810 5082 5809 5081 5873 5145 5874 5146 5816 5088 5875 5147 5817 5089 5874 5146 5868 5140 5811 5083 5810 5082 5876 5148 5818 5090 5875 5147 5869 5141 5812 5084 5811 5083 5877 5149 5819 5091 5876 5148 5870 5142 5813 5085 5812 5084 5878 5150 5820 5092 5877 5149 5871 5143 5814 5086 5813 5085 5879 5151 5821 5093 5878 5150 5872 5144 5815 5087 5814 5086 5880 5152 5822 5094 5879 5151 5873 5145 5816 5088 5815 5087 5881 5153 5823 5095 5880 5152 5874 5146 5817 5089 5816 5088 5882 5154 5824 5096 5881 5153 5875 5147 5818 5090 5817 5089 5883 5155 5825 5097 5882 5154 5876 5148 5819 5091 5818 5090 5877 5149 5820 5092 5819 5091 5884 5156 5826 5098 5883 5155 5878 5150 5821 5093 5820 5092 5879 5151 5822 5094 5821 5093 5885 5157 5827 5099 5884 5156 5880 5152 5823 5095 5822 5094 5881 5153 5824 5096 5823 5095 5882 5154 5825 5097 5824 5096 5886 5158 5828 5100 5885 5157 5883 5155 5826 5098 5825 5097 5826 5098 5884 5156 5827 5099 5767 5043 5829 5101 5830 5103 5768 5046 5830 5103 5831 5104 5885 5157 5828 5100 5827 5099 5769 5047 5831 5104 5832 5105 5770 5048 5832 5105 5833 5106 5771 5049 5833 5106 5834 5107 5886 5158 5829 5101 5828 5100 5772 5050 5834 5107 5835 5108 5773 5051 5835 5108 5836 5109 5887 5159 5830 5103 5829 5101 5774 5102 5836 5109 5837 5110 5888 5160 5831 5104 5830 5103 5775 5052 5837 5110 5838 5111 5889 5161 5832 5105 5831 5104 5890 5162 5833 5106 5832 5105 5776 5053 5838 5111 5839 5112 5891 5163 5834 5107 5833 5106 5777 5054 5839 5112 5840 5113 5892 5164 5835 5108 5834 5107 5778 5055 5840 5113 5841 5114 5893 5165 5836 5109 5835 5108 5779 5056 5841 5114 5842 5115 5894 5166 5837 5110 5836 5109 5781 5058 5842 5115 5844 5117 5895 5167 5838 5111 5837 5110 5782 5059 5844 5117 5845 5118 5783 5060 5845 5118 5846 5119 5896 5168 5839 5112 5838 5111 5347 4606 5846 5119 5532 4796 5897 5169 5840 5113 5839 5112 5380 4639 5532 4796 5381 4640 5897 5169 5841 5114 5840 5113 5376 4635 5843 5116 5378 4637 5898 5170 5842 5115 5841 5114 5844 5117 5842 5115 5899 5171 5377 4636 5342 4601 5843 5116 5843 5116 5376 4635 5377 4636 5900 5172 5845 5118 5844 5117 5846 5119 5845 5118 5901 5173 5902 5174 5903 5175 5904 5176 5343 4602 5342 4601 5377 4636 5846 5119 5905 5177 5532 4796 5594 4858 5907 5178 5374 4633 5343 4602 5348 4607 5344 4603 5381 4640 5374 4633 5376 4635 5365 4623 5348 4607 5363 4630 5784 5120 4991 4327 5596 5062 4984 4328 5910 4863 4983 4930 4991 4327 4992 4329 5535 5000 5911 5179 4978 4320 5912 5180 4965 5122 4984 4328 4983 4930 4965 5122 5785 5063 4984 4328 5913 5181 5850 5121 4964 5182 4960 4732 5785 5063 4965 5122 5914 5183 5791 5184 5915 5185 5470 4733 4960 4732 5850 5121 5916 5186 5794 5187 5727 4936 5604 5004 5727 4936 5792 4935 5794 5187 5917 5188 5852 4941 5794 5187 5664 4937 5727 4936 5917 5188 4886 5189 4887 4942 5853 5124 4894 5190 4886 5189 5852 4941 5664 4937 5794 5187 5795 5067 4887 4942 5854 5126 5796 5068 5854 5126 5855 5127 5917 5188 4887 4942 5852 4941 5797 5069 5855 5127 5856 5128 5798 5070 5856 5128 5857 5129 4886 5189 5854 5126 4887 4942 5918 5191 5855 5127 5854 5126 5799 5071 5857 5129 5858 5130 5918 5191 5856 5128 5855 5127 5919 5192 5857 5129 5856 5128 5800 5074 5858 5130 5860 5131 5921 5193 5858 5130 5857 5129 5802 5072 5860 5131 5859 5132 5859 5132 5924 5194 5923 5195 5860 5131 5858 5130 5922 5196 5859 5132 5923 5195 5925 5197 5860 5131 5924 5194 5859 5132 5861 5133 5925 5197 5926 5198 5925 5197 5861 5133 5859 5132 5862 5134 5926 5198 5927 5199 5926 5198 5862 5134 5861 5133 5863 5135 5927 5199 5928 5200 5927 5199 5863 5135 5862 5134 5928 5200 5929 5201 5865 5137 5929 5201 5930 5202 5866 5138 5928 5200 5864 5136 5863 5135 5930 5202 5931 5203 5867 5139 5931 5203 5932 5204 5868 5140 5928 5200 5865 5137 5864 5136 5932 5204 5933 5205 5869 5141 5929 5201 5866 5138 5865 5137 5933 5205 5934 5206 5870 5142 5934 5206 5935 5207 5871 5143 5930 5202 5867 5139 5866 5138 5935 5207 5936 5208 5872 5144 5936 5208 5937 5209 5873 5145 5931 5203 5868 5140 5867 5139 5937 5209 5938 5210 5874 5146 5938 5210 5939 5211 5875 5147 5932 5204 5869 5141 5868 5140 5939 5211 5940 5212 5876 5148 5933 5205 5870 5142 5869 5141 5940 5212 5941 5213 5877 5149 5934 5206 5871 5143 5870 5142 5941 5213 5942 5214 5878 5150 5935 5207 5872 5144 5871 5143 5942 5214 5943 5215 5879 5151 5936 5208 5873 5145 5872 5144 5943 5215 5944 5216 5880 5152 5937 5209 5874 5146 5873 5145 5944 5216 5945 5217 5881 5153 5938 5210 5875 5147 5874 5146 5945 5217 5946 5218 5882 5154 5939 5211 5876 5148 5875 5147 5946 5218 5947 5219 5883 5155 5940 5212 5877 5149 5876 5148 5941 5213 5878 5150 5877 5149 5947 5219 5948 5220 5884 5156 5942 5214 5879 5151 5878 5150 5943 5215 5880 5152 5879 5151 5948 5220 5949 5221 5885 5157 5944 5216 5881 5153 5880 5152 5945 5217 5882 5154 5881 5153 5946 5218 5883 5155 5882 5154 5949 5221 5950 5222 5886 5158 5947 5219 5884 5156 5883 5155 5829 5101 5886 5158 5887 5159 5830 5103 5887 5159 5888 5160 5885 5157 5884 5156 5948 5220 5831 5104 5888 5160 5889 5161 5832 5105 5889 5161 5890 5162 5833 5106 5890 5162 5891 5163 5886 5158 5885 5157 5949 5221 5834 5107 5891 5163 5892 5164 5835 5108 5892 5164 5893 5165 5950 5222 5887 5159 5886 5158 5836 5109 5893 5165 5894 5166 5951 5223 5888 5160 5887 5159 5837 5110 5894 5166 5895 5167 5952 5224 5889 5161 5888 5160 5838 5111 5895 5167 5896 5168 5953 5225 5890 5162 5889 5161 5954 5226 5891 5163 5890 5162 5839 5112 5896 5168 5897 5169 5955 5227 5892 5164 5891 5163 5956 5228 5893 5165 5892 5164 5841 5114 5897 5169 5898 5170 5957 5229 5894 5166 5893 5165 5842 5115 5898 5170 5899 5171 5958 5230 5895 5167 5894 5166 5844 5117 5899 5171 5900 5172 5959 5231 5896 5168 5895 5167 5845 5118 5900 5172 5901 5173 5846 5119 5901 5173 5905 5177 5961 5232 5897 5169 5896 5168 5532 4796 5905 5177 5594 4858 5381 4640 5594 4858 5374 4633 5962 5233 5898 5170 5897 5169 5375 4634 5377 4636 5376 4635 5963 5234 5899 5171 5898 5170 5900 5172 5899 5171 5964 5235 5965 5236 5901 5173 5900 5172 5905 5177 5901 5173 5966 5237 5335 4594 5967 5238 5968 5239 5905 5177 5969 5240 5594 4858 5904 5176 5907 5178 5969 5240 5324 4587 5322 4586 5323 5241 5364 4622 5375 4634 5374 4633 5723 4998 5970 5242 5971 5243 5908 5244 6031 5245 5598 4865 5910 4863 4984 4328 4991 4327 4964 5182 4983 4930 4981 4929 4964 5182 4965 5122 4983 4930 5973 5246 5913 5181 5972 5247 4964 5182 5850 5121 4965 5122 5850 5121 5913 5181 5604 5004 5728 5248 5916 5186 5603 5003 5603 5003 5604 5004 5913 5181 5794 5187 5916 5186 5793 5249 5916 5186 5727 4936 5603 5003 5917 5188 5793 5249 5853 5124 5917 5188 5794 5187 5793 5249 5854 5126 4886 5189 5918 5191 5917 5188 5853 5124 4886 5189 5856 5128 5918 5191 5919 5192 5857 5129 5919 5192 5920 5250 4894 5190 5918 5191 4886 5189 5857 5129 5920 5250 5921 5193 5858 5130 5921 5193 5922 5196 5976 5251 5919 5192 5918 5191 5977 5252 5920 5250 5919 5192 5860 5131 5922 5196 5924 5194 5978 5253 5921 5193 5920 5250 5979 5254 5922 5196 5921 5193 5981 5255 5923 5195 5980 5256 5982 5257 5924 5194 5922 5196 5980 5256 5923 5195 5924 5194 5983 5258 5926 5198 5981 5255 5981 5255 5925 5197 5923 5195 5984 5259 5927 5199 5983 5258 5985 5260 5927 5199 5984 5259 5981 5255 5926 5198 5925 5197 5986 5261 5928 5200 5985 5260 5983 5258 5927 5199 5926 5198 5929 5201 5986 5261 5987 5262 5927 5199 5985 5260 5928 5200 5930 5202 5987 5262 5988 5263 5931 5203 5988 5263 5989 5264 5928 5200 5986 5261 5929 5201 5932 5204 5989 5264 5990 5265 5929 5201 5987 5262 5930 5202 5933 5205 5990 5265 5991 5266 5934 5206 5991 5266 5992 5267 5988 5263 5931 5203 5930 5202 5935 5207 5992 5267 5993 5268 5936 5208 5993 5268 5994 5269 5989 5264 5932 5204 5931 5203 5937 5209 5994 5269 5995 5270 5938 5210 5995 5270 5996 5271 5990 5265 5933 5205 5932 5204 5939 5211 5996 5271 5997 5272 5991 5266 5934 5206 5933 5205 5940 5212 5997 5272 5998 5273 5992 5267 5935 5207 5934 5206 5941 5213 5998 5273 5999 5274 5993 5268 5936 5208 5935 5207 6000 5275 6001 5276 5943 5215 5994 5269 5937 5209 5936 5208 6001 5276 6002 5277 5944 5216 5995 5270 5938 5210 5937 5209 6002 5277 6003 5278 5945 5217 5996 5271 5939 5211 5938 5210 6003 5278 6004 5279 5946 5218 5997 5272 5940 5212 5939 5211 6004 5279 6005 5280 5947 5219 5998 5273 5941 5213 5940 5212 5999 5274 5942 5214 5941 5213 6005 5280 6006 5281 5948 5220 6000 5275 5943 5215 5942 5214 6001 5276 5944 5216 5943 5215 6002 5277 5945 5217 5944 5216 6006 5281 6007 5282 5949 5221 6003 5278 5946 5218 5945 5217 6004 5279 5947 5219 5946 5218 6007 5282 6008 5283 5950 5222 6008 5283 6009 5284 5950 5222 6005 5280 5948 5220 5947 5219 5887 5159 5950 5222 5951 5223 5888 5160 5951 5223 5952 5224 5949 5221 5948 5220 6006 5281 5889 5161 5952 5224 5953 5225 5890 5162 5953 5225 5954 5226 5891 5163 5954 5226 5955 5227 5950 5222 5949 5221 6007 5282 5892 5164 5955 5227 5956 5228 5893 5165 5956 5228 5957 5229 6009 5284 5951 5223 5950 5222 5894 5166 5957 5229 5958 5230 6010 5285 5952 5224 5951 5223 5895 5167 5958 5230 5959 5231 6011 5286 5953 5225 5952 5224 5896 5168 5959 5231 5960 5287 6012 5288 5954 5226 5953 5225 5896 5168 5960 5287 5961 5232 6013 5289 5955 5227 5954 5226 5897 5169 5961 5232 5962 5233 6014 5290 5956 5228 5955 5227 6015 5291 5957 5229 5956 5228 5898 5170 5962 5233 5963 5234 6016 5292 5958 5230 5957 5229 5899 5171 5963 5234 5964 5235 6017 5293 5959 5231 5958 5230 5900 5172 5964 5235 5965 5236 6018 5294 5960 5287 5959 5231 5901 5173 5965 5236 5966 5237 6019 5295 5961 5232 5960 5287 5905 5177 5966 5237 5969 5240 6020 5296 5962 5233 5961 5232 5594 4858 5969 5240 5907 5178 5374 4633 5907 5178 5364 4622 6021 5297 5963 5234 5962 5233 5375 4634 5364 4622 5359 4618 6022 5298 5964 5235 5963 5234 5377 4636 5359 4618 6023 5299 6024 5300 5965 5236 5964 5235 5966 5237 5965 5236 6025 5301 6023 5299 5339 4598 5343 4602 5343 4602 5377 4636 6023 5299 6026 5302 5969 5240 5966 5237 6027 5303 6028 5304 6029 5305 5847 5306 5722 4997 6030 5307 5339 4598 5348 4607 5343 4602 5364 4622 5907 5178 5903 5175 5348 4607 5341 4600 5363 4630 5908 5244 5598 4865 5597 4864 6031 5245 5848 5308 5849 5309 4981 4929 6031 5245 4980 5310 5598 4865 4983 4930 5910 4863 6330 5311 6032 5312 6097 5313 5972 5247 4981 4929 4980 5310 4981 4929 5972 5247 4964 5182 5973 5246 6035 5314 6036 5315 5972 5247 5913 5181 4964 5182 5729 5316 5728 5248 5973 5246 5914 5183 5915 5185 6040 5317 5913 5181 5973 5246 5603 5003 5603 5003 5973 5246 5728 5248 6041 5318 6042 5125 5793 5249 5728 5248 6041 5318 5916 5186 6041 5318 5793 5249 5916 5186 4891 5319 6156 5320 6219 5321 5793 5249 6042 5125 5853 5124 5918 5191 4894 5190 5976 5251 4893 5123 4894 5190 5853 5124 5919 5192 5976 5251 5977 5252 5920 5250 5977 5252 5978 5253 6043 5322 5976 5251 4894 5190 5921 5193 5978 5253 5979 5254 6044 5323 5977 5252 5976 5251 5922 5196 5979 5254 5982 5257 6044 5323 5978 5253 5977 5252 6045 5324 5979 5254 5978 5253 5924 5194 5982 5257 5980 5256 5979 5254 6046 5325 5982 5257 6048 5326 6047 5327 5981 5255 6048 5326 5980 5256 5982 5257 6048 5326 5981 5255 5980 5256 6047 5327 6049 5328 5983 5258 6049 5328 6050 5329 5984 5259 6050 5329 6051 5330 5985 5260 6047 5327 5983 5258 5981 5255 6051 5330 6052 5331 5986 5261 6049 5328 5984 5259 5983 5258 6050 5329 5985 5260 5984 5259 6052 5331 6053 5332 5987 5262 6051 5330 5986 5261 5985 5260 6053 5332 6054 5333 5988 5263 6055 5334 5989 5264 6054 5333 6056 5335 5990 5265 6055 5334 6052 5331 5987 5262 5986 5261 6057 5336 5991 5266 6056 5335 6053 5332 5988 5263 5987 5262 6058 5337 5992 5267 6057 5336 6059 5338 5993 5268 6058 5337 6054 5333 5989 5264 5988 5263 6060 5339 5994 5269 6059 5338 6061 5340 5995 5270 6060 5339 6055 5334 5990 5265 5989 5264 6062 5341 5996 5271 6061 5340 6063 5342 5997 5272 6062 5341 6056 5335 5991 5266 5990 5265 6064 5343 5998 5273 6063 5342 6057 5336 5992 5267 5991 5266 6065 5344 5999 5274 6064 5343 6058 5337 5993 5268 5992 5267 5942 5214 5999 5274 6000 5275 5993 5268 6059 5338 5994 5269 6000 5275 6065 5344 6066 5345 5994 5269 6060 5339 5995 5270 6001 5276 6066 5345 6067 5346 5995 5270 6061 5340 5996 5271 6002 5277 6067 5346 6068 5347 5996 5271 6062 5341 5997 5272 6003 5278 6068 5347 6069 5348 5997 5272 6063 5342 5998 5273 6004 5279 6069 5348 6070 5349 5998 5273 6064 5343 5999 5274 6005 5280 6070 5349 6071 5350 5999 5274 6065 5344 6000 5275 6005 5280 6071 5350 6072 5351 6000 5275 6066 5345 6001 5276 6001 5276 6067 5346 6002 5277 6002 5277 6068 5347 6003 5278 6006 5281 6072 5351 6073 5352 6003 5278 6069 5348 6004 5279 6004 5279 6070 5349 6005 5280 6007 5282 6073 5352 6074 5353 6005 5280 6072 5351 6006 5281 5951 5223 6009 5284 6010 5285 5952 5224 6010 5285 6011 5286 5953 5225 6011 5286 6012 5288 6006 5281 6073 5352 6007 5282 5954 5226 6012 5288 6013 5289 5955 5227 6013 5289 6014 5290 6008 5283 6007 5282 6074 5353 5956 5228 6014 5290 6015 5291 6074 5353 6009 5284 6008 5283 5957 5229 6015 5291 6016 5292 6075 5354 6010 5285 6009 5284 5958 5230 6016 5292 6017 5293 6076 5355 6011 5286 6010 5285 5959 5231 6017 5293 6018 5294 6077 5356 6012 5288 6011 5286 5960 5287 6018 5294 6019 5295 6078 5357 6013 5289 6012 5288 5961 5232 6019 5295 6020 5296 6079 5358 6014 5290 6013 5289 6080 5359 6015 5291 6014 5290 5962 5233 6020 5296 6021 5297 6081 5360 6016 5292 6015 5291 5963 5234 6021 5297 6022 5298 6082 5361 6017 5293 6016 5292 5964 5235 6022 5298 6024 5300 6083 5362 6018 5294 6017 5293 5965 5236 6024 5300 6025 5301 6084 5363 6019 5295 6018 5294 5966 5237 6025 5301 6026 5302 6085 5364 6020 5296 6019 5295 5969 5240 6026 5302 5904 5176 5907 5178 5904 5176 5903 5175 6086 5365 6021 5297 6020 5296 5364 4622 5903 5175 5360 4619 6087 5366 6022 5298 6021 5297 6087 5366 6024 5300 6022 5298 6088 5367 6025 5301 6024 5300 6026 5302 6025 5301 6089 5368 6090 5369 5904 5176 6026 5302 5902 5174 5337 4596 6091 5370 5903 5175 6091 5370 5360 4619 5971 5243 6094 5371 6095 5372 5362 4621 6023 5299 5359 4618 5363 4630 5371 4629 5372 4631 5848 5308 6031 5245 5908 5244 5909 5373 6153 5374 5849 5309 4980 5310 5849 5309 5467 5375 6031 5245 4981 4929 5598 4865 4966 5376 4975 5064 6097 5313 6035 5314 4980 5310 5467 5375 5972 5247 4980 5310 6035 5314 6099 5377 6036 5315 6098 5378 5973 5246 5972 5247 6035 5314 6036 5315 6099 5377 5729 5316 6039 5379 5851 5380 5729 5316 6041 5318 5728 5248 5851 5380 5973 5246 6036 5315 5729 5316 6041 5318 5851 5380 5975 5381 5851 5380 5728 5248 5729 5316 6042 5125 5975 5381 6100 5382 5975 5381 6042 5125 6041 5318 4894 5190 4893 5123 6043 5322 6042 5125 6100 5382 4893 5123 5976 5251 6043 5322 6044 5323 6101 5383 6043 5322 4893 5123 5978 5253 6044 5323 6045 5324 6102 5384 6044 5323 6043 5322 5979 5254 6045 5324 6046 5325 6103 5385 6045 5324 6044 5323 5982 5257 6046 5325 6048 5326 6105 5386 6046 5325 6045 5324 6048 5326 6046 5325 6106 5387 6106 5387 6107 5388 6047 5327 6107 5388 6108 5389 6049 5328 6106 5387 6047 5327 6048 5326 6108 5389 6109 5390 6050 5329 6109 5390 6110 5391 6051 5330 6107 5388 6049 5328 6047 5327 6110 5391 6111 5392 6052 5331 6108 5389 6050 5329 6049 5328 6109 5390 6051 5330 6050 5329 6111 5392 6112 5393 6053 5332 6110 5391 6052 5331 6051 5330 6112 5393 6113 5394 6054 5333 6113 5394 6114 5395 6055 5334 6114 5395 6115 5396 6056 5335 6111 5392 6053 5332 6052 5331 6115 5396 6116 5397 6057 5336 6112 5393 6054 5333 6053 5332 6116 5397 6117 5398 6058 5337 6117 5398 6118 5399 6059 5338 6113 5394 6055 5334 6054 5333 6118 5399 6119 5400 6060 5339 6119 5400 6120 5401 6061 5340 6114 5395 6056 5335 6055 5334 6120 5401 6121 5402 6062 5341 6121 5402 6122 5403 6063 5342 6115 5396 6057 5336 6056 5335 6122 5403 6123 5404 6064 5343 6116 5397 6058 5337 6057 5336 6123 5404 6124 5405 6065 5344 6117 5398 6059 5338 6058 5337 6124 5405 6125 5406 6066 5345 6118 5399 6060 5339 6059 5338 6125 5406 6126 5407 6067 5346 6119 5400 6061 5340 6060 5339 6126 5407 6127 5408 6068 5347 6120 5401 6062 5341 6061 5340 6127 5408 6128 5409 6069 5348 6121 5402 6063 5342 6062 5341 6128 5409 6129 5410 6070 5349 6122 5403 6064 5343 6063 5342 6123 5404 6065 5344 6064 5343 6129 5410 6130 5411 6072 5351 6124 5405 6066 5345 6065 5344 6125 5406 6067 5346 6066 5345 6130 5411 6131 5412 6072 5351 6126 5407 6068 5347 6067 5346 6127 5408 6069 5348 6068 5347 6128 5409 6070 5349 6069 5348 6131 5412 6132 5413 6074 5353 6129 5410 6071 5350 6070 5349 6129 5410 6072 5351 6071 5350 6009 5284 6074 5353 6075 5354 6010 5285 6075 5354 6076 5355 6011 5286 6076 5355 6077 5356 6131 5412 6073 5352 6072 5351 6012 5288 6077 5356 6078 5357 6013 5289 6078 5357 6079 5358 6074 5353 6073 5352 6131 5412 6014 5290 6079 5358 6080 5359 6015 5291 6080 5359 6081 5360 6132 5413 6075 5354 6074 5353 6016 5292 6081 5360 6082 5361 6133 5414 6076 5355 6075 5354 6017 5293 6082 5361 6083 5362 6134 5415 6077 5356 6076 5355 6018 5294 6083 5362 6084 5363 6135 5416 6078 5357 6077 5356 6019 5295 6084 5363 6085 5364 6136 5417 6079 5358 6078 5357 6020 5296 6085 5364 6086 5365 6137 5418 6080 5359 6079 5358 6138 5419 6081 5360 6080 5359 6021 5297 6086 5365 6087 5366 6139 5420 6082 5361 6081 5360 6140 5421 6083 5362 6082 5361 6024 5300 6087 5366 6088 5367 6141 5422 6084 5363 6083 5362 6025 5301 6088 5367 6089 5368 6142 5423 6085 5364 6084 5363 6026 5302 6089 5368 6090 5369 6143 5424 6086 5365 6085 5364 5904 5176 6090 5369 5902 5174 5903 5175 5902 5174 6091 5370 6145 5425 6087 5366 6086 5365 5360 4619 6091 5370 5358 4617 5359 4618 5358 4617 5362 4621 6146 5426 6088 5367 6087 5366 6023 5299 5362 4621 5338 4597 6147 5427 6089 5368 6088 5367 6090 5369 6089 5368 6148 5428 5906 5429 5330 4589 5325 5430 5339 4598 6023 5299 5338 4597 6090 5369 6149 5431 5902 5174 6150 5432 6028 5304 6151 5433 5331 4590 5341 4600 5339 4598 6091 5370 5336 4595 5358 4617 5341 4600 5340 4599 5363 4630 6153 5374 6096 5434 5912 5180 6152 5435 5467 5375 6153 5374 5849 5309 4980 5310 6031 5245 6098 5378 5467 5375 6152 5435 6035 5314 5467 5375 6098 5378 6099 5377 5790 5436 5914 5183 6036 5315 6035 5314 6098 5378 6099 5377 5914 5183 6039 5379 6099 5377 6039 5379 5729 5316 5975 5381 5974 5437 6156 5320 6039 5379 5974 5437 5851 5380 5975 5381 5851 5380 5974 5437 4892 5438 6100 5382 6156 5320 4893 5123 6100 5382 6101 5383 6100 5382 5975 5381 6156 5320 6043 5322 6101 5383 6102 5384 4892 5438 6101 5383 6100 5382 6044 5323 6102 5384 6103 5385 6045 5324 6103 5385 6104 5439 6157 5440 6102 5384 6101 5383 6045 5324 6104 5439 6105 5386 6158 5441 6103 5385 6102 5384 6158 5441 6104 5439 6103 5385 6046 5325 6105 5386 6106 5387 6159 5442 6105 5386 6104 5439 6106 5387 6162 5443 6161 5444 6160 5445 6106 5387 6105 5386 6161 5444 6107 5388 6106 5387 6161 5444 6108 5389 6107 5388 6109 5390 6108 5389 6164 5446 6110 5391 6109 5390 6165 5447 6108 5389 6161 5444 6164 5446 6111 5392 6110 5391 6166 5448 6164 5446 6165 5447 6109 5390 6165 5447 6166 5448 6110 5391 6112 5393 6111 5392 6167 5449 6113 5394 6112 5393 6168 5450 6166 5448 6167 5449 6111 5392 6114 5395 6113 5394 6169 5451 6115 5396 6114 5395 6170 5452 6167 5449 6168 5450 6112 5393 6116 5397 6115 5396 6171 5453 6117 5398 6116 5397 6171 5453 6168 5450 6169 5451 6113 5394 6118 5399 6117 5398 6172 5454 6119 5400 6118 5399 6173 5455 6169 5451 6170 5452 6114 5395 6120 5401 6119 5400 6174 5456 6121 5402 6120 5401 6175 5457 6170 5452 6171 5453 6115 5396 6122 5403 6121 5402 6176 5458 6123 5404 6122 5403 6177 5459 6171 5453 6172 5454 6117 5398 6124 5405 6123 5404 6178 5460 6172 5454 6173 5455 6118 5399 6125 5406 6124 5405 6179 5461 6173 5455 6174 5456 6119 5400 6126 5407 6125 5406 6180 5462 6174 5456 6175 5457 6120 5401 6127 5408 6126 5407 6181 5463 6175 5457 6176 5458 6121 5402 6128 5409 6127 5408 6182 5464 6176 5458 6177 5459 6122 5403 6129 5410 6128 5409 6183 5465 6177 5459 6178 5460 6123 5404 6178 5460 6179 5461 6124 5405 6130 5411 6129 5410 6184 5466 6179 5461 6180 5462 6125 5406 6180 5462 6181 5463 6126 5407 6131 5412 6130 5411 6185 5467 6181 5463 6182 5464 6127 5408 6182 5464 6183 5465 6128 5409 6183 5465 6184 5466 6129 5410 6132 5413 6131 5412 6186 5468 6184 5466 6185 5467 6130 5411 6075 5354 6132 5413 6133 5414 6076 5355 6133 5414 6134 5415 6077 5356 6134 5415 6135 5416 6185 5467 6186 5468 6131 5412 6078 5357 6135 5416 6136 5417 6079 5358 6136 5417 6137 5418 6187 5469 6132 5413 6186 5468 6080 5359 6137 5418 6138 5419 6187 5469 6188 5470 6132 5413 6081 5360 6138 5419 6139 5420 6188 5470 6189 5471 6133 5414 6082 5361 6139 5420 6140 5421 6189 5471 6190 5472 6134 5415 6083 5362 6140 5421 6141 5422 6190 5472 6191 5473 6135 5416 6084 5363 6141 5422 6142 5423 6191 5473 6192 5474 6136 5417 6085 5364 6142 5423 6143 5424 6192 5474 6193 5475 6137 5418 6086 5365 6143 5424 6144 5476 6193 5475 6138 5419 6137 5418 6086 5365 6144 5476 6145 5425 6194 5477 6139 5420 6138 5419 6195 5478 6140 5421 6139 5420 6087 5366 6145 5425 6146 5426 6196 5479 6141 5422 6140 5421 6088 5367 6146 5426 6147 5427 6197 5480 6142 5423 6141 5422 6089 5368 6147 5427 6148 5428 6198 5481 6143 5424 6142 5423 6090 5369 6148 5428 6149 5431 6199 5482 6144 5476 6143 5424 5902 5174 6149 5431 5337 4596 6200 5483 6145 5425 6144 5476 6091 5370 5337 4596 5336 4595 5358 4617 5336 4595 5361 4620 6201 5484 6146 5426 6145 5425 6202 5485 6147 5427 6146 5426 6202 5485 6148 5428 6147 5427 6149 5431 6148 5428 6203 5486 6204 5487 6030 5307 5906 5429 6205 5488 5337 4596 6149 5431 6206 5489 6207 5490 6208 5491 5361 4620 5336 4595 5968 5239 6210 5492 6093 5493 6211 5494 5338 4597 5362 4621 5357 4616 6096 5434 6153 5374 5909 5373 6152 5435 5912 5180 4977 4319 5849 5309 6153 5374 5467 5375 5790 5436 6152 5435 4977 4319 6098 5378 6152 5435 5790 5436 6099 5377 6098 5378 5790 5436 6508 5495 6565 5496 6217 5497 5974 5437 6039 5379 6218 5498 6039 5379 5914 5183 6040 5317 5974 5437 6218 5498 6219 5321 6040 5317 6218 5498 6039 5379 5196 5499 6339 5500 6220 5501 6276 5502 5200 5503 4891 5319 5974 5437 6219 5321 6156 5320 6101 5383 4892 5438 6157 5440 6156 5320 4891 5319 4892 5438 6102 5384 6157 5440 6158 5441 6221 5504 6157 5440 4892 5438 6104 5439 6158 5441 6159 5442 6222 5505 6158 5441 6157 5440 6105 5386 6159 5442 6160 5445 6223 5506 6159 5442 6158 5441 6106 5387 6160 5445 6162 5443 6224 5507 6160 5445 6159 5442 6163 5508 6160 5445 6224 5507 6161 5444 6162 5443 6225 5509 6162 5443 6163 5508 6225 5509 6225 5509 6226 5510 6161 5444 6161 5444 6227 5511 6164 5446 6161 5444 6226 5510 6227 5511 6165 5447 6164 5446 6229 5512 6166 5448 6165 5447 6229 5512 6164 5446 6227 5511 6228 5513 6164 5446 6228 5513 6229 5512 6167 5449 6166 5448 6230 5514 6166 5448 6229 5512 6230 5514 6168 5450 6167 5449 6231 5515 6167 5449 6230 5514 6231 5515 6169 5451 6168 5450 6232 5516 6170 5452 6169 5451 6233 5517 6168 5450 6231 5515 6232 5516 6171 5453 6170 5452 6234 5518 6169 5451 6232 5516 6233 5517 6172 5454 6171 5453 6235 5519 6173 5455 6236 5520 6174 5456 6170 5452 6233 5517 6234 5518 6174 5456 6237 5521 6175 5457 6175 5457 6238 5522 6176 5458 6171 5453 6234 5518 6235 5519 6176 5458 6239 5523 6177 5459 6177 5459 6240 5524 6178 5460 6172 5454 6235 5519 6241 5525 6178 5460 6242 5526 6179 5461 6173 5455 6241 5525 6236 5520 6179 5461 6243 5527 6180 5462 6174 5456 6236 5520 6237 5521 6180 5462 6244 5528 6181 5463 6175 5457 6237 5521 6238 5522 6181 5463 6245 5529 6182 5464 6176 5458 6238 5522 6239 5523 6182 5464 6246 5530 6183 5465 6177 5459 6239 5523 6240 5524 6183 5465 6247 5531 6184 5466 6178 5460 6240 5524 6242 5526 6179 5461 6242 5526 6243 5527 6184 5466 6248 5532 6185 5467 6180 5462 6243 5527 6244 5528 6181 5463 6244 5528 6245 5529 6182 5464 6245 5529 6246 5530 6185 5467 6250 5533 6186 5468 6183 5465 6246 5530 6247 5531 6184 5466 6247 5531 6248 5532 6186 5468 6250 5533 6187 5469 6187 5469 6251 5534 6188 5470 6248 5532 6249 5535 6185 5467 6133 5414 6132 5413 6188 5470 6134 5415 6133 5414 6189 5471 6250 5533 6185 5467 6249 5535 6135 5416 6134 5415 6190 5472 6136 5417 6135 5416 6191 5473 6137 5418 6136 5417 6192 5474 6251 5534 6187 5469 6250 5533 6193 5475 6194 5477 6138 5419 6251 5534 6252 5536 6188 5470 6139 5420 6194 5477 6195 5478 6252 5536 6253 5537 6189 5471 6140 5421 6195 5478 6196 5479 6253 5537 6254 5538 6190 5472 6141 5422 6196 5479 6197 5480 6254 5538 6255 5539 6191 5473 6142 5423 6197 5480 6198 5481 6255 5539 6256 5540 6192 5474 6143 5424 6198 5481 6199 5482 6256 5540 6257 5541 6193 5475 6144 5476 6199 5482 6200 5483 6257 5541 6258 5542 6194 5477 6145 5425 6200 5483 6201 5484 6258 5542 6259 5543 6195 5478 6259 5543 6196 5479 6195 5478 6146 5426 6201 5484 6202 5485 6260 5544 6197 5480 6196 5479 6261 5545 6198 5481 6197 5480 6148 5428 6202 5485 6203 5486 6262 5546 6199 5482 6198 5481 6149 5431 6203 5486 6205 5488 6263 5547 6200 5483 6199 5482 5337 4596 6205 5488 5335 4594 6264 5548 6201 5484 6200 5483 5336 4595 5335 4594 5968 5239 5361 4620 5968 5239 5355 4614 6265 5549 6202 5485 6201 5484 5362 4621 5355 4614 5357 4616 5338 4597 5357 4616 5329 4588 6266 5550 6203 5486 6202 5485 6205 5488 6203 5486 5334 4593 6267 5551 6268 5552 6269 5553 5331 4590 5338 4597 5329 4588 5333 4592 5335 4594 6205 5488 5967 5238 6027 5303 6270 5554 5330 4589 5340 4599 5331 4590 5968 5239 6270 5554 5355 4614 5340 4599 5533 4996 5371 4629 4978 4320 6212 5555 6330 5311 5912 5180 6152 5435 6153 5374 5791 5184 4977 4319 4974 4321 5790 5436 4977 4319 5791 5184 6274 5556 5915 5185 5789 5065 5914 5183 5790 5436 5791 5184 5915 5185 6274 5556 6038 5557 6218 5498 6040 5317 6038 5557 5915 5185 6038 5557 6040 5317 6219 5321 6155 5558 6276 5502 6038 5557 6155 5558 6218 5498 6155 5558 6219 5321 6218 5498 4892 5438 4891 5319 6221 5504 6219 5321 6276 5502 4891 5319 6157 5440 6221 5504 6222 5505 5200 5503 6221 5504 4891 5319 6158 5441 6222 5505 6223 5506 6277 5559 6222 5505 6221 5504 6159 5442 6223 5506 6224 5507 6278 5560 6223 5506 6222 5505 6162 5443 6160 5445 6163 5508 6163 5508 6280 5561 6282 5562 6225 5509 6281 5563 6226 5510 6282 5562 6281 5563 6225 5509 6226 5510 6281 5563 6227 5511 6227 5511 6283 5564 6228 5513 6228 5513 6283 5564 6229 5512 6281 5563 6283 5564 6227 5511 6229 5512 6284 5565 6230 5514 6283 5564 6284 5565 6229 5512 6230 5514 6285 5566 6231 5515 6284 5565 6285 5566 6230 5514 6231 5515 6286 5567 6232 5516 6232 5516 6287 5568 6233 5517 6285 5566 6286 5567 6231 5515 6233 5517 6288 5569 6234 5518 6234 5518 6289 5570 6235 5519 6286 5567 6287 5568 6232 5516 6235 5519 6290 5571 6241 5525 6287 5568 6288 5569 6233 5517 6173 5455 6172 5454 6241 5525 6291 5572 6236 5520 6241 5525 6234 5518 6288 5569 6289 5570 6292 5573 6237 5521 6236 5520 6293 5574 6238 5522 6237 5521 6235 5519 6289 5570 6290 5571 6294 5575 6239 5523 6238 5522 6295 5576 6240 5524 6239 5523 6241 5525 6290 5571 6291 5572 6296 5577 6242 5526 6240 5524 6236 5520 6291 5572 6292 5573 6297 5578 6243 5527 6242 5526 6237 5521 6292 5573 6293 5574 6298 5579 6244 5528 6243 5527 6238 5522 6293 5574 6294 5575 6299 5580 6245 5529 6244 5528 6239 5523 6294 5575 6295 5576 6300 5581 6246 5530 6245 5529 6240 5524 6295 5576 6296 5577 6301 5582 6247 5531 6246 5530 6242 5526 6296 5577 6297 5578 6302 5583 6248 5532 6247 5531 6243 5527 6297 5578 6298 5579 6244 5528 6298 5579 6299 5580 6249 5535 6248 5532 6304 5584 6245 5529 6299 5580 6300 5581 6246 5530 6300 5581 6301 5582 6250 5533 6249 5535 6304 5584 6247 5531 6301 5582 6302 5583 6248 5532 6302 5583 6303 5585 6248 5532 6303 5585 6304 5584 6251 5534 6306 5586 6252 5536 6189 5471 6188 5470 6252 5536 6190 5472 6189 5471 6253 5537 6304 5584 6305 5587 6250 5533 6191 5473 6190 5472 6254 5538 6192 5474 6191 5473 6255 5539 6306 5586 6250 5533 6305 5587 6193 5475 6192 5474 6256 5540 6194 5477 6193 5475 6257 5541 6306 5586 6307 5588 6252 5536 6195 5478 6194 5477 6258 5542 6307 5588 6308 5589 6253 5537 6259 5543 6260 5544 6196 5479 6308 5589 6309 5590 6254 5538 6197 5480 6260 5544 6261 5545 6309 5590 6310 5591 6255 5539 6198 5481 6261 5545 6262 5546 6310 5591 6311 5592 6256 5540 6199 5482 6262 5546 6263 5547 6311 5592 6312 5593 6257 5541 6200 5483 6263 5547 6264 5548 6312 5593 6313 5594 6258 5542 6201 5484 6264 5548 6265 5549 6313 5594 6314 5595 6259 5543 6314 5595 6315 5596 6260 5544 6202 5485 6265 5549 6266 5550 6315 5596 6316 5597 6261 5545 6316 5597 6262 5546 6261 5545 6203 5486 6266 5550 5334 4593 6317 5598 6263 5547 6262 5546 6205 5488 5334 4593 5333 4592 6318 5599 6264 5548 6263 5547 5335 4594 5333 4592 5967 5238 6319 5600 6265 5549 6264 5548 5968 5239 5967 5238 6270 5554 6321 5601 6266 5550 6265 5549 6322 5602 5334 4593 6266 5550 6323 5603 6324 5604 6268 5552 5332 4591 6267 5551 6325 5605 5333 4592 6325 5605 5967 5238 6326 5606 6327 5607 6207 5490 6209 5608 6094 5371 5970 5242 6270 5554 6029 5305 5355 4614 5533 4996 5906 5429 5722 4997 5357 4616 5326 4859 5329 4588 5371 4629 5723 4998 5372 4631 6212 5555 4978 4320 5911 5179 4974 4321 6330 5311 4975 5064 4978 4320 4977 4319 5912 5180 6331 5609 6332 5610 6333 5611 4974 4321 5789 5065 5791 5184 6274 5556 6335 5612 6336 5613 5789 5065 5915 5185 5791 5184 6274 5556 6336 5613 6037 5614 6155 5558 6038 5557 6037 5614 6038 5557 6274 5556 6037 5614 6337 5615 6509 5616 6338 5617 6155 5558 6154 5618 6339 5500 6037 5614 6154 5618 6155 5558 5197 5619 6276 5502 6339 5500 6155 5558 6339 5500 6276 5502 6221 5504 5200 5503 6277 5559 5197 5619 5200 5503 6276 5502 6222 5505 6277 5559 6278 5560 6340 5620 6277 5559 5200 5503 6223 5506 6278 5560 6279 5621 6223 5506 6279 5621 6280 5561 6278 5560 6277 5559 6341 5622 6224 5507 6223 5506 6280 5561 6163 5508 6224 5507 6280 5561 6341 5622 6342 5623 6279 5621 6342 5623 6343 5624 6280 5561 6225 5509 6163 5508 6282 5562 6282 5562 6345 5625 6281 5563 6282 5562 6343 5624 6345 5625 6345 5625 6344 5626 6281 5563 6281 5563 6346 5627 6283 5564 6283 5564 6347 5628 6284 5565 6344 5626 6346 5627 6281 5563 6284 5565 6347 5628 6285 5566 6346 5627 6347 5628 6283 5564 6285 5566 6348 5629 6286 5567 6347 5628 6348 5629 6285 5566 6286 5567 6349 5630 6287 5568 6287 5568 6350 5631 6288 5569 6348 5629 6349 5630 6286 5567 6288 5569 6351 5632 6289 5570 6289 5570 6352 5633 6290 5571 6349 5630 6350 5631 6287 5568 6290 5571 6353 5634 6291 5572 6350 5631 6351 5632 6288 5569 6291 5572 6354 5635 6292 5573 6292 5573 6355 5636 6293 5574 6351 5632 6352 5633 6289 5570 6293 5574 6356 5637 6294 5575 6294 5575 6357 5638 6295 5576 6352 5633 6353 5634 6290 5571 6295 5576 6358 5639 6296 5577 6296 5577 6359 5640 6297 5578 6353 5634 6354 5635 6291 5572 6297 5578 6360 5641 6298 5579 6354 5635 6355 5636 6292 5573 6298 5579 6361 5642 6299 5580 6355 5636 6356 5637 6293 5574 6299 5580 6362 5643 6300 5581 6356 5637 6357 5638 6294 5575 6300 5581 6363 5644 6301 5582 6357 5638 6358 5639 6295 5576 6301 5582 6364 5645 6302 5583 6358 5639 6359 5640 6296 5577 6302 5583 6365 5646 6303 5585 6359 5640 6360 5641 6297 5578 6303 5585 6366 5647 6304 5584 6360 5641 6361 5642 6298 5579 6361 5642 6362 5643 6299 5580 6362 5643 6363 5644 6300 5581 6304 5584 6367 5648 6305 5587 6363 5644 6364 5645 6301 5582 6364 5645 6365 5646 6302 5583 6305 5587 6368 5649 6306 5586 6365 5646 6366 5647 6303 5585 6251 5534 6250 5533 6306 5586 6304 5584 6366 5647 6367 5648 6253 5537 6252 5536 6307 5588 6254 5538 6253 5537 6308 5589 6367 5648 6368 5649 6305 5587 6255 5539 6254 5538 6309 5590 6256 5540 6255 5539 6310 5591 6369 5650 6306 5586 6368 5649 6257 5541 6256 5540 6311 5592 6258 5542 6257 5541 6312 5593 6369 5650 6370 5651 6307 5588 6259 5543 6258 5542 6313 5594 6370 5651 6371 5652 6308 5589 6260 5544 6259 5543 6314 5595 6371 5652 6372 5653 6309 5590 6261 5545 6260 5544 6315 5596 6372 5653 6373 5654 6310 5591 6316 5597 6317 5598 6262 5546 6373 5654 6374 5655 6311 5592 6263 5547 6317 5598 6318 5599 6374 5655 6375 5656 6312 5593 6264 5548 6318 5599 6319 5600 6375 5656 6376 5657 6313 5594 6265 5549 6319 5600 6320 5658 6376 5657 6377 5659 6314 5595 6265 5549 6320 5658 6321 5601 6377 5659 6378 5660 6315 5596 6378 5660 6379 5661 6316 5597 6266 5550 6321 5601 6322 5602 6379 5661 6380 5662 6317 5598 5334 4593 6322 5602 5332 4591 6380 5662 6318 5599 6317 5598 5333 4592 5332 4591 6325 5605 6381 5663 6319 5600 6318 5599 5967 5238 6325 5605 6027 5303 6382 5664 6320 5658 6319 5600 6270 5554 6027 5303 6029 5305 6383 5665 6321 5601 6320 5658 5355 4614 6029 5305 5356 4615 5357 4616 5356 4615 5326 4859 6384 5666 6322 5602 6321 5601 5329 4588 5326 4859 5325 5430 6267 5551 5332 4591 6322 5602 5325 5430 5721 5667 6204 5487 5327 5668 6385 5669 6030 5307 5330 4589 5329 4588 5325 5430 6269 5553 6027 5303 6325 5605 5906 5429 5533 4996 5330 4589 5356 4615 6029 5305 6150 5432 6211 5494 6387 5670 6388 5671 5533 4996 5722 4997 5371 4629 6328 5672 6450 5673 6097 5313 6330 5311 4974 4321 4978 4320 6335 5612 4975 5064 4966 5376 5789 5065 4975 5064 6335 5612 6336 5613 6391 5674 6392 5675 6335 5612 6274 5556 5789 5065 6154 5618 6037 5614 6275 5676 6336 5613 6275 5676 6037 5614 6339 5500 6394 5677 6220 5501 6154 5618 6275 5676 6394 5677 6154 5618 6394 5677 6339 5500 5200 5503 5197 5619 6340 5620 6339 5500 5196 5499 5197 5619 6277 5559 6340 5620 6341 5622 6395 5678 6340 5620 5197 5619 6279 5621 6278 5560 6341 5622 6280 5561 6279 5621 6342 5623 6396 5679 6341 5622 6340 5620 6396 5679 6397 5680 6341 5622 6282 5562 6280 5561 6343 5624 6397 5680 6398 5681 6343 5624 6345 5625 6399 5682 6344 5626 6398 5681 6399 5682 6345 5625 6344 5626 6401 5683 6346 5627 6344 5626 6399 5682 6400 5684 6346 5627 6402 5685 6347 5628 6344 5626 6400 5684 6401 5683 6347 5628 6403 5686 6348 5629 6346 5627 6401 5683 6402 5685 6347 5628 6402 5685 6403 5686 6348 5629 6404 5687 6349 5630 6348 5629 6403 5686 6404 5687 6349 5630 6405 5688 6350 5631 6350 5631 6406 5689 6351 5632 6349 5630 6404 5687 6405 5688 6351 5632 6407 5690 6352 5633 6352 5633 6408 5691 6353 5634 6350 5631 6405 5688 6406 5689 6353 5634 6409 5692 6354 5635 6351 5632 6406 5689 6407 5690 6354 5635 6410 5693 6355 5636 6355 5636 6411 5694 6356 5637 6352 5633 6407 5690 6408 5691 6356 5637 6412 5695 6357 5638 6357 5638 6413 5696 6358 5639 6353 5634 6408 5691 6409 5692 6358 5639 6414 5697 6359 5640 6359 5640 6415 5698 6360 5641 6354 5635 6409 5692 6410 5693 6360 5641 6416 5699 6361 5642 6355 5636 6410 5693 6411 5694 6361 5642 6417 5700 6362 5643 6356 5637 6411 5694 6412 5695 6362 5643 6418 5701 6363 5644 6357 5638 6412 5695 6413 5696 6363 5644 6419 5702 6364 5645 6413 5696 6414 5697 6358 5639 6364 5645 6420 5703 6365 5646 6414 5697 6415 5698 6359 5640 6365 5646 6421 5704 6366 5647 6415 5698 6416 5699 6360 5641 6366 5647 6422 5705 6367 5648 6416 5699 6417 5700 6361 5642 6417 5700 6418 5701 6362 5643 6418 5701 6419 5702 6363 5644 6367 5648 6424 5706 6368 5649 6419 5702 6420 5703 6364 5645 6420 5703 6421 5704 6365 5646 6368 5649 6424 5706 6369 5650 6421 5704 6422 5705 6366 5647 6422 5705 6423 5707 6367 5648 6307 5588 6306 5586 6369 5650 6308 5589 6307 5588 6370 5651 6424 5706 6367 5648 6423 5707 6309 5590 6308 5589 6371 5652 6310 5591 6309 5590 6372 5653 6311 5592 6310 5591 6373 5654 6425 5708 6369 5650 6424 5706 6312 5593 6311 5592 6374 5655 6425 5708 6426 5709 6369 5650 6313 5594 6312 5593 6375 5656 6426 5709 6427 5710 6370 5651 6314 5595 6313 5594 6376 5657 6427 5710 6428 5711 6371 5652 6315 5596 6314 5595 6377 5659 6428 5711 6429 5712 6372 5653 6316 5597 6315 5596 6378 5660 6429 5712 6430 5713 6373 5654 6317 5598 6316 5597 6379 5661 6430 5713 6431 5714 6374 5655 6380 5662 6381 5663 6318 5599 6431 5714 6432 5715 6375 5656 6319 5600 6381 5663 6382 5664 6432 5715 6433 5716 6376 5657 6320 5658 6382 5664 6383 5665 6433 5716 6434 5717 6377 5659 6321 5601 6383 5665 6384 5666 6434 5717 6435 5718 6378 5660 6435 5718 6436 5719 6379 5661 6322 5602 6384 5666 6267 5551 6436 5719 6437 5720 6380 5662 6437 5720 6438 5721 6381 5663 6325 5605 6267 5551 6269 5553 6438 5721 6382 5664 6381 5663 6027 5303 6269 5553 6028 5304 6439 5722 6383 5665 6382 5664 6029 5305 6028 5304 6150 5432 6440 5723 6384 5666 6383 5665 6441 5724 6267 5551 6384 5666 5721 5667 5595 4860 5328 5061 6444 5725 6209 5608 6385 5669 6028 5304 6269 5553 6324 5604 5320 4585 6445 5726 6446 5727 6151 5433 6206 5489 6447 5728 6150 5432 6447 5728 5356 4615 6387 5670 6448 5729 6388 5671 6389 5730 6449 5731 6095 5372 5326 4859 5721 5667 5325 5430 6328 5672 6097 5313 6032 5312 6450 5673 6272 5732 6273 5733 4966 5376 6450 5673 4967 5734 6097 5313 4975 5064 6330 5311 6391 5674 4966 5376 4967 5734 4966 5376 6391 5674 6335 5612 6392 5675 6453 5735 6454 5736 6392 5675 6275 5676 6336 5613 6335 5612 6391 5674 6336 5613 6337 5615 6394 5677 6275 5676 6392 5675 6337 5615 6275 5676 6220 5501 6338 5617 4889 5737 6337 5615 6338 5617 6394 5677 6394 5677 6338 5617 6220 5501 5197 5619 5196 5499 6395 5678 6220 5501 4889 5737 5196 5499 6340 5620 6395 5678 6396 5679 6455 5738 6395 5678 5196 5499 6342 5623 6341 5622 6397 5680 6456 5739 6396 5679 6395 5678 6343 5624 6342 5623 6397 5680 6456 5739 6457 5740 6396 5679 6457 5740 6458 5741 6397 5680 6345 5625 6343 5624 6398 5681 6458 5741 6459 5742 6398 5681 6459 5742 6460 5743 6399 5682 6461 5744 6400 5684 6399 5682 6399 5682 6460 5743 6461 5744 6461 5744 6401 5683 6400 5684 6462 5745 6402 5685 6401 5683 6401 5683 6461 5744 6462 5745 6464 5746 6403 5686 6402 5685 6464 5746 6404 5687 6403 5686 6402 5685 6462 5745 6463 5747 6402 5685 6463 5747 6464 5746 6404 5687 6464 5746 6465 5748 6406 5689 6405 5688 6466 5749 6404 5687 6465 5748 6466 5749 6407 5690 6406 5689 6467 5750 6408 5691 6407 5690 6468 5751 6409 5692 6408 5691 6469 5752 6406 5689 6466 5749 6467 5750 6410 5693 6409 5692 6470 5753 6407 5690 6467 5750 6468 5751 6411 5694 6410 5693 6471 5754 6412 5695 6411 5694 6472 5755 6408 5691 6468 5751 6469 5752 6413 5696 6412 5695 6473 5756 6414 5697 6413 5696 6474 5757 6409 5692 6469 5752 6470 5753 6414 5697 6475 5758 6415 5698 6415 5698 6476 5759 6416 5699 6410 5693 6470 5753 6471 5754 6416 5699 6477 5760 6417 5700 6411 5694 6471 5754 6472 5755 6417 5700 6478 5761 6418 5701 6412 5695 6472 5755 6473 5756 6418 5701 6479 5762 6419 5702 6413 5696 6473 5756 6474 5757 6419 5702 6480 5763 6420 5703 6414 5697 6474 5757 6475 5758 6420 5703 6481 5764 6421 5704 6415 5698 6475 5758 6476 5759 6421 5704 6482 5765 6422 5705 6416 5699 6476 5759 6477 5760 6422 5705 6483 5766 6423 5707 6417 5700 6477 5760 6478 5761 6418 5701 6478 5761 6479 5762 6423 5707 6484 5767 6424 5706 6419 5702 6479 5762 6480 5763 6420 5703 6480 5763 6481 5764 6421 5704 6481 5764 6482 5765 6424 5706 6485 5768 6425 5708 6422 5705 6482 5765 6483 5766 6425 5708 6486 5769 6426 5709 6423 5707 6483 5766 6484 5767 6370 5651 6369 5650 6426 5709 6371 5652 6370 5651 6427 5710 6372 5653 6371 5652 6428 5711 6424 5706 6484 5767 6485 5768 6373 5654 6372 5653 6429 5712 6374 5655 6373 5654 6430 5713 6485 5768 6486 5769 6425 5708 6375 5656 6374 5655 6431 5714 6486 5769 6487 5770 6426 5709 6376 5657 6375 5656 6432 5715 6487 5770 6488 5771 6427 5710 6377 5659 6376 5657 6433 5716 6488 5771 6489 5772 6428 5711 6378 5660 6377 5659 6434 5717 6489 5772 6490 5773 6429 5712 6379 5661 6378 5660 6435 5718 6490 5773 6491 5774 6430 5713 6380 5662 6379 5661 6436 5719 6491 5774 6492 5775 6431 5714 6381 5663 6380 5662 6437 5720 6492 5775 6493 5776 6432 5715 6438 5721 6439 5722 6382 5664 6493 5776 6494 5777 6433 5716 6383 5665 6439 5722 6440 5723 6494 5777 6495 5778 6434 5717 6384 5666 6440 5723 6441 5724 6495 5778 6496 5779 6435 5718 6496 5779 6497 5780 6436 5719 6267 5551 6441 5724 6268 5552 6497 5780 6498 5781 6437 5720 6498 5781 6499 5782 6438 5721 6269 5553 6268 5552 6324 5604 6499 5782 6500 5783 6439 5722 6028 5304 6324 5604 6151 5433 6500 5783 6440 5723 6439 5722 6150 5432 6151 5433 6447 5728 6501 5784 6441 5724 6440 5723 5356 4615 6447 5728 5595 4860 5326 4859 5595 4860 5721 5667 6503 5785 6268 5552 6441 5724 6204 5487 5328 5061 5327 5668 5906 5429 5325 5430 6204 5487 6324 5604 6323 5603 6151 5433 6030 5307 5722 4997 5906 5429 6447 5728 6208 5491 5595 4860 5722 4997 5847 5306 5723 4998 5721 5667 5328 5061 6204 5487 6272 5732 6450 5673 6328 5672 6329 5786 6390 5787 6273 5733 6450 5673 4966 5376 6097 5313 6453 5735 4967 5734 6334 5788 6334 5788 6508 5495 6453 5735 6391 5674 4967 5734 6453 5735 6391 5674 6453 5735 6392 5675 6337 5615 6392 5675 6509 5616 6454 5736 6509 5616 6392 5675 4889 5737 6512 5789 4888 5790 6509 5616 6512 5789 6338 5617 5196 5499 4889 5737 6455 5738 4889 5737 6338 5617 6512 5789 6395 5678 6455 5738 6456 5739 4888 5790 6455 5738 4889 5737 6397 5680 6396 5679 6457 5740 6513 5791 6456 5739 6455 5738 6398 5681 6397 5680 6458 5741 6514 5792 6515 5793 6457 5740 6515 5793 6516 5794 6458 5741 6399 5682 6398 5681 6459 5742 6517 5795 6459 5742 6516 5794 6460 5743 6517 5795 6461 5744 6461 5744 6518 5796 6462 5745 6517 5795 6518 5796 6461 5744 6462 5745 6519 5797 6463 5747 6463 5747 6520 5798 6464 5746 6518 5796 6519 5797 6462 5745 6464 5746 6521 5799 6465 5748 6519 5797 6520 5798 6463 5747 6520 5798 6521 5799 6464 5746 6465 5748 6522 5800 6466 5749 6405 5688 6404 5687 6466 5749 6465 5748 6521 5799 6522 5800 6523 5801 6467 5750 6466 5749 6466 5749 6522 5800 6523 5801 6524 5802 6468 5751 6467 5750 6525 5803 6469 5752 6468 5751 6467 5750 6523 5801 6524 5802 6526 5804 6470 5753 6469 5752 6468 5751 6524 5802 6525 5803 6527 5805 6471 5754 6470 5753 6528 5806 6472 5755 6471 5754 6469 5752 6525 5803 6526 5804 6529 5807 6473 5756 6472 5755 6530 5808 6474 5757 6473 5756 6470 5753 6526 5804 6527 5805 6531 5809 6475 5758 6474 5757 6532 5810 6476 5759 6475 5758 6471 5754 6527 5805 6528 5806 6533 5811 6477 5760 6476 5759 6472 5755 6528 5806 6529 5807 6534 5812 6478 5761 6477 5760 6473 5756 6529 5807 6530 5808 6535 5813 6479 5762 6478 5761 6474 5757 6530 5808 6531 5809 6536 5814 6480 5763 6479 5762 6475 5758 6531 5809 6532 5810 6482 5765 6481 5764 6537 5815 6476 5759 6532 5810 6533 5811 6483 5766 6482 5765 6538 5816 6477 5760 6533 5811 6534 5812 6484 5767 6483 5766 6539 5817 6478 5761 6534 5812 6535 5813 6479 5762 6535 5813 6536 5814 6480 5763 6536 5814 6541 5818 6485 5768 6484 5767 6540 5819 6481 5764 6541 5818 6537 5815 6482 5765 6537 5815 6538 5816 6486 5769 6485 5768 6542 5820 6483 5766 6538 5816 6539 5817 6487 5770 6486 5769 6543 5821 6484 5767 6539 5817 6540 5819 6427 5710 6426 5709 6487 5770 6428 5711 6427 5710 6488 5771 6429 5712 6428 5711 6489 5772 6485 5768 6540 5819 6542 5820 6430 5713 6429 5712 6490 5773 6431 5714 6430 5713 6491 5774 6542 5820 6543 5821 6486 5769 6432 5715 6431 5714 6492 5775 6543 5821 6544 5822 6487 5770 6433 5716 6432 5715 6493 5776 6544 5822 6545 5823 6488 5771 6434 5717 6433 5716 6494 5777 6545 5823 6546 5824 6489 5772 6435 5718 6434 5717 6495 5778 6546 5824 6547 5825 6490 5773 6436 5719 6435 5718 6496 5779 6547 5825 6548 5826 6491 5774 6437 5720 6436 5719 6497 5780 6548 5826 6549 5827 6492 5775 6438 5721 6437 5720 6498 5781 6549 5827 6550 5828 6493 5776 6439 5722 6438 5721 6499 5782 6550 5828 6551 5829 6494 5777 6500 5783 6501 5784 6440 5723 6551 5829 6552 5830 6495 5778 6441 5724 6501 5784 6502 5831 6552 5830 6553 5832 6496 5779 6441 5724 6502 5831 6503 5785 6553 5832 6554 5833 6497 5780 6554 5833 6555 5834 6498 5781 6268 5552 6503 5785 6323 5603 6555 5834 6556 5835 6499 5782 6556 5835 6557 5836 6500 5783 6151 5433 6323 5603 6206 5489 6557 5836 6558 5837 6501 5784 6447 5728 6206 5489 6208 5491 6558 5837 6502 5831 6501 5784 6559 5838 6503 5785 6502 5831 5324 4587 5595 4860 6327 5607 6503 5785 6560 5839 6323 5603 6561 5840 6562 5841 6445 5726 6563 5842 6386 5843 6209 5608 6030 5307 6204 5487 5327 5668 6206 5489 6323 5603 6442 5844 6446 5727 5319 5845 5320 4585 6504 5846 6389 5730 6271 5847 6327 5607 5595 4860 6208 5491 5847 5306 6385 5669 5970 5242 5723 4998 5971 5243 5372 4631 6390 5787 6507 5848 6333 5611 6450 5673 6273 5733 6334 5788 6334 5788 4967 5734 6450 5673 6737 5849 7022 5850 6214 5851 6508 5495 6393 5852 6454 5736 6509 5616 6454 5736 6393 5852 6454 5736 6453 5735 6508 5495 6512 5789 6509 5616 6566 5853 6509 5616 6393 5852 6566 5853 4888 5790 6567 5854 5198 5855 4885 5856 6680 5857 6739 5858 6566 5853 6567 5854 6512 5789 6455 5738 4888 5790 6513 5791 4888 5790 6512 5789 6567 5854 6456 5739 6513 5791 6514 5792 5198 5855 6513 5791 4888 5790 6457 5740 6456 5739 6514 5792 6458 5741 6457 5740 6515 5793 6568 5859 6514 5792 6513 5791 6568 5859 6569 5860 6514 5792 6459 5742 6458 5741 6516 5794 6569 5860 6570 5861 6515 5793 6570 5861 6571 5862 6516 5794 6460 5743 6459 5742 6517 5795 6517 5795 6571 5862 6572 5863 6517 5795 6573 5864 6518 5796 6517 5795 6572 5863 6573 5864 6518 5796 6573 5864 6519 5797 6519 5797 6574 5865 6520 5798 6520 5798 6575 5866 6521 5799 6519 5797 6573 5864 6574 5865 6521 5799 6576 5867 6522 5800 6520 5798 6574 5865 6575 5866 6521 5799 6575 5866 6576 5867 6522 5800 6577 5868 6523 5801 6522 5800 6576 5867 6577 5868 6523 5801 6578 5869 6524 5802 6523 5801 6577 5868 6578 5869 6524 5802 6579 5867 6525 5803 6525 5803 6580 5870 6526 5804 6526 5804 6581 5871 6527 5805 6578 5869 6579 5867 6524 5802 6527 5805 6582 5872 6528 5806 6579 5867 6580 5870 6525 5803 6528 5806 6583 5873 6529 5807 6529 5807 6584 5874 6530 5808 6580 5870 6581 5871 6526 5804 6530 5808 6585 5875 6531 5809 6531 5809 6586 5876 6532 5810 6581 5871 6582 5872 6527 5805 6532 5810 6587 5877 6533 5811 6533 5811 6588 5878 6534 5812 6582 5872 6583 5873 6528 5806 6534 5812 6589 5879 6535 5813 6583 5873 6584 5874 6529 5807 6535 5813 6590 5880 6536 5814 6584 5874 6585 5875 6530 5808 6536 5814 6591 5881 6541 5818 6585 5875 6586 5876 6531 5809 6481 5764 6480 5763 6541 5818 6532 5810 6586 5876 6587 5877 6592 5882 6537 5815 6541 5818 6533 5811 6587 5877 6588 5878 6593 5883 6538 5816 6537 5815 6534 5812 6588 5878 6589 5879 6594 5884 6539 5817 6538 5816 6535 5813 6589 5879 6590 5880 6595 5885 6540 5819 6539 5817 6536 5814 6590 5880 6591 5881 6541 5818 6591 5881 6592 5882 6537 5815 6592 5882 6593 5883 6597 5886 6542 5820 6540 5819 6538 5816 6593 5883 6594 5884 6539 5817 6594 5884 6595 5885 6597 5886 6543 5821 6542 5820 6540 5819 6595 5885 6596 5887 6488 5771 6487 5770 6544 5822 6489 5772 6488 5771 6545 5823 6596 5887 6597 5886 6540 5819 6490 5773 6489 5772 6546 5824 6491 5774 6490 5773 6547 5825 6492 5775 6491 5774 6548 5826 6597 5886 6598 5888 6543 5821 6493 5776 6492 5775 6549 5827 6598 5888 6599 5889 6544 5822 6494 5777 6493 5776 6550 5828 6599 5889 6600 5890 6545 5823 6495 5778 6494 5777 6551 5829 6600 5890 6601 5891 6546 5824 6496 5779 6495 5778 6552 5830 6601 5891 6602 5892 6547 5825 6497 5780 6496 5779 6553 5832 6602 5892 6603 5893 6548 5826 6498 5781 6497 5780 6554 5833 6603 5893 6604 5894 6549 5827 6499 5782 6498 5781 6555 5834 6604 5894 6605 5895 6550 5828 6500 5783 6499 5782 6556 5835 6605 5895 6606 5896 6551 5829 6501 5784 6500 5783 6557 5836 6606 5896 6607 5897 6552 5830 6558 5837 6559 5838 6502 5831 6607 5897 6608 5898 6553 5832 6503 5785 6559 5838 6560 5839 6608 5898 6609 5899 6554 5833 6609 5899 6610 5900 6555 5834 6323 5603 6560 5839 6442 5844 6610 5900 6611 5901 6556 5835 6611 5901 6612 5902 6557 5836 6206 5489 6442 5844 6207 5490 6612 5902 6613 5903 6558 5837 6208 5491 6207 5490 6327 5607 6613 5903 6559 5838 6558 5837 6093 5493 5322 4586 5319 5845 6560 5839 6559 5838 6614 5904 5328 5061 5324 4587 5323 5241 6560 5839 6443 5905 6442 5844 5327 5668 5323 5241 6444 5725 6326 5606 6443 5905 6561 5840 6207 5490 6442 5844 6326 5606 6326 5606 6445 5726 6327 5607 6385 5669 5847 5306 6030 5307 6449 5731 6389 5730 6616 5906 6617 5907 6618 5908 6619 5909 5847 5306 5970 5242 5723 4998 5327 5668 5328 5061 5323 5241 6507 5848 6390 5787 6329 5786 6334 5788 6390 5787 6564 5910 6565 5496 6564 5910 6034 5911 6565 5496 6334 5788 6564 5910 6034 5911 6216 5912 6565 5496 6620 5913 6621 5914 5786 5915 6508 5495 6334 5788 6565 5496 6622 5916 6566 5853 6393 5852 6393 5852 6508 5495 6217 5497 6567 5854 6566 5853 6623 5917 6393 5852 6217 5497 6622 5916 6567 5854 6623 5917 4882 5918 6622 5916 6623 5917 6566 5853 6513 5791 5198 5855 6568 5859 4882 5918 5198 5855 6567 5854 6624 5919 6568 5859 5198 5855 6515 5793 6514 5792 6569 5860 6516 5794 6515 5793 6570 5861 6625 5920 6626 5921 6569 5860 6517 5795 6516 5794 6571 5862 6626 5921 6627 5922 6571 5862 6573 5864 6572 5863 6628 5923 6572 5863 6627 5922 6629 5924 6572 5863 6629 5924 6628 5923 6574 5865 6573 5864 6630 5925 6573 5864 6628 5923 6630 5925 6575 5866 6574 5865 6631 5926 6576 5867 6575 5866 6632 5927 6574 5865 6630 5925 6631 5926 6577 5868 6576 5867 6633 5928 6575 5866 6631 5926 6632 5927 6576 5867 6632 5927 6633 5928 6578 5869 6577 5868 6634 5929 6577 5868 6633 5928 6634 5929 6578 5869 6635 5930 6579 5867 6578 5869 6634 5929 6635 5930 6579 5867 6636 5931 6580 5870 6580 5870 6637 5932 6581 5871 6581 5871 6638 5933 6582 5872 6579 5867 6635 5930 6636 5931 6582 5872 6639 5934 6583 5873 6580 5870 6636 5931 6637 5932 6583 5873 6640 5935 6584 5874 6584 5874 6641 5936 6585 5875 6581 5871 6637 5932 6638 5933 6585 5875 6642 5937 6586 5876 6586 5876 6643 5938 6587 5877 6582 5872 6638 5933 6639 5934 6587 5877 6644 5939 6588 5878 6588 5878 6645 5940 6589 5879 6583 5873 6639 5934 6640 5935 6589 5879 6646 5941 6590 5880 6584 5874 6640 5935 6641 5936 6590 5880 6647 5942 6591 5881 6585 5875 6641 5936 6642 5937 6591 5881 6648 5943 6592 5882 6586 5876 6642 5937 6643 5938 6592 5882 6649 5944 6593 5883 6587 5877 6643 5938 6644 5939 6593 5883 6650 5945 6594 5884 6588 5878 6644 5939 6645 5940 6594 5884 6651 5946 6595 5885 6589 5879 6645 5940 6646 5941 6595 5885 6652 5947 6596 5887 6590 5880 6646 5941 6647 5942 6591 5881 6647 5942 6648 5943 6596 5887 6653 5948 6597 5886 6592 5882 6648 5943 6649 5944 6593 5883 6649 5944 6650 5945 6594 5884 6650 5945 6651 5946 6597 5886 6654 5949 6598 5888 6595 5885 6651 5946 6652 5947 6544 5822 6543 5821 6598 5888 6653 5948 6596 5887 6652 5947 6545 5823 6544 5822 6599 5889 6546 5824 6545 5823 6600 5890 6597 5886 6653 5948 6654 5949 6547 5825 6546 5824 6601 5891 6548 5826 6547 5825 6602 5892 6549 5827 6548 5826 6603 5893 6654 5949 6655 5950 6598 5888 6550 5828 6549 5827 6604 5894 6655 5950 6656 5951 6599 5889 6551 5829 6550 5828 6605 5895 6656 5951 6657 5952 6600 5890 6552 5830 6551 5829 6606 5896 6657 5952 6658 5953 6601 5891 6553 5832 6552 5830 6607 5897 6658 5953 6659 5954 6602 5892 6554 5833 6553 5832 6608 5898 6659 5954 6660 5955 6603 5893 6555 5834 6554 5833 6609 5899 6660 5955 6661 5956 6604 5894 6556 5835 6555 5834 6610 5900 6661 5956 6662 5957 6605 5895 6557 5836 6556 5835 6611 5901 6662 5957 6663 5958 6606 5896 6558 5837 6557 5836 6612 5902 6663 5958 6664 5959 6607 5897 6613 5903 6614 5904 6559 5838 6664 5959 6665 5960 6608 5898 6560 5839 6614 5904 6615 5961 6665 5960 6666 5962 6609 5899 6560 5839 6615 5961 6443 5905 6666 5962 6667 5963 6610 5900 6667 5963 6668 5964 6611 5901 6442 5844 6443 5905 6326 5606 6668 5964 6669 5965 6612 5902 6669 5965 6670 5966 6613 5903 6670 5966 6671 5967 6614 5904 6327 5607 6445 5726 5320 4585 6671 5967 6615 5961 6614 5904 6615 5961 6672 5968 6443 5905 6674 5969 6504 5846 6386 5843 6385 5669 5327 5668 6444 5725 6209 5608 5970 5242 6385 5669 5320 4585 5324 4587 6327 5607 5971 5243 6095 5372 5372 4631 6332 5610 6331 5609 6451 5970 6273 5733 6390 5787 6334 5788 6564 5910 6333 5611 6034 5911 6033 5971 6621 5914 6216 5912 6216 5912 6679 5972 6217 5497 6679 5972 6622 5916 6217 5497 6217 5497 6565 5496 6216 5912 6511 5973 6623 5917 6622 5916 6622 5916 6679 5972 6511 5973 4883 5974 4882 5918 6680 5857 5198 5855 4882 5918 6624 5919 6511 5973 6680 5857 6623 5917 4882 5918 6623 5917 6680 5857 6568 5859 6624 5919 6625 5920 6569 5860 6568 5859 6625 5920 4883 5974 6624 5919 4882 5918 6570 5861 6569 5860 6626 5921 6571 5862 6570 5861 6626 5921 6681 5975 6682 5976 6625 5920 6682 5976 6683 5977 6626 5921 6572 5863 6571 5862 6627 5922 6683 5977 6684 5978 6627 5922 6684 5978 6628 5923 6629 5924 6630 5925 6628 5923 6685 5979 6628 5923 6684 5978 6685 5979 6631 5926 6630 5925 6686 5980 6630 5925 6685 5979 6686 5980 6632 5927 6631 5926 6687 5981 6633 5928 6632 5927 6688 5982 6631 5926 6686 5980 6687 5981 6634 5929 6633 5928 6689 5983 6632 5927 6687 5981 6688 5982 6633 5928 6688 5982 6689 5983 6635 5930 6634 5929 6690 5984 6634 5929 6689 5983 6690 5984 6636 5931 6635 5930 6691 5985 6635 5930 6690 5984 6691 5985 6637 5932 6636 5931 6692 5986 6638 5933 6637 5932 6693 5987 6639 5934 6638 5933 6694 5988 6636 5931 6691 5985 6692 5986 6640 5935 6639 5934 6695 5989 6637 5932 6692 5986 6693 5987 6641 5936 6640 5935 6696 5990 6642 5937 6641 5936 6697 5991 6638 5933 6693 5987 6694 5988 6643 5938 6642 5937 6698 5992 6644 5939 6643 5938 6699 5993 6639 5934 6694 5988 6695 5989 6645 5940 6644 5939 6700 5994 6646 5941 6645 5940 6701 5995 6640 5935 6695 5989 6696 5990 6647 5942 6646 5941 6702 5996 6641 5936 6696 5990 6697 5991 6648 5943 6647 5942 6703 5997 6642 5937 6697 5991 6698 5992 6649 5944 6648 5943 6704 5998 6643 5938 6698 5992 6699 5993 6650 5945 6649 5944 6705 5999 6644 5939 6699 5993 6700 5994 6651 5946 6650 5945 6706 6000 6645 5940 6700 5994 6701 5995 6652 5947 6651 5946 6707 6001 6646 5941 6701 5995 6702 5996 6653 5948 6652 5947 6708 6002 6647 5942 6702 5996 6703 5997 6648 5943 6703 5997 6704 5998 6654 5949 6653 5948 6709 6003 6649 5944 6704 5998 6705 5999 6650 5945 6705 5999 6706 6000 6651 5946 6706 6000 6707 6001 6655 5950 6654 5949 6710 6004 6652 5947 6707 6001 6708 6002 6599 5889 6598 5888 6655 5950 6709 6003 6653 5948 6708 6002 6600 5890 6599 5889 6656 5951 6601 5891 6600 5890 6657 5952 6602 5892 6601 5891 6658 5953 6710 6004 6654 5949 6709 6003 6603 5893 6602 5892 6659 5954 6604 5894 6603 5893 6660 5955 6710 6004 6711 6005 6655 5950 6605 5895 6604 5894 6661 5956 6711 6005 6712 6006 6656 5951 6606 5896 6605 5895 6662 5957 6712 6006 6713 6007 6657 5952 6607 5897 6606 5896 6663 5958 6713 6007 6714 6008 6658 5953 6608 5898 6607 5897 6664 5959 6714 6008 6715 6009 6659 5954 6609 5899 6608 5898 6665 5960 6715 6009 6716 6010 6660 5955 6610 5900 6609 5899 6666 5962 6716 6010 6717 6011 6661 5956 6611 5901 6610 5900 6667 5963 6717 6011 6718 6012 6662 5957 6612 5902 6611 5901 6668 5964 6718 6012 6719 6013 6663 5958 6613 5903 6612 5902 6669 5965 6719 6013 6720 6014 6664 5959 6614 5904 6613 5903 6670 5966 6720 6014 6721 6015 6665 5960 6671 5967 6672 5968 6615 5961 6721 6015 6722 6016 6666 5962 6443 5905 6672 5968 6561 5840 6722 6016 6723 6017 6667 5963 6723 6017 6724 6018 6668 5964 6326 5606 6561 5840 6445 5726 6724 6018 6725 6019 6669 5965 6725 6019 6726 6020 6670 5966 6727 6021 5321 6022 5316 4582 6728 6023 6671 5967 6726 6020 6728 6023 6672 5968 6671 5967 6729 6024 6561 5840 6672 5968 5323 5241 5322 4586 6092 6025 6444 5725 6092 6025 6563 5842 6731 6026 6727 6021 6732 6027 6092 6025 5322 4586 6093 5493 5970 5242 6094 5371 5971 5243 5323 5241 6092 6025 6444 5725 6390 5787 6333 5611 6564 5910 6034 5911 6332 5610 6033 5971 6033 5971 6451 5970 5786 5915 6216 5912 6034 5911 6033 5971 6621 5914 6511 5973 6679 5972 6679 5972 6216 5912 6621 5914 6680 5857 6511 5973 6739 5858 6511 5973 6621 5914 6510 6028 6510 6028 6739 5858 6511 5973 6624 5919 4883 5974 6681 5975 4885 5856 4883 5974 6680 5857 6625 5920 6624 5919 6681 5975 6626 5921 6625 5920 6682 5976 6740 6029 6681 5975 4883 5974 6627 5922 6626 5921 6683 5977 6740 6029 6741 6030 6682 5976 6741 6030 6742 6031 6683 5977 6629 5924 6627 5922 6684 5978 6743 6032 6684 5978 6742 6031 6743 6032 6685 5979 6684 5978 6744 6033 6686 5980 6685 5979 6685 5979 6743 6032 6744 6033 6745 6034 6687 5981 6686 5980 6686 5980 6744 6033 6745 6034 6746 6035 6688 5982 6687 5981 6687 5981 6745 6034 6746 6035 6747 6036 6689 5983 6688 5982 6748 6037 6690 5984 6689 5983 6688 5982 6746 6035 6747 6036 6689 5983 6747 6036 6748 6037 6749 6038 6691 5985 6690 5984 6690 5984 6748 6037 6749 6038 6750 6039 6692 5986 6691 5985 6691 5985 6749 6038 6750 6039 6751 6040 6693 5987 6692 5986 6752 6041 6694 5988 6693 5987 6692 5986 6750 6039 6751 6040 6696 5990 6695 5989 6754 6042 6693 5987 6751 6040 6752 6041 6697 5991 6696 5990 6755 6043 6698 5992 6697 5991 6756 6044 6694 5988 6752 6041 6753 6045 6699 5993 6698 5992 6757 6046 6700 5994 6699 5993 6758 6047 6695 5989 6753 6045 6754 6042 6701 5995 6700 5994 6759 6048 6702 5996 6701 5995 6760 6049 6696 5990 6754 6042 6755 6043 6703 5997 6702 5996 6761 6050 6697 5991 6755 6043 6756 6044 6704 5998 6703 5997 6762 6051 6698 5992 6756 6044 6757 6046 6705 5999 6704 5998 6763 6052 6699 5993 6757 6046 6758 6047 6706 6000 6705 5999 6764 6053 6700 5994 6758 6047 6759 6048 6707 6001 6706 6000 6765 6054 6701 5995 6759 6048 6760 6049 6708 6002 6707 6001 6766 6055 6702 5996 6760 6049 6761 6050 6709 6003 6708 6002 6767 6056 6703 5997 6761 6050 6762 6051 6704 5998 6762 6051 6763 6052 6705 5999 6763 6052 6764 6053 6710 6004 6709 6003 6768 6057 6706 6000 6764 6053 6765 6054 6707 6001 6765 6054 6766 6055 6711 6005 6710 6004 6769 6058 6708 6002 6766 6055 6767 6056 6656 5951 6655 5950 6711 6005 6657 5952 6656 5951 6712 6006 6658 5953 6657 5952 6713 6007 6709 6003 6767 6056 6768 6057 6659 5954 6658 5953 6714 6008 6660 5955 6659 5954 6715 6009 6768 6057 6769 6058 6710 6004 6661 5956 6660 5955 6716 6010 6769 6058 6770 6059 6711 6005 6662 5957 6661 5956 6717 6011 6770 6059 6771 6060 6712 6006 6663 5958 6662 5957 6718 6012 6771 6060 6772 6061 6713 6007 6664 5959 6663 5958 6719 6013 6772 6061 6773 6062 6714 6008 6665 5960 6664 5959 6720 6014 6773 6062 6774 6063 6715 6009 6666 5962 6665 5960 6721 6015 6774 6063 6775 6064 6716 6010 6667 5963 6666 5962 6722 6016 6775 6064 6776 6065 6717 6011 6668 5964 6667 5963 6723 6017 6776 6065 6777 6066 6718 6012 6669 5965 6668 5964 6724 6018 6777 6066 6778 6067 6719 6013 6670 5966 6669 5965 6725 6019 6778 6067 6779 6068 6720 6014 6671 5967 6670 5966 6726 6020 6779 6068 6780 6069 6721 6015 6728 6023 6729 6024 6672 5968 6780 6069 6781 6070 6722 6016 6561 5840 6729 6024 6730 6071 6781 6070 6782 6072 6723 6017 6561 5840 6730 6071 6562 5841 6782 6072 6783 6073 6724 6018 6783 6073 6784 6074 6725 6019 6445 5726 6562 5841 6446 5727 6784 6074 6785 6075 6726 6020 6446 5727 6673 6076 5319 5845 6785 6075 6786 6077 6728 6023 6211 5494 6093 5493 6727 6021 6728 6023 6786 6077 6729 6024 6730 6071 6729 6024 6787 6078 6563 5842 6210 5492 6674 5969 6788 6079 6562 5841 6730 6071 6209 5608 6444 5725 6563 5842 6446 5727 6562 5841 6673 6076 6386 5843 6094 5371 6209 5608 5320 4585 5319 5845 5322 4586 6094 5371 6386 5843 6271 5847 6789 6080 6790 6081 6617 5907 6333 5611 6332 5610 6034 5911 6734 6082 6677 6083 6452 6084 6793 6085 6792 6086 6215 6087 5786 5915 6621 5914 6033 5971 6794 6088 6510 6028 6621 5914 6739 5858 6510 6028 6794 6088 6621 5914 6620 5913 6794 6088 6739 5858 6794 6088 4874 4253 4883 5974 4885 5856 6740 6029 4885 5856 6739 5858 4874 4253 6682 5976 6681 5975 6740 6029 6795 6089 6740 6029 4885 5856 6795 6089 6796 6090 6740 6029 6683 5977 6682 5976 6741 6030 6796 6090 6797 6091 6741 6030 6684 5978 6683 5977 6742 6031 6797 6091 6798 6092 6742 6031 6798 6092 6799 6093 6742 6031 6744 6033 6743 6032 6800 6094 6799 6093 6800 6094 6743 6032 6744 6033 6801 6095 6745 6034 6744 6033 6800 6094 6801 6095 6745 6034 6802 6096 6746 6035 6745 6034 6801 6095 6802 6096 6746 6035 6803 6097 6747 6036 6747 6036 6804 6098 6748 6037 6746 6035 6802 6096 6803 6097 6748 6037 6805 6099 6749 6038 6747 6036 6803 6097 6804 6098 6748 6037 6804 6098 6805 6099 6749 6038 6807 6100 6750 6039 6749 6038 6805 6099 6806 6101 6749 6038 6806 6101 6807 6100 6750 6039 6808 6102 6751 6040 6751 6040 6809 6103 6752 6041 6750 6039 6807 6100 6808 6102 6752 6041 6810 6104 6753 6045 6695 5989 6694 5988 6753 6045 6811 6105 6754 6042 6753 6045 6809 6103 6751 6040 6808 6102 6812 6106 6755 6043 6754 6042 6810 6104 6752 6041 6809 6103 6812 6106 6756 6044 6755 6043 6813 6107 6757 6046 6756 6044 6811 6105 6753 6045 6810 6104 6814 6108 6758 6047 6757 6046 6815 6109 6759 6048 6758 6047 6812 6106 6754 6042 6811 6105 6816 6110 6760 6049 6759 6048 6817 6111 6761 6050 6760 6049 6813 6107 6756 6044 6812 6106 6818 6112 6762 6051 6761 6050 6814 6108 6757 6046 6813 6107 6819 6113 6763 6052 6762 6051 6815 6109 6758 6047 6814 6108 6820 6114 6764 6053 6763 6052 6816 6110 6759 6048 6815 6109 6821 6115 6765 6054 6764 6053 6817 6111 6760 6049 6816 6110 6822 6116 6766 6055 6765 6054 6818 6112 6761 6050 6817 6111 6823 6117 6767 6056 6766 6055 6819 6113 6762 6051 6818 6112 6820 6114 6763 6052 6819 6113 6821 6115 6764 6053 6820 6114 6824 6118 6768 6057 6767 6056 6822 6116 6765 6054 6821 6115 6823 6117 6766 6055 6822 6116 6825 6119 6769 6058 6768 6057 6824 6118 6767 6056 6823 6117 6712 6006 6711 6005 6770 6059 6713 6007 6712 6006 6771 6060 6714 6008 6713 6007 6772 6061 6768 6057 6824 6118 6825 6119 6715 6009 6714 6008 6773 6062 6716 6010 6715 6009 6774 6063 6825 6119 6826 6120 6769 6058 6717 6011 6716 6010 6775 6064 6826 6120 6827 6121 6770 6059 6718 6012 6717 6011 6776 6065 6827 6121 6828 6122 6771 6060 6719 6013 6718 6012 6777 6066 6828 6122 6829 6123 6772 6061 6720 6014 6719 6013 6778 6067 6829 6123 6830 6124 6773 6062 6721 6015 6720 6014 6779 6068 6830 6124 6831 6125 6774 6063 6722 6016 6721 6015 6780 6069 6831 6125 6832 6126 6775 6064 6723 6017 6722 6016 6781 6070 6832 6126 6833 6127 6776 6065 6724 6018 6723 6017 6782 6072 6833 6127 6834 6128 6777 6066 6725 6019 6724 6018 6783 6073 6834 6128 6835 6129 6778 6067 6726 6020 6725 6019 6784 6074 6835 6129 6836 6130 6779 6068 6728 6023 6726 6020 6785 6075 6836 6130 6837 6131 6780 6069 6786 6077 6787 6078 6729 6024 6837 6131 6838 6132 6781 6070 6730 6071 6787 6078 6788 6079 6838 6132 6839 6133 6782 6072 6562 5841 6788 6079 6673 6076 6839 6133 6840 6134 6783 6073 6840 6134 6841 6135 6784 6074 6842 6136 6731 6026 6732 6027 6785 6075 6841 6135 6843 6137 5319 5845 5317 4583 5321 6022 6844 6138 6786 6077 6843 6137 6844 6138 6787 6078 6786 6077 6787 6078 6845 6139 6788 6079 6092 6025 6093 5493 6210 5492 6673 6076 6788 6079 6846 6140 5313 4579 6732 6027 5314 4580 5319 5845 6673 6076 5317 4583 6387 5670 6731 6026 6848 6141 5319 5845 5321 6022 6093 5493 6676 6142 6616 5906 6850 6143 6094 5371 6271 5847 6095 5372 6563 5842 6092 6025 6210 5492 6734 6144 6452 6144 6451 6144 6332 5610 6451 5970 6033 5971 6451 5970 6452 6084 5787 6145 5787 6145 5786 5915 6451 5970 6791 6146 5787 6145 5788 6147 5787 6145 6791 6146 5786 5915 6791 6146 6854 6148 6620 5913 6791 6146 6620 5913 5786 5915 6854 6148 6794 6088 6620 5913 6794 6088 6854 6148 6738 6149 4885 5856 4874 4253 6795 6089 4873 4251 6794 6088 6738 6149 4873 4251 4874 4253 6794 6088 5018 4252 6795 6089 4874 4253 6741 6030 6740 6029 6796 6090 6742 6031 6741 6030 6797 6091 6855 6150 6856 6151 6796 6090 6856 6151 6857 6152 6797 6091 6743 6032 6742 6031 6799 6093 6857 6152 6858 6153 6798 6092 6860 6154 6799 6093 6858 6153 6801 6095 6800 6094 6859 6155 6800 6094 6860 6154 6859 6155 6802 6096 6801 6095 6859 6155 6803 6097 6802 6096 6861 6156 6802 6096 6859 6155 6861 6156 6804 6098 6803 6097 6862 6157 6805 6099 6804 6098 6863 6158 6803 6097 6861 6156 6862 6157 6806 6101 6805 6099 6864 6159 6804 6098 6862 6157 6863 6158 6807 6100 6806 6101 6865 6160 6805 6099 6863 6158 6864 6159 6808 6102 6807 6100 6866 6161 6806 6101 6864 6159 6865 6160 6866 6161 6868 6162 6808 6102 6807 6100 6865 6160 6866 6161 6868 6162 6869 6163 6809 6103 6869 6163 6870 6164 6810 6104 6809 6103 6808 6102 6868 6162 6870 6164 6871 6165 6811 6105 6810 6104 6809 6103 6869 6163 6871 6165 6872 6166 6812 6106 6872 6166 6873 6167 6813 6107 6811 6105 6810 6104 6870 6164 6873 6167 6874 6168 6814 6108 6874 6168 6875 6169 6815 6109 6812 6106 6811 6105 6871 6165 6875 6169 6876 6170 6816 6110 6876 6170 6877 6171 6817 6111 6813 6107 6812 6106 6872 6166 6877 6171 6878 6172 6818 6112 6814 6108 6813 6107 6873 6167 6878 6172 6879 6173 6819 6113 6815 6109 6814 6108 6874 6168 6879 6173 6880 6174 6820 6114 6816 6110 6815 6109 6875 6169 6880 6174 6881 6175 6821 6115 6817 6111 6816 6110 6876 6170 6881 6175 6882 6176 6822 6116 6818 6112 6817 6111 6877 6171 6882 6176 6883 6177 6823 6117 6819 6113 6818 6112 6878 6172 6883 6177 6884 6178 6824 6118 6820 6114 6819 6113 6879 6173 6821 6115 6820 6114 6880 6174 6822 6116 6821 6115 6881 6175 6885 6179 6825 6119 6884 6178 6823 6117 6822 6116 6882 6176 6824 6118 6823 6117 6883 6177 6770 6059 6769 6058 6826 6120 6771 6060 6770 6059 6827 6121 6772 6061 6771 6060 6828 6122 6825 6119 6824 6118 6884 6178 6773 6062 6772 6061 6829 6123 6774 6063 6773 6062 6830 6124 6825 6119 6885 6179 6826 6120 6775 6064 6774 6063 6831 6125 6826 6120 6886 6180 6827 6121 6776 6065 6775 6064 6832 6126 6827 6121 6887 6181 6828 6122 6777 6066 6776 6065 6833 6127 6828 6122 6888 6182 6829 6123 6778 6067 6777 6066 6834 6128 6888 6182 6889 6183 6829 6123 6779 6068 6778 6067 6835 6129 6889 6183 6890 6184 6830 6124 6780 6069 6779 6068 6836 6130 6890 6184 6891 6185 6831 6125 6781 6070 6780 6069 6837 6131 6891 6185 6892 6186 6832 6126 6782 6072 6781 6070 6838 6132 6892 6186 6893 6187 6833 6127 6783 6073 6782 6072 6839 6133 6893 6187 6894 6188 6834 6128 6784 6074 6783 6073 6840 6134 6894 6188 6895 6189 6835 6129 6785 6075 6784 6074 6841 6135 6895 6189 6896 6190 6836 6130 6786 6077 6785 6075 6843 6137 6896 6190 6897 6191 6837 6131 6844 6138 6845 6139 6787 6078 6897 6191 6898 6192 6838 6132 6788 6079 6845 6139 6846 6140 6898 6192 6899 6193 6839 6133 6673 6076 6846 6140 5317 4583 6899 6193 6900 6194 6840 6134 6900 6194 6901 6195 6841 6135 5313 4579 6842 6136 6732 6027 6901 6195 6902 6196 6843 6137 6731 6026 6387 5670 6727 6021 6844 6138 6902 6196 6903 6197 6845 6139 6903 6197 6904 6198 6210 5492 6211 5494 6388 5671 6846 6140 6845 6139 6904 6198 6674 5969 6388 5671 6847 6199 6846 6140 6905 6200 5317 4583 5316 4582 5315 4581 5314 4580 6386 5843 6563 5842 6674 5969 5316 4582 5321 6022 5317 4583 6727 6021 5316 4582 6732 6027 6504 5846 6271 5847 6386 5843 6093 5493 5321 6022 6727 6021 6790 6081 6906 6201 6907 6202 6735 6203 6963 6204 6678 6205 5787 6145 6677 6083 5788 6147 5788 6147 6678 6205 6213 6206 6853 6207 5788 6147 6213 6206 6853 6207 6791 6146 5788 6147 6854 6148 6853 6207 6908 6208 6853 6207 6854 6148 6791 6146 6908 6208 6738 6149 6854 6148 4873 4251 6738 6149 6910 6209 6910 6209 4954 4249 4873 4251 6738 6149 6908 6208 6910 6209 6795 6089 5018 4252 6855 6150 6796 6090 6795 6089 6855 6150 4873 4251 4954 4249 5018 4252 6797 6091 6796 6090 6856 6151 4954 4249 6911 6210 6855 6150 6798 6092 6797 6091 6857 6152 6911 6210 6912 6211 6856 6151 6799 6093 6798 6092 6858 6153 6800 6094 6799 6093 6860 6154 6912 6211 6913 6212 6858 6153 6915 6213 6860 6154 6913 6212 6915 6213 6859 6155 6860 6154 6914 6214 6916 6215 6859 6155 6916 6215 6917 6216 6861 6156 6861 6156 6859 6155 6916 6215 6917 6216 6918 6217 6862 6157 6862 6157 6861 6156 6917 6216 6918 6217 6919 6218 6863 6158 6919 6218 6920 6219 6864 6159 6863 6158 6862 6157 6918 6217 6920 6219 6867 6220 6865 6160 6864 6159 6863 6158 6919 6218 6867 6220 6921 6221 6866 6161 6865 6160 6864 6159 6920 6219 6866 6161 6865 6160 6867 6220 6922 6222 6868 6162 6921 6221 6923 6223 6869 6163 6922 6222 6924 6224 6870 6164 6923 6223 6868 6162 6866 6161 6921 6221 6925 6225 6871 6165 6924 6224 6869 6163 6868 6162 6922 6222 6926 6226 6872 6166 6925 6225 6870 6164 6869 6163 6923 6223 6927 6227 6873 6167 6926 6226 6928 6228 6874 6168 6927 6227 6871 6165 6870 6164 6924 6224 6929 6229 6875 6169 6928 6228 6930 6230 6876 6170 6929 6229 6872 6166 6871 6165 6925 6225 6931 6231 6877 6171 6930 6230 6873 6167 6872 6166 6926 6226 6932 6232 6878 6172 6931 6231 6874 6168 6873 6167 6927 6227 6933 6233 6879 6173 6932 6232 6875 6169 6874 6168 6928 6228 6934 6234 6880 6174 6933 6233 6876 6170 6875 6169 6929 6229 6935 6235 6881 6175 6934 6234 6877 6171 6876 6170 6930 6230 6936 6236 6882 6176 6935 6235 6878 6172 6877 6171 6931 6231 6937 6237 6883 6177 6936 6236 6879 6173 6878 6172 6932 6232 6938 6238 6884 6178 6937 6237 6880 6174 6879 6173 6933 6233 6881 6175 6880 6174 6934 6234 6882 6176 6881 6175 6935 6235 6939 6239 6885 6179 6938 6238 6883 6177 6882 6176 6936 6236 6884 6178 6883 6177 6937 6237 6886 6180 6826 6120 6885 6179 6887 6181 6827 6121 6886 6180 6888 6182 6828 6122 6887 6181 6885 6179 6884 6178 6938 6238 6829 6123 6889 6183 6830 6124 6831 6125 6830 6124 6890 6184 6885 6179 6939 6239 6886 6180 6832 6126 6831 6125 6891 6185 6886 6180 6940 6240 6887 6181 6833 6127 6832 6126 6892 6186 6887 6181 6941 6241 6888 6182 6834 6128 6833 6127 6893 6187 6888 6182 6942 6242 6889 6183 6835 6129 6834 6128 6894 6188 6889 6183 6943 6243 6890 6184 6836 6130 6835 6129 6895 6189 6890 6184 6944 6244 6891 6185 6837 6131 6836 6130 6896 6190 6944 6244 6945 6245 6891 6185 6838 6132 6837 6131 6897 6191 6945 6245 6946 6246 6892 6186 6839 6133 6838 6132 6898 6192 6946 6246 6947 6247 6893 6187 6840 6134 6839 6133 6899 6193 6947 6247 6948 6248 6894 6188 6841 6135 6840 6134 6900 6194 6948 6248 6949 6249 6895 6189 6843 6137 6841 6135 6901 6195 6949 6249 6950 6250 6896 6190 6844 6138 6843 6137 6902 6196 6950 6250 6951 6251 6897 6191 6845 6139 6844 6138 6903 6197 6951 6251 6952 6252 6898 6192 6904 6198 6905 6200 6846 6140 6952 6252 6953 6253 6899 6193 5317 4583 6905 6200 5315 4581 6953 6253 6954 6254 6900 6194 6955 6255 5313 4579 5312 4578 6954 6254 6956 6256 6901 6195 5316 4582 5314 4580 6732 6027 6902 6196 6956 6256 6957 6257 6958 6258 6903 6197 6957 6257 6958 6258 6959 6259 6904 6198 6904 6198 6959 6259 6905 6200 6847 6199 6505 6260 6618 5908 5318 4584 5315 4581 6905 6200 6960 6261 6961 6262 6842 6136 6961 6262 6849 6263 6848 6141 6504 5846 6847 6199 6675 6264 6271 5847 6389 5730 6095 5372 6388 5671 6674 5969 6210 5492 6095 5372 6449 5731 5372 4631 6963 6204 6735 6203 6736 6265 6452 6084 6677 6083 5787 6145 6213 6206 6963 6204 6215 6087 6853 6207 6213 6206 6792 6086 6792 6086 6908 6208 6853 6207 6910 6209 6908 6208 6964 6266 6908 6208 6792 6086 6964 6266 6964 6266 6965 4250 6910 6209 6855 6150 5018 4252 4954 4249 6965 4250 4954 4249 6910 6209 6856 6151 6855 6150 6911 6210 4953 4248 6966 6267 4954 4249 6857 6152 6856 6151 6912 6211 6966 6267 6967 6268 6911 6210 6858 6153 6857 6152 6912 6211 6967 6268 6968 6269 6912 6211 6860 6154 6858 6153 6913 6212 6968 6269 6969 6270 6913 6212 6914 6214 6859 6155 6915 6213 6913 6212 6969 6270 6915 6213 6971 6271 6970 6272 6914 6214 6971 6271 6914 6214 6915 6213 6970 6272 6972 6273 6916 6215 6970 6272 6916 6215 6914 6214 6972 6273 6973 6274 6917 6216 6974 6275 6918 6217 6973 6274 6972 6273 6917 6216 6916 6215 6975 6276 6919 6218 6974 6275 6976 6277 6920 6219 6975 6276 6973 6274 6918 6217 6917 6216 6974 6275 6919 6218 6918 6217 6977 6278 6867 6220 6976 6277 6975 6276 6920 6219 6919 6218 6978 6279 6921 6221 6977 6278 6976 6277 6867 6220 6920 6219 6977 6278 6921 6221 6867 6220 6979 6280 6922 6222 6978 6279 6980 6281 6923 6223 6979 6280 6981 6282 6924 6224 6980 6281 6978 6279 6922 6222 6921 6221 6982 6283 6925 6225 6981 6282 6979 6280 6923 6223 6922 6222 6983 6284 6926 6226 6982 6283 6980 6281 6924 6224 6923 6223 6984 6285 6927 6227 6983 6284 6985 6286 6928 6228 6984 6285 6981 6282 6925 6225 6924 6224 6986 6287 6929 6229 6985 6286 6987 6288 6930 6230 6986 6287 6982 6283 6926 6226 6925 6225 6988 6289 6931 6231 6987 6288 6983 6284 6927 6227 6926 6226 6989 6290 6932 6232 6988 6289 6984 6285 6928 6228 6927 6227 6990 6291 6933 6233 6989 6290 6985 6286 6929 6229 6928 6228 6991 6292 6934 6234 6990 6291 6986 6287 6930 6230 6929 6229 6992 6293 6935 6235 6991 6292 6931 6231 6930 6230 6987 6288 6993 6294 6936 6236 6992 6293 6932 6232 6931 6231 6988 6289 6994 6295 6937 6237 6993 6294 6933 6233 6932 6232 6989 6290 6995 6296 6938 6238 6994 6295 6934 6234 6933 6233 6990 6291 6935 6235 6934 6234 6991 6292 6996 6297 6938 6238 6995 6296 6936 6236 6935 6235 6992 6293 6937 6237 6936 6236 6993 6294 6938 6238 6937 6237 6994 6295 6940 6240 6886 6180 6939 6239 6941 6241 6887 6181 6940 6240 6942 6242 6888 6182 6941 6241 6939 6239 6938 6238 6996 6297 6943 6243 6889 6183 6942 6242 6944 6244 6890 6184 6943 6243 6939 6239 6996 6297 6940 6240 6891 6185 6945 6245 6892 6186 6940 6240 6997 6298 6941 6241 6893 6187 6892 6186 6946 6246 6941 6241 6998 6299 6942 6242 6894 6188 6893 6187 6947 6247 6942 6242 6999 6300 6943 6243 6895 6189 6894 6188 6948 6248 6943 6243 7000 6301 6944 6244 6896 6190 6895 6189 6949 6249 6944 6244 7001 6302 6945 6245 6897 6191 6896 6190 6950 6250 6945 6245 7002 6303 6946 6246 6898 6192 6897 6191 6951 6251 6946 6246 7003 6304 6947 6247 6899 6193 6898 6192 6952 6252 7003 6304 7004 6305 6947 6247 6900 6194 6899 6193 6953 6253 7004 6305 7005 6306 6948 6248 6901 6195 6900 6194 6954 6254 7005 6306 7006 6307 6949 6249 6902 6196 6901 6195 6956 6256 7006 6307 7007 6308 6950 6250 6903 6197 6902 6196 6957 6257 7007 6308 7008 6309 6951 6251 6904 6198 6903 6197 6958 6258 7008 6309 7009 6310 6952 6252 6959 6259 5318 4584 6905 6200 7009 6310 7010 6311 6953 6253 5318 4584 7011 6312 5312 4578 6954 6254 7010 6311 7012 6313 6960 6261 6842 6136 5313 4579 6956 6256 7012 6313 7013 6314 6848 6141 6842 6136 6961 6262 7014 6315 6957 6257 7013 6314 7014 6315 7015 6316 6958 6258 6959 6259 7015 6316 7011 6312 6505 6260 6388 5671 6448 5729 6959 6259 7011 6312 5318 4584 5318 4584 5312 4578 5314 4580 6504 5846 6674 5969 6847 6199 6616 5906 6733 6317 7016 6318 7017 6319 7018 6320 6962 6321 6675 6264 6389 5730 6504 5846 6211 5494 6727 6021 6387 5670 7020 6322 6907 6202 7021 6323 6677 6083 6678 6205 5788 6147 6678 6205 6963 6204 6213 6206 6215 6087 6792 6086 6213 6206 7024 6324 7025 6325 7239 6326 6793 6085 6964 6266 6792 6086 6965 4250 6964 6266 6909 6327 6964 6266 6793 6085 6909 6327 6965 4250 6909 6327 5047 4358 6911 6210 4954 4249 6966 6267 5047 4358 4953 4248 6965 4250 5047 4358 5046 4357 4953 4248 6912 6211 6911 6210 6967 6268 5046 4357 7026 6328 6967 6268 6913 6212 6912 6211 6968 6269 7026 6328 7027 6329 6968 6269 6971 6271 6915 6213 6969 6270 7029 6330 6971 6271 6969 6270 7030 6331 6970 6272 7029 6330 6970 6272 6971 6271 7029 6330 7031 6332 6972 6273 7030 6331 7032 6333 6973 6274 7031 6332 6972 6273 6970 6272 7030 6331 7031 6332 6973 6274 6972 6273 6974 6275 7032 6333 7033 6334 6975 6276 7033 6334 7034 6335 7032 6333 6974 6275 6973 6274 6976 6277 7034 6335 7035 6336 7033 6334 6975 6276 6974 6275 6977 6278 7035 6336 7036 6337 7034 6335 6976 6277 6975 6276 6978 6279 7036 6337 7037 6338 7035 6336 6977 6278 6976 6277 7036 6337 6978 6279 6977 6278 6979 6280 7037 6338 7038 6339 6980 6281 7038 6339 7039 6340 7037 6338 6979 6280 6978 6279 6981 6282 7039 6340 7040 6341 7038 6339 6980 6281 6979 6280 6982 6283 7040 6341 7041 6342 7039 6340 6981 6282 6980 6281 6983 6284 7041 6342 7042 6343 6984 6285 7042 6343 7043 6344 7040 6341 6982 6283 6981 6282 6985 6286 7043 6344 7044 6345 7045 6346 7046 6347 6987 6288 7041 6342 6983 6284 6982 6283 7047 6348 6988 6289 7046 6347 7042 6343 6984 6285 6983 6284 7048 6349 6989 6290 7047 6348 7043 6344 6985 6286 6984 6285 7049 6350 6990 6291 7048 6349 7044 6345 6986 6287 6985 6286 7050 6351 6991 6292 7049 6350 7045 6346 6987 6288 6986 6287 7051 6352 6992 6293 7050 6351 7046 6347 6988 6289 6987 6288 7052 6353 6993 6294 7051 6352 7047 6348 6989 6290 6988 6289 7053 6354 6994 6295 7052 6353 7048 6349 6990 6291 6989 6290 7054 6355 6995 6296 7053 6354 7049 6350 6991 6292 6990 6291 7050 6351 6992 6293 6991 6292 7051 6352 6993 6294 6992 6293 7055 6356 6996 6297 7054 6355 7052 6353 6994 6295 6993 6294 7053 6354 6995 6296 6994 6295 6997 6298 6940 6240 6996 6297 6998 6299 6941 6241 6997 6298 6996 6297 6995 6296 7054 6355 6999 6300 6942 6242 6998 6299 7000 6301 6943 6243 6999 6300 7001 6302 6944 6244 7000 6301 6996 6297 7055 6356 6997 6298 7002 6303 6945 6245 7001 6302 6997 6298 7056 6357 6998 6299 7003 6304 6946 6246 7002 6303 6998 6299 7057 6358 6999 6300 6947 6247 7004 6305 6948 6248 6999 6300 7058 6359 7000 6301 6949 6249 6948 6248 7005 6306 7000 6301 7059 6360 7001 6302 6950 6250 6949 6249 7006 6307 7001 6302 7060 6361 7002 6303 6951 6251 6950 6250 7007 6308 7002 6303 7061 6362 7003 6304 6952 6252 6951 6251 7008 6309 7003 6304 7062 6363 7004 6305 6953 6253 6952 6252 7009 6310 7004 6305 7063 6364 7005 6306 6954 6254 6953 6253 7010 6311 7063 6364 7064 6365 7005 6306 6956 6256 6954 6254 7012 6313 7064 6365 7065 6366 7006 6307 6957 6257 6956 6256 7013 6314 7065 6366 7066 6367 7007 6308 6958 6258 6957 6257 7014 6315 7066 6367 7067 6368 7008 6309 6959 6259 6958 6258 7015 6316 7067 6368 7068 6369 7009 6310 7011 6312 7015 6316 7069 6370 7070 6371 7010 6311 7068 6369 7070 6371 7072 6372 7012 6313 7013 6314 7072 6372 7073 6373 7014 6315 7073 6373 7074 6374 6731 6026 6842 6136 6848 6141 7015 6316 7074 6374 7069 6370 6387 5670 6848 6141 6448 5729 7069 6370 5311 6375 7011 6312 7011 6312 5311 6375 5312 4578 6619 5909 6618 5908 6505 6260 6617 5907 6733 6317 6618 5908 7075 6376 7076 6377 6849 6263 6675 6264 6618 5908 6733 6317 6848 6141 6506 6378 6448 5729 6388 5671 6505 6260 6847 6199 6214 5851 6963 6204 6736 6265 6215 6087 6963 6204 6214 5851 6793 6085 6214 5851 7079 6379 6214 5851 6793 6085 6215 6087 7079 6379 7080 6380 6793 6085 7080 6380 6909 6327 6793 6085 5047 4358 6909 6327 7080 6380 6966 6267 4953 4248 5046 4357 7080 6380 4868 6381 5047 4358 6967 6268 6966 6267 5046 4357 5047 4358 4868 6381 5048 4359 6968 6269 6967 6268 7026 6328 5048 4359 7084 6382 5046 4357 6969 6270 6968 6269 7027 6329 7085 6383 7026 6328 7084 6382 7028 6384 6969 6270 7027 6329 7029 6330 6969 6270 7028 6384 7027 6329 7086 6385 7028 6384 7028 6384 7086 6385 7029 6330 7089 6386 7031 6332 7087 6387 7030 6331 7029 6330 7087 6387 7090 6388 7032 6333 7089 6386 7031 6332 7030 6331 7087 6387 7091 6389 7032 6333 7090 6388 7032 6333 7031 6332 7089 6386 7092 6390 7034 6335 7091 6389 7033 6334 7032 6333 7091 6389 7093 6391 7035 6336 7092 6390 7034 6335 7033 6334 7091 6389 7094 6392 7036 6337 7093 6391 7035 6336 7034 6335 7092 6390 7095 6393 7037 6338 7094 6392 7036 6337 7035 6336 7093 6391 7037 6338 7036 6337 7094 6392 7096 6394 7038 6339 7095 6393 7097 6395 7039 6340 7096 6394 7098 6396 7040 6341 7097 6395 7038 6339 7037 6338 7095 6393 7099 6397 7041 6342 7098 6396 7039 6340 7038 6339 7096 6394 7100 6398 7042 6343 7099 6397 7040 6341 7039 6340 7097 6395 7101 6399 7043 6344 7100 6398 7102 6400 7044 6345 7101 6399 7041 6342 7040 6341 7098 6396 7045 6346 6986 6287 7044 6345 7045 6346 7102 6400 7103 6401 7099 6397 7042 6343 7041 6342 7046 6347 7103 6401 7104 6402 7100 6398 7043 6344 7042 6343 7047 6348 7104 6402 7105 6403 7101 6399 7044 6345 7043 6344 7048 6349 7105 6403 7106 6404 7102 6400 7045 6346 7044 6345 7049 6350 7106 6404 7107 6405 7103 6401 7046 6347 7045 6346 7050 6351 7107 6405 7108 6406 7104 6402 7047 6348 7046 6347 7051 6352 7108 6406 7109 6407 7105 6403 7048 6349 7047 6348 7052 6353 7109 6407 7110 6408 7106 6404 7049 6350 7048 6349 7053 6354 7110 6408 7111 6409 7107 6405 7050 6351 7049 6350 7054 6355 7111 6409 7112 6410 7108 6406 7051 6352 7050 6351 7109 6407 7052 6353 7051 6352 7110 6408 7053 6354 7052 6353 7055 6356 7112 6410 7113 6411 7111 6409 7054 6355 7053 6354 7056 6357 6997 6298 7055 6356 7057 6358 6998 6299 7056 6357 7058 6359 6999 6300 7057 6358 7112 6410 7055 6356 7054 6355 7059 6360 7000 6301 7058 6359 7060 6361 7001 6302 7059 6360 7055 6356 7113 6411 7056 6357 7061 6362 7002 6303 7060 6361 7056 6357 7114 6412 7057 6358 7062 6363 7003 6304 7061 6362 7057 6358 7115 6413 7058 6359 7063 6364 7004 6305 7062 6363 7058 6359 7116 6414 7059 6360 7005 6306 7064 6365 7006 6307 7059 6360 7117 6415 7060 6361 7007 6308 7006 6307 7065 6366 7060 6361 7118 6416 7061 6362 7008 6309 7007 6308 7066 6367 7061 6362 7119 6417 7062 6363 7009 6310 7008 6309 7067 6368 7062 6363 7120 6418 7063 6364 7010 6311 7009 6310 7068 6369 7063 6364 7121 6419 7064 6365 7012 6313 7010 6311 7070 6371 7064 6365 7122 6420 7065 6366 7013 6314 7012 6313 7072 6372 7122 6420 7123 6421 7065 6366 7014 6315 7013 6314 7073 6373 7123 6421 7124 6422 7066 6367 7015 6316 7014 6315 7074 6374 7124 6422 7125 6423 7067 6368 7069 6370 7074 6374 7126 6424 7127 6425 7068 6369 7125 6423 5311 6375 7069 6370 5309 6426 7128 6427 7070 6371 7127 6425 7129 6428 6960 6261 6955 6255 7128 6427 7130 6429 7072 6372 7131 6430 6961 6262 6960 6261 7073 6373 7130 6429 7132 6431 7075 6376 6849 6263 6961 6262 7126 6424 7074 6374 7132 6431 6848 6141 6849 6263 6506 6378 7069 6370 7126 6424 5309 6426 5312 4578 5311 6375 6955 6255 6506 6378 6505 6260 6448 5729 5313 4579 6955 6255 6960 6261 6675 6264 6847 6199 6618 5908 6616 5906 7016 6318 7133 6432 6733 6317 6389 5730 6675 6264 7019 6433 6850 6143 7135 6434 7079 6379 7022 5850 7136 6435 7022 5850 7079 6379 6214 5851 7080 6380 7079 6379 7136 6435 7080 6380 7136 6435 7137 6436 4868 6381 7080 6380 4869 6437 4868 6381 7083 6438 5048 4359 7080 6380 7137 6436 4869 6437 7026 6328 5046 4357 7084 6382 4869 6437 7083 6438 4868 6381 7027 6329 7026 6328 7085 6383 7083 6438 7138 6439 5048 4359 7138 6439 7139 6440 7084 6382 7086 6385 7027 6329 7085 6383 7088 6441 7029 6330 7086 6385 7085 6383 7140 6442 7086 6385 7087 6387 7029 6330 7088 6441 7086 6385 7141 6443 7088 6441 7142 6444 7087 6387 7141 6443 7141 6443 7087 6387 7088 6441 7143 6445 7089 6386 7142 6444 7144 6446 7090 6388 7143 6445 7142 6444 7089 6386 7087 6387 7145 6447 7091 6389 7144 6446 7143 6445 7090 6388 7089 6386 7146 6448 7092 6390 7145 6447 7144 6446 7091 6389 7090 6388 7147 6449 7093 6391 7146 6448 7148 6450 7094 6392 7147 6449 7145 6447 7092 6390 7091 6389 7146 6448 7093 6391 7092 6390 7149 6451 7095 6393 7148 6450 7147 6449 7094 6392 7093 6391 7148 6450 7095 6393 7094 6392 7150 6452 7096 6394 7149 6451 7151 6453 7097 6395 7150 6452 7152 6454 7098 6396 7151 6453 7096 6394 7095 6393 7149 6451 7153 6455 7099 6397 7152 6454 7097 6395 7096 6394 7150 6452 7154 6456 7100 6398 7153 6455 7098 6396 7097 6395 7151 6453 7155 6457 7101 6399 7154 6456 7156 6458 7102 6400 7155 6457 7099 6397 7098 6396 7152 6454 7157 6459 7103 6401 7156 6458 7158 6460 7104 6402 7157 6459 7100 6398 7099 6397 7153 6455 7159 6461 7105 6403 7158 6460 7101 6399 7100 6398 7154 6456 7160 6462 7106 6404 7159 6461 7102 6400 7101 6399 7155 6457 7161 6463 7107 6405 7160 6462 7103 6401 7102 6400 7156 6458 7162 6464 7108 6406 7161 6463 7104 6402 7103 6401 7157 6459 7163 6465 7109 6407 7162 6464 7105 6403 7104 6402 7158 6460 7164 6466 7110 6408 7163 6465 7106 6404 7105 6403 7159 6461 7165 6467 7111 6409 7164 6466 7107 6405 7106 6404 7160 6462 7166 6468 7112 6410 7165 6467 7108 6406 7107 6405 7161 6463 7109 6407 7108 6406 7162 6464 7110 6408 7109 6407 7163 6465 7167 6469 7113 6411 7166 6468 7111 6409 7110 6408 7164 6466 7165 6467 7112 6410 7111 6409 7114 6412 7056 6357 7113 6411 7115 6413 7057 6358 7114 6412 7116 6414 7058 6359 7115 6413 7166 6468 7113 6411 7112 6410 7117 6415 7059 6360 7116 6414 7118 6416 7060 6361 7117 6415 7113 6411 7167 6469 7114 6412 7119 6417 7061 6362 7118 6416 7114 6412 7168 6470 7115 6413 7120 6418 7062 6363 7119 6417 7115 6413 7169 6471 7116 6414 7121 6419 7063 6364 7120 6418 7116 6414 7170 6472 7117 6415 7122 6420 7064 6365 7121 6419 7117 6415 7171 6473 7118 6416 7065 6366 7123 6421 7066 6367 7118 6416 7172 6474 7119 6417 7067 6368 7066 6367 7124 6422 7119 6417 7173 6475 7120 6418 7068 6369 7067 6368 7125 6423 7120 6418 7174 6476 7121 6419 7070 6371 7068 6369 7127 6425 7121 6419 7175 6477 7122 6420 7072 6372 7070 6371 7128 6427 7122 6420 7176 6478 7123 6421 7073 6373 7072 6372 7130 6429 7176 6478 7177 6479 7123 6421 7074 6374 7073 6373 7132 6431 7177 6479 7178 6480 7124 6422 7126 6424 7132 6431 7179 6481 7180 6482 7125 6423 7178 6480 5309 6426 7126 6424 5310 6483 7127 6425 7180 6482 7181 6484 5308 4577 7071 6485 5309 6426 7128 6427 7181 6484 7182 6486 6955 6255 5311 6375 7071 6485 7183 6487 7130 6429 7182 6486 7183 6487 7179 6481 7132 6431 5310 6483 7126 6424 7179 6481 5311 6375 5309 6426 7071 6485 6617 5907 6619 5909 6789 6080 7016 6318 6617 5907 6790 6081 6962 6321 6506 6378 7076 6377 6733 6317 6616 5906 6389 5730 6506 6378 6619 5909 6505 6260 6449 5731 6676 6142 5372 4631 6737 5849 6214 5851 6736 6265 7023 6488 6737 5849 6851 6489 7023 6488 7022 5850 6737 5849 7136 6435 7023 6488 7025 6325 7023 6488 7136 6435 7022 5850 7025 6325 7081 6490 7136 6435 7081 6490 7137 6436 7136 6435 4869 6437 7137 6436 4871 6491 4871 6491 7137 6436 7081 6490 7083 6438 4869 6437 7186 6492 7186 6492 4869 6437 4871 6491 7084 6382 5048 4359 7138 6439 7085 6383 7084 6382 7139 6440 7186 6492 7187 6493 7138 6439 7140 6442 7085 6383 7139 6440 7187 6493 7188 6494 7139 6440 7141 6443 7086 6385 7140 6442 7139 6440 7188 6494 7140 6442 7140 6442 7189 6495 7141 6443 7190 6496 7191 6497 7142 6444 7191 6497 7192 6498 7143 6445 7190 6496 7142 6444 7141 6443 7192 6498 7193 6499 7144 6446 7191 6497 7143 6445 7142 6444 7193 6499 7194 6500 7145 6447 7192 6498 7144 6446 7143 6445 7194 6500 7195 6501 7145 6447 7193 6499 7145 6447 7144 6446 7195 6501 7196 6502 7146 6448 7196 6502 7197 6503 7147 6449 7195 6501 7146 6448 7145 6447 7197 6503 7198 6504 7148 6450 7196 6502 7147 6449 7146 6448 7197 6503 7148 6450 7147 6449 7199 6505 7149 6451 7198 6504 7198 6504 7149 6451 7148 6450 7200 6506 7150 6452 7199 6505 7201 6507 7151 6453 7200 6506 7199 6505 7150 6452 7149 6451 7202 6508 7152 6454 7201 6507 7200 6506 7151 6453 7150 6452 7203 6509 7153 6455 7202 6508 7201 6507 7152 6454 7151 6453 7204 6510 7155 6457 7203 6509 7205 6511 7156 6458 7204 6510 7202 6508 7153 6455 7152 6454 7206 6512 7157 6459 7205 6511 7207 6513 7158 6460 7206 6512 7203 6509 7154 6456 7153 6455 7208 6514 7159 6461 7207 6513 7203 6509 7155 6457 7154 6456 7209 6515 7160 6462 7208 6514 7204 6510 7156 6458 7155 6457 7210 6516 7161 6463 7209 6515 7205 6511 7157 6459 7156 6458 7211 6517 7162 6464 7210 6516 7206 6512 7158 6460 7157 6459 7212 6518 7163 6465 7211 6517 7207 6513 7159 6461 7158 6460 7213 6519 7164 6466 7212 6518 7208 6514 7160 6462 7159 6461 7214 6520 7165 6467 7213 6519 7209 6515 7161 6463 7160 6462 7215 6521 7166 6468 7214 6520 7210 6516 7162 6464 7161 6463 7211 6517 7163 6465 7162 6464 7216 6522 7166 6468 7215 6521 7212 6518 7164 6466 7163 6465 7213 6519 7165 6467 7164 6466 7165 6467 7214 6520 7166 6468 7168 6470 7114 6412 7167 6469 7169 6471 7115 6413 7168 6470 7170 6472 7116 6414 7169 6471 7166 6468 7216 6522 7167 6469 7171 6473 7117 6415 7170 6472 7172 6474 7118 6416 7171 6473 7167 6469 7216 6522 7168 6470 7173 6475 7119 6417 7172 6474 7168 6470 7217 6523 7169 6471 7174 6476 7120 6418 7173 6475 7169 6471 7218 6524 7170 6472 7175 6477 7121 6419 7174 6476 7170 6472 7219 6525 7171 6473 7176 6478 7122 6420 7175 6477 7171 6473 7220 6526 7172 6474 7123 6421 7177 6479 7124 6422 7172 6474 7221 6527 7173 6475 7125 6423 7124 6422 7178 6480 7173 6475 7222 6528 7174 6476 7127 6425 7125 6423 7180 6482 7174 6476 7223 6529 7175 6477 7128 6427 7127 6425 7181 6484 7175 6477 7224 6530 7176 6478 7130 6429 7128 6427 7182 6486 7176 6478 7225 6531 7177 6479 7132 6431 7130 6429 7183 6487 7177 6479 7226 6532 7178 6480 7227 6533 5301 4573 5303 6534 7228 6535 7178 6480 7226 6532 5310 6483 7179 6481 7229 6536 7180 6482 7228 6535 7230 6537 7232 6538 7181 6484 7230 6537 7232 6538 7233 6539 7182 6486 7131 6430 7129 6428 7234 6540 7233 6539 7235 6541 7183 6487 7179 6481 7235 6541 7229 6536 5308 4577 5309 6426 5310 6483 7076 6377 6506 6378 6849 6263 7129 6428 6955 6255 7071 6485 6619 5909 6506 6378 6962 6321 6960 6261 7129 6428 7131 6430 6961 6262 7131 6430 7075 6376 7076 6377 7075 6376 7185 6542 7016 6318 6733 6317 6617 5907 6449 5731 6616 5906 6676 6142 7023 6488 6852 6543 7239 6326 7239 6326 7025 6325 7023 6488 7432 6544 5013 6545 7242 6546 7081 6490 7025 6325 7024 6324 4871 6491 7081 6490 7082 4243 7082 4243 7081 6490 7024 6324 4871 6491 4870 4245 7186 6492 7082 4243 4870 4245 4871 6491 7138 6439 7083 6438 7186 6492 4870 4245 4876 6547 7186 6492 7139 6440 7138 6439 7187 6493 4876 6547 7244 6548 7187 6493 7189 6495 7140 6442 7188 6494 7190 6496 7141 6443 7189 6495 7188 6494 7245 6549 7189 6495 7189 6495 7245 6549 7190 6496 7191 6497 7246 6550 7247 6551 7246 6550 7191 6497 7190 6496 7192 6498 7247 6551 7248 6552 7248 6552 7249 6553 7193 6499 7247 6551 7192 6498 7191 6497 7249 6553 7250 6554 7193 6499 7248 6552 7193 6499 7192 6498 7250 6554 7251 6555 7194 6500 7251 6555 7252 6556 7195 6501 7250 6554 7194 6500 7193 6499 7252 6556 7253 6557 7196 6502 7251 6555 7195 6501 7194 6500 7253 6557 7254 6558 7197 6503 7252 6556 7196 6502 7195 6501 7253 6557 7197 6503 7196 6502 7254 6558 7255 6559 7199 6505 7254 6558 7198 6504 7197 6503 7255 6559 7256 6560 7200 6506 7254 6558 7199 6505 7198 6504 7256 6560 7257 6561 7201 6507 7257 6561 7258 6562 7202 6508 7255 6559 7200 6506 7199 6505 7258 6562 7259 6563 7203 6509 7256 6560 7201 6507 7200 6506 7259 6563 7260 6564 7204 6510 7257 6561 7202 6508 7201 6507 7260 6564 7261 6565 7205 6511 7261 6565 7262 6566 7206 6512 7258 6562 7203 6509 7202 6508 7262 6566 7263 6567 7207 6513 7263 6567 7264 6568 7208 6514 7259 6563 7204 6510 7203 6509 7264 6568 7265 6569 7209 6515 7260 6564 7205 6511 7204 6510 7265 6569 7266 6570 7210 6516 7261 6565 7206 6512 7205 6511 7266 6570 7267 6571 7211 6517 7262 6566 7207 6513 7206 6512 7267 6571 7268 6572 7212 6518 7263 6567 7208 6514 7207 6513 7268 6572 7269 6573 7213 6519 7264 6568 7209 6515 7208 6514 7269 6573 7270 6574 7214 6520 7265 6569 7210 6516 7209 6515 7270 6574 7271 6575 7215 6521 7266 6570 7211 6517 7210 6516 7267 6571 7212 6518 7211 6517 7271 6575 7272 6576 7216 6522 7268 6572 7213 6519 7212 6518 7269 6573 7214 6520 7213 6519 7214 6520 7270 6574 7215 6521 7217 6523 7168 6470 7216 6522 7218 6524 7169 6471 7217 6523 7271 6575 7216 6522 7215 6521 7219 6525 7170 6472 7218 6524 7220 6526 7171 6473 7219 6525 7221 6527 7172 6474 7220 6526 7216 6522 7272 6576 7217 6523 7222 6528 7173 6475 7221 6527 7217 6523 7273 6577 7218 6524 7223 6529 7174 6476 7222 6528 7218 6524 7274 6578 7219 6525 7224 6530 7175 6477 7223 6529 7219 6525 7275 6579 7220 6526 7225 6531 7176 6478 7224 6530 7220 6526 7276 6580 7221 6527 7226 6532 7177 6479 7225 6531 7221 6527 7277 6581 7222 6528 7178 6480 7228 6535 7180 6482 7222 6528 7278 6582 7223 6529 7181 6484 7180 6482 7230 6537 7223 6529 7279 6583 7224 6530 7182 6486 7181 6484 7232 6538 7224 6530 7280 6584 7225 6531 7183 6487 7182 6486 7233 6539 7225 6531 7281 6585 7226 6532 7179 6481 7183 6487 7235 6541 7226 6532 7282 6586 7228 6535 7228 6535 7282 6586 7283 6587 5310 6483 7229 6536 7284 6588 7285 6589 7230 6537 7283 6587 7231 6590 5308 4577 5310 6483 7285 6589 7286 6591 7232 6538 7233 6539 7286 6591 7287 6592 5307 4576 7129 6428 7071 6485 7284 6588 7229 6536 7235 6541 5310 6483 7284 6588 7231 6590 7017 6319 7185 6542 7288 6593 7071 6485 5308 4577 5307 4576 7185 6542 6962 6321 7076 6377 7291 6594 7021 6594 7134 6594 6619 5909 6962 6321 6789 6080 7293 6595 7294 6596 7020 6322 6852 6543 7023 6488 6851 6489 7239 6326 6852 6543 7077 6597 7077 6597 7296 6598 7239 6326 7296 6598 7297 4244 7024 6324 7297 4244 7082 4243 7024 6324 7024 6324 7239 6326 7296 6598 4870 4245 4872 4247 4876 6547 4872 4247 4870 4245 7297 4244 7187 6493 7186 6492 4876 6547 7188 6494 7187 6493 7244 6548 4872 4247 7243 6599 4876 6547 7245 6549 7188 6494 7244 6548 7243 6599 7298 6600 7244 6548 7244 6548 7298 6600 7245 6549 7246 6550 7190 6496 7245 6549 7245 6549 7300 6601 7246 6550 7301 6602 7247 6551 7300 6601 7302 6603 7248 6552 7301 6602 7247 6551 7246 6550 7300 6601 7301 6602 7248 6552 7247 6551 7249 6553 7302 6603 7303 6604 7302 6603 7249 6553 7248 6552 7250 6554 7303 6604 7304 6605 7303 6604 7250 6554 7249 6553 7252 6556 7304 6605 7305 6606 7304 6605 7251 6555 7250 6554 7253 6557 7305 6606 7306 6607 7304 6605 7252 6556 7251 6555 7305 6606 7253 6557 7252 6556 7254 6558 7306 6607 7307 6608 7306 6607 7254 6558 7253 6557 7255 6559 7307 6608 7308 6609 7307 6608 7255 6559 7254 6558 7256 6560 7308 6609 7309 6610 7257 6561 7309 6610 7310 6611 7308 6609 7256 6560 7255 6559 7258 6562 7310 6611 7311 6612 7309 6610 7257 6561 7256 6560 7259 6563 7311 6612 7312 6613 7310 6611 7258 6562 7257 6561 7260 6564 7312 6613 7313 6614 7261 6565 7313 6614 7314 6615 7311 6612 7259 6563 7258 6562 7262 6566 7314 6615 7315 6616 7263 6567 7315 6616 7316 6617 7312 6613 7260 6564 7259 6563 7264 6568 7316 6617 7317 6618 7313 6614 7261 6565 7260 6564 7318 6619 7319 6620 7266 6570 7314 6615 7262 6566 7261 6565 7319 6620 7320 6621 7267 6571 7315 6616 7263 6567 7262 6566 7320 6621 7321 6622 7268 6572 7316 6617 7264 6568 7263 6567 7321 6622 7322 6623 7269 6573 7317 6618 7265 6569 7264 6568 7322 6623 7323 6624 7270 6574 7318 6619 7266 6570 7265 6569 7323 6624 7324 6625 7271 6575 7319 6620 7267 6571 7266 6570 7320 6621 7268 6572 7267 6571 7324 6625 7325 6626 7272 6576 7321 6622 7269 6573 7268 6572 7322 6623 7270 6574 7269 6573 7270 6574 7323 6624 7271 6575 7273 6577 7217 6523 7272 6576 7274 6578 7218 6524 7273 6577 7324 6625 7272 6576 7271 6575 7275 6579 7219 6525 7274 6578 7276 6580 7220 6526 7275 6579 7277 6581 7221 6527 7276 6580 7272 6576 7325 6626 7273 6577 7278 6582 7222 6528 7277 6581 7273 6577 7326 6627 7274 6578 7279 6583 7223 6529 7278 6582 7274 6578 7327 6628 7275 6579 7280 6584 7224 6530 7279 6583 7275 6579 7328 6629 7276 6580 7281 6585 7225 6531 7280 6584 7276 6580 7329 6630 7277 6581 7282 6586 7226 6532 7281 6585 7277 6581 7330 6631 7278 6582 7228 6535 7283 6587 7230 6537 7278 6582 7331 6632 7279 6583 7232 6538 7230 6537 7285 6589 7279 6583 7332 6633 7280 6584 7233 6539 7232 6538 7286 6591 7280 6584 7333 6634 7281 6585 7235 6541 7233 6539 7287 6592 7281 6585 7334 6635 7282 6586 7335 6636 7283 6587 7282 6586 7227 6533 7284 6588 7235 6541 7335 6636 7336 6637 7283 6587 7336 6637 7337 6638 7285 6589 7338 6639 5305 4575 7339 6640 7227 6533 7235 6541 7287 6592 7340 6641 7075 6376 7131 6430 7184 6642 7185 6542 7075 6376 5305 4575 5308 4577 7231 6590 7234 6540 7129 6428 5307 4576 7018 6320 6789 6080 6962 6321 7340 6641 7131 6430 7234 6540 7184 6642 7075 6376 7340 6641 7288 6593 7289 6643 7341 6644 7185 6542 7184 6642 7288 6593 7133 6432 7016 6318 6790 6081 7185 6542 7017 6319 6962 6321 7078 6645 7238 6646 7077 6597 7506 6647 7344 6647 7471 6647 7296 6598 7077 6597 7238 6646 7238 6646 7345 6648 7296 6598 7345 6648 7346 4246 7297 4244 7297 4244 7296 6598 7345 6648 4872 4247 4879 6649 7243 6599 4872 4247 7346 4246 7347 6650 7244 6548 4876 6547 7243 6599 4879 6649 4872 4247 7347 6650 7299 6651 7245 6549 7298 6600 7298 6600 7348 6652 7299 6651 7300 6601 7245 6549 7299 6651 7299 6651 7350 6653 7300 6601 7352 6654 7302 6603 7351 6655 7351 6655 7301 6602 7300 6601 7353 6656 7303 6604 7352 6654 7351 6655 7302 6603 7301 6602 7354 6657 7304 6605 7353 6656 7352 6654 7303 6604 7302 6603 7355 6658 7304 6605 7354 6657 7356 6659 7305 6606 7355 6658 7353 6656 7304 6605 7303 6604 7357 6660 7306 6607 7356 6659 7355 6658 7305 6606 7304 6605 7358 6661 7307 6608 7357 6660 7356 6659 7306 6607 7305 6606 7357 6660 7307 6608 7306 6607 7359 6662 7308 6609 7358 6661 7360 6663 7309 6610 7359 6662 7358 6661 7308 6609 7307 6608 7361 6664 7310 6611 7360 6663 7359 6662 7309 6610 7308 6609 7362 6665 7311 6612 7361 6664 7360 6663 7310 6611 7309 6610 7363 6666 7312 6613 7362 6665 7361 6664 7311 6612 7310 6611 7364 6667 7314 6615 7363 6666 7365 6668 7315 6616 7364 6667 7362 6665 7312 6613 7311 6612 7366 6669 7316 6617 7365 6668 7367 6670 7317 6618 7366 6669 7363 6666 7313 6614 7312 6613 7318 6619 7265 6569 7317 6618 7313 6614 7363 6666 7314 6615 7318 6619 7367 6670 7368 6671 7314 6615 7364 6667 7315 6616 7319 6620 7368 6671 7369 6672 7315 6616 7365 6668 7316 6617 7320 6621 7369 6672 7370 6673 7316 6617 7366 6669 7317 6618 7321 6622 7370 6673 7371 6674 7317 6618 7367 6670 7318 6619 7322 6623 7371 6674 7372 6675 7318 6619 7368 6671 7319 6620 7323 6624 7372 6675 7373 6676 7319 6620 7369 6672 7320 6621 7324 6625 7373 6676 7374 6677 7320 6621 7370 6673 7321 6622 7321 6622 7371 6674 7322 6623 7322 6623 7372 6675 7323 6624 7324 6625 7323 6624 7373 6676 7326 6627 7273 6577 7325 6626 7327 6628 7274 6578 7326 6627 7324 6625 7374 6677 7325 6626 7328 6629 7275 6579 7327 6628 7329 6630 7276 6580 7328 6629 7330 6631 7277 6581 7329 6630 7325 6626 7375 6678 7326 6627 7331 6632 7278 6582 7330 6631 7326 6627 7376 6679 7327 6628 7332 6633 7279 6583 7331 6632 7327 6628 7377 6680 7328 6629 7333 6634 7280 6584 7332 6633 7328 6629 7378 6681 7329 6630 7334 6635 7281 6585 7333 6634 7329 6630 7379 6682 7330 6631 7335 6636 7282 6586 7334 6635 7330 6631 7380 6683 7331 6632 7283 6587 7336 6637 7285 6589 7331 6632 7381 6684 7332 6633 7286 6591 7285 6589 7337 6638 7332 6633 7382 6685 7333 6634 7333 6634 7383 6686 7334 6635 7384 6687 7287 6592 7286 6591 7385 6688 7227 6533 7287 6592 7336 6637 7335 6636 7386 6689 5303 6534 7231 6590 7284 6588 5302 6690 5305 4575 7231 6590 7337 6638 7384 6687 7286 6591 7385 6688 7287 6592 7384 6687 7338 6639 7234 6540 5307 4576 5303 6534 7284 6588 7227 6533 5302 6690 7231 6590 5303 6534 7134 6691 7288 6593 7341 6644 5307 4576 5305 4575 7338 6639 7134 6691 6906 6201 7018 6320 6906 6201 6790 6081 6789 6080 6907 6202 7133 6432 6790 6081 7290 6692 6850 6143 7133 6432 7292 6693 7135 6434 7388 6694 7133 6432 6850 6143 6616 5906 6906 6201 6789 6080 7018 6320 6676 6142 7019 6433 5372 4631 7295 6695 7389 6696 7238 6646 7345 6648 7238 6646 7389 6696 7345 6648 7389 6696 7242 6546 7346 4246 7345 6648 7242 6546 5013 6545 7347 6650 7346 4246 7242 6546 5013 6545 7346 4246 7391 6697 4879 6649 7347 6650 7347 6650 5013 6545 7391 6697 7298 6600 7243 6599 4879 6649 4879 6649 7391 6697 4880 6698 7348 6652 7298 6600 4879 6649 7349 6699 7299 6651 7348 6652 4879 6649 7392 6700 7348 6652 7350 6653 7299 6651 7349 6699 7348 6652 7392 6700 7349 6699 7349 6699 7393 6701 7350 6653 7351 6655 7300 6601 7350 6653 7350 6653 7394 6702 7351 6655 7395 6703 7396 6704 7352 6654 7396 6704 7397 6705 7353 6656 7395 6703 7352 6654 7351 6655 7397 6705 7398 6706 7354 6657 7396 6704 7353 6656 7352 6654 7398 6706 7399 6707 7355 6658 7399 6707 7400 6708 7356 6659 7397 6705 7354 6657 7353 6656 7400 6708 7401 6709 7357 6660 7398 6706 7355 6658 7354 6657 7399 6707 7356 6659 7355 6658 7401 6709 7402 6710 7358 6661 7400 6708 7357 6660 7356 6659 7401 6709 7358 6661 7357 6660 7402 6710 7403 6711 7359 6662 7403 6711 7404 6712 7360 6663 7404 6712 7405 6713 7361 6664 7402 6710 7359 6662 7358 6661 7405 6713 7406 6714 7362 6665 7403 6711 7360 6663 7359 6662 7406 6714 7407 6715 7363 6666 7404 6712 7361 6664 7360 6663 7407 6715 7408 6716 7364 6667 7405 6713 7362 6665 7361 6664 7408 6716 7409 6717 7365 6668 7409 6717 7410 6718 7366 6669 7406 6714 7363 6666 7362 6665 7410 6718 7411 6719 7367 6670 7411 6719 7412 6720 7368 6671 7407 6715 7364 6667 7363 6666 7412 6720 7413 6721 7369 6672 7408 6716 7365 6668 7364 6667 7413 6721 7414 6722 7370 6673 7409 6717 7366 6669 7365 6668 7414 6722 7415 6723 7371 6674 7410 6718 7367 6670 7366 6669 7415 6723 7416 6724 7372 6675 7411 6719 7368 6671 7367 6670 7416 6724 7417 6725 7373 6676 7412 6720 7369 6672 7368 6671 7417 6725 7418 6726 7374 6677 7413 6721 7370 6673 7369 6672 7414 6722 7371 6674 7370 6673 7415 6723 7372 6675 7371 6674 7375 6678 7325 6626 7374 6677 7372 6675 7416 6724 7373 6676 7374 6677 7373 6676 7417 6725 7376 6679 7326 6627 7375 6678 7377 6680 7327 6628 7376 6679 7378 6681 7328 6629 7377 6680 7374 6677 7418 6726 7375 6678 7379 6682 7329 6630 7378 6681 7380 6683 7330 6631 7379 6682 7375 6678 7419 6727 7376 6679 7381 6684 7331 6632 7380 6683 7382 6685 7332 6633 7381 6684 7383 6686 7333 6634 7382 6685 7386 6689 7335 6636 7334 6635 7380 6683 7420 6728 7381 6684 7421 6729 7384 6687 7337 6638 7386 6689 7334 6635 7422 6730 7423 6731 5299 4574 7424 6732 7425 6733 7336 6637 7386 6689 7337 6638 7425 6733 7421 6729 7426 6734 7427 6735 7338 6639 5301 4573 7227 6533 7385 6688 7427 6735 7340 6641 7234 6540 7387 6736 7184 6642 7340 6641 7289 6643 7288 6593 7184 6642 7339 6640 5305 4575 5302 6690 7134 6691 7018 6320 7017 6319 7427 6735 7234 6540 7338 6639 7387 6736 7340 6641 7427 6735 7289 6643 7184 6642 7387 6736 7341 6644 7428 6737 7429 6738 7135 6434 7290 6692 7430 6739 7290 6692 7133 6432 6907 6202 7017 6319 7288 6593 7134 6691 6676 6142 6850 6143 7019 6433 7295 6695 7238 6646 7078 6645 7389 6696 7343 6740 7241 6741 7241 6741 7432 6544 7242 6546 7241 6741 7242 6546 7389 6696 5013 6545 5016 6742 7391 6697 7432 6544 5016 6742 5013 6545 7391 6697 5043 6743 4880 6698 5016 6742 5043 6743 7391 6697 7392 6700 4879 6649 4880 6698 5043 6743 7433 6744 4880 6698 7393 6701 7349 6699 7392 6700 7394 6702 7350 6653 7393 6701 7392 6700 7434 6745 7393 6701 7393 6701 7435 6746 7394 6702 7395 6703 7351 6655 7394 6702 7394 6702 7435 6746 7395 6703 7396 6704 7395 6703 7438 6747 7437 6748 7438 6747 7395 6703 7397 6705 7396 6704 7439 6749 7438 6747 7439 6749 7396 6704 7398 6706 7397 6705 7440 6750 7399 6707 7398 6706 7440 6750 7439 6749 7440 6750 7397 6705 7400 6708 7399 6707 7441 6751 7401 6709 7400 6708 7442 6752 7440 6750 7441 6751 7399 6707 7441 6751 7442 6752 7400 6708 7402 6710 7401 6709 7444 6753 7442 6752 7443 6754 7401 6709 7443 6754 7444 6753 7401 6709 7403 6711 7402 6710 7445 6755 7444 6753 7445 6755 7402 6710 7404 6712 7403 6711 7446 6756 7405 6713 7404 6712 7447 6757 7445 6755 7446 6756 7403 6711 7406 6714 7405 6713 7448 6758 7446 6756 7447 6757 7404 6712 7407 6715 7406 6714 7449 6759 7447 6757 7448 6758 7405 6713 7408 6716 7407 6715 7451 6760 7448 6758 7449 6759 7406 6714 7449 6759 7450 6761 7407 6715 7411 6719 7410 6718 7452 6762 7450 6761 7451 6760 7407 6715 7412 6720 7411 6719 7453 6763 7409 6717 7452 6762 7410 6718 7452 6762 7453 6763 7411 6719 7416 6724 7415 6723 7454 6764 7418 6726 7417 6725 7455 6765 7414 6722 7454 6764 7415 6723 7419 6727 7375 6678 7418 6726 7417 6725 7416 6724 7455 6765 7456 6766 7418 6726 7455 6765 7419 6727 7456 6766 7457 6767 7420 6728 7380 6683 7379 6682 7376 6679 7457 6767 7458 6768 7376 6679 7458 6768 7377 6680 7377 6680 7459 6769 7378 6681 7378 6681 7460 6770 7379 6682 7422 6730 7334 6635 7383 6686 7379 6682 7461 6771 7420 6728 7336 6637 7425 6733 7337 6638 7381 6684 7462 6772 7382 6685 7463 6773 7383 6686 7382 6685 7422 6730 7383 6686 7464 6774 7465 6775 7385 6688 7384 6687 5300 6776 5301 4573 7385 6688 7386 6689 7466 6777 7425 6733 5304 4572 5302 6690 5303 6534 5306 6778 7339 6640 5302 6690 7421 6729 7465 6775 7384 6687 7426 6734 7467 6779 7468 6780 5300 6776 7385 6688 7465 6775 5304 4572 5303 6534 5301 4573 5306 6778 5302 6690 5304 4572 7426 6734 7338 6639 7339 6640 7021 6323 6907 6202 6906 6201 7020 6322 7290 6692 6907 6202 7293 6595 7470 6781 7294 6596 7134 6691 7021 6323 6906 6201 7295 6695 7343 6740 7389 6696 7431 6782 7241 6782 7343 6782 7241 6783 7431 6783 7240 6783 7240 6784 7473 6784 7432 6784 7432 6785 7241 6785 7240 6785 5016 6786 7474 6786 5043 6786 5016 6787 7473 6787 7474 6787 7392 6700 4880 6698 7433 6744 5044 6788 5043 6788 7474 6788 7434 6745 7392 6700 7433 6744 7433 6789 7475 6789 7434 6789 7435 6746 7393 6701 7434 6745 7434 6790 7476 6790 7435 6790 7437 6748 7395 6703 7435 6746 7437 6791 7436 6791 7477 6791 7437 6792 7477 6792 7438 6792 7438 6793 7478 6793 7439 6793 7438 6794 7477 6794 7478 6794 7439 6795 7479 6795 7440 6795 7439 6796 7478 6796 7479 6796 7440 6797 7480 6797 7441 6797 7440 6798 7479 6798 7480 6798 7441 6799 7481 6799 7442 6799 7442 6800 7482 6800 7443 6800 7441 6801 7480 6801 7481 6801 7443 6802 7483 6802 7444 6802 7442 6803 7481 6803 7482 6803 7443 6804 7482 6804 7483 6804 7444 6805 7484 6805 7445 6805 7444 6806 7483 6806 7484 6806 7445 6807 7485 6807 7446 6807 7446 6808 7486 6808 7447 6808 7445 6755 7484 6809 7485 6810 7447 6811 7487 6811 7448 6811 7446 6756 7485 6810 7486 6812 7448 6813 7488 6813 7449 6813 7449 6814 7489 6814 7450 6814 7447 6757 7486 6812 7487 6815 7448 6758 7487 6815 7488 6816 7408 6817 7490 6817 7409 6817 7449 6759 7488 6816 7489 6818 7409 6717 7491 6819 7452 6762 7408 6716 7451 6760 7490 6820 7412 6720 7492 6821 7413 6721 7409 6717 7490 6820 7491 6819 7413 6721 7493 6822 7414 6722 7414 6722 7494 6823 7454 6764 7412 6720 7453 6763 7492 6821 7416 6724 7495 6824 7455 6765 7492 6821 7493 6822 7413 6721 7493 6822 7494 6823 7414 6722 7454 6764 7495 6824 7416 6724 7456 6766 7419 6727 7418 6726 7496 6825 7456 6825 7455 6825 7457 6767 7376 6679 7419 6727 7377 6680 7458 6768 7459 6769 7460 6770 7378 6681 7459 6769 7457 6826 7496 6826 7497 6826 7461 6771 7379 6682 7460 6770 7462 6772 7381 6684 7420 6728 7463 6773 7382 6685 7462 6772 7464 6774 7383 6686 7463 6773 7466 6777 7386 6689 7422 6730 7420 6728 7498 6827 7462 6772 7500 6828 7421 6729 7425 6733 7501 6829 7465 6775 7421 6729 7499 6830 7466 6777 7422 6730 5293 6831 5300 6776 7465 6775 5304 4572 7423 6731 5306 6778 7466 6777 7500 6828 7425 6733 5306 6778 7502 6832 7503 6833 7501 6829 7421 6729 7500 6828 7503 6833 7426 6734 7339 6640 5299 4574 5301 4573 5300 6776 7468 6780 7387 6736 7427 6735 7469 6834 7289 6643 7387 6736 7428 6737 7341 6644 7289 6643 7503 6833 7339 6640 5306 6778 7291 6835 7342 6835 7021 6835 7468 6780 7427 6735 7426 6734 7469 6834 7387 6736 7468 6780 7428 6737 7289 6643 7469 6834 7504 6836 7429 6738 7505 6837 7291 6838 7134 6691 7341 6644 7471 6839 7344 6839 7431 6839 7240 6840 7431 6840 7344 6840 7344 6841 5015 6841 7473 6841 7473 6842 7240 6842 7344 6842 7474 6843 7473 6843 5015 6843 5044 6844 7474 6844 7507 6844 7474 6845 5015 6845 7507 6845 7508 6846 7558 6846 7509 6846 7433 6847 5043 6847 5044 6847 7475 6848 7433 6848 5044 6848 5019 6849 5044 6849 7507 6849 7476 6850 7434 6850 7475 6850 5044 6851 5019 6851 7475 6851 7475 6852 7510 6852 7476 6852 7436 6853 7435 6853 7476 6853 7436 6854 7437 6854 7435 6854 7511 6855 7512 6855 7436 6855 7513 6856 7478 6856 7477 6856 7477 6857 7512 6857 7513 6857 7514 6858 7479 6858 7478 6858 7478 6859 7513 6859 7514 6859 7515 6860 7480 6860 7479 6860 7479 6861 7514 6861 7515 6861 7516 6862 7481 6862 7480 6862 7480 6863 7515 6863 7516 6863 7517 6864 7482 6864 7481 6864 7481 6865 7516 6865 7517 6865 7518 6866 7483 6866 7482 6866 7482 6867 7517 6867 7518 6867 7483 6868 7518 6868 7519 6868 7520 6869 7484 6869 7483 6869 7483 6870 7519 6870 7520 6870 7521 6871 7485 6871 7484 6871 7484 6872 7520 6872 7521 6872 7522 6873 7486 6873 7485 6873 7523 6874 7487 6874 7486 6874 7485 6875 7521 6875 7522 6875 7524 6876 7488 6816 7487 6815 7486 6877 7522 6877 7523 6877 7525 6878 7489 6818 7488 6816 7451 6760 7450 6761 7526 6879 7487 6815 7523 6880 7524 6876 7490 6820 7451 6760 7527 6881 7488 6816 7524 6876 7525 6878 7450 6761 7489 6818 7526 6879 7453 6763 7452 6762 7528 6882 7451 6760 7526 6879 7527 6881 7492 6821 7453 6763 7529 6883 7452 6762 7491 6819 7528 6882 7453 6763 7528 6882 7529 6883 7454 6764 7530 6884 7495 6824 7455 6885 7531 6885 7496 6885 7454 6764 7494 6823 7530 6884 7496 6886 7457 6886 7456 6886 7531 6887 7455 6765 7495 6824 7531 6887 7532 6888 7496 6889 7497 6890 7458 6768 7457 6767 7497 6891 7532 6891 7533 6891 7498 6827 7420 6728 7461 6771 7458 6768 7533 6892 7534 6893 7459 6769 7534 6893 7535 6894 7460 6770 7535 6894 7536 6895 7461 6771 7536 6895 7537 6896 7499 6830 7422 6730 7464 6774 7461 6771 7537 6896 7498 6827 7499 6830 7540 6897 7466 6777 7463 6773 7462 6772 7541 6898 7463 6773 7542 6899 7464 6774 7543 6900 7499 6830 7464 6774 5296 6901 5299 4574 5300 6776 7540 6897 7500 6828 7466 6777 7502 6832 7545 6902 7546 6903 5293 6831 7465 6775 7501 6829 7467 6779 7547 6904 7548 6905 5296 6901 5300 6776 5293 6831 7423 6731 5304 4572 5299 4574 7428 6737 7505 6837 7429 6738 7502 6832 5306 6778 7423 6731 7429 6738 7291 6838 7341 6644 7503 6833 7467 6779 7426 6734 7290 6692 7135 6434 6850 6143 7292 6693 7552 6906 7553 6907 7506 6908 7554 6908 7344 6908 7344 6909 7554 6909 7390 6909 5015 6910 7344 6910 7390 6910 7507 6911 5015 6911 5014 6911 7390 6912 5014 6912 5015 6912 5019 6913 7507 6913 7558 6913 7507 6914 5014 6914 7558 6914 7510 6915 7475 6915 5019 6915 5019 6916 7508 6916 7510 6916 7511 6917 7476 6917 7510 6917 7511 6918 7436 6918 7476 6918 7510 6919 7559 6919 7511 6919 7511 6920 7559 6920 7560 6920 7512 6921 7477 6921 7436 6921 7560 6922 7561 6922 7512 6922 7512 6923 7561 6923 7513 6923 7513 6924 7561 6924 7514 6924 7514 6925 7562 6925 7515 6925 7561 6926 7562 6926 7514 6926 7515 6927 7563 6927 7516 6927 7562 6928 7563 6928 7515 6928 7519 6929 7564 6929 7520 6929 7518 6930 7564 6930 7519 6930 7520 6931 7566 6931 7521 6931 7564 6932 7565 6932 7520 6932 7565 6933 7566 6933 7520 6933 7521 6934 7567 6934 7522 6934 7522 6935 7568 6935 7523 6935 7566 6936 7567 6936 7521 6936 7523 6937 7570 6937 7524 6937 7567 6938 7568 6938 7522 6938 7524 6939 7571 6939 7525 6939 7568 6940 7569 6940 7523 6940 7523 6941 7569 6941 7570 6941 7572 6942 7526 6879 7489 6818 7524 6943 7570 6943 7571 6943 7489 6818 7525 6878 7572 6942 7573 6944 7491 6819 7490 6820 7574 6945 7528 6882 7491 6819 7490 6820 7527 6881 7573 6944 7491 6819 7573 6944 7574 6945 7575 6946 7493 6822 7492 6821 7576 6947 7494 6823 7493 6822 7577 6948 7530 6884 7494 6823 7492 6821 7529 6883 7575 6946 7493 6822 7575 6946 7576 6947 7578 6949 7531 6887 7495 6824 7494 6823 7576 6947 7577 6948 7495 6824 7530 6884 7578 6949 7532 6950 7497 6950 7496 6950 7531 6887 7579 6951 7532 6888 7533 6892 7458 6768 7497 6890 7534 6893 7459 6769 7458 6768 7535 6894 7460 6770 7459 6769 7536 6895 7461 6771 7460 6770 7541 6898 7462 6772 7498 6827 7542 6899 7463 6773 7541 6898 7543 6900 7464 6774 7542 6899 7499 6830 7543 6900 7539 6952 7541 6898 7498 6827 7581 6953 7582 6954 7501 6829 7500 6828 5294 4571 5293 6831 7501 6829 7539 6952 7540 6897 7499 6830 7502 6832 7423 6731 7583 6955 7500 6828 7540 6897 7582 6954 7582 6954 5294 4571 7501 6829 7546 6903 7467 6779 7503 6833 5296 6901 7424 6732 5299 4574 7548 6905 7469 6834 7468 6780 7549 6956 7428 6737 7469 6834 7546 6903 7503 6833 7502 6832 7548 6905 7468 6780 7467 6779 7549 6956 7469 6834 7548 6905 7430 6739 7020 6322 7294 6596 7505 6837 7428 6737 7549 6956 7430 6739 7290 6692 7020 6322 7342 6957 7291 6838 7429 6738 5372 4631 7019 6433 7292 6693 7019 6433 7135 6434 7292 6693 7236 6958 7584 6958 7554 6958 7236 6959 7554 6959 7506 6959 7390 6960 7584 6960 7585 6960 7584 6961 7390 6961 7554 6961 7585 6962 5014 6962 7390 6962 5017 6963 5014 6963 7585 6963 7586 6964 7558 6964 5014 6964 7586 6965 5014 6965 5017 6965 7508 6966 5019 6966 7558 6966 7558 6967 7586 6967 7509 6967 7559 6968 7510 6968 7508 6968 7508 6969 7587 6969 7559 6969 7560 6970 7512 6970 7511 6970 7560 6971 7588 6971 7589 6971 7589 6972 7590 6972 7561 6972 7561 6973 7590 6973 7562 6973 7562 6974 7592 6974 7563 6974 7590 6975 7591 6975 7562 6975 7591 6976 7592 6976 7562 6976 7563 6977 7593 6977 7516 6977 7516 6978 7594 6978 7517 6978 7563 6979 7592 6979 7593 6979 7517 6980 7595 6980 7518 6980 7516 6981 7593 6981 7594 6981 7518 6982 7596 6982 7564 6982 7594 6983 7595 6983 7517 6983 7595 6984 7596 6984 7518 6984 7565 6985 7597 6985 7566 6985 7564 6986 7597 6986 7565 6986 7566 6987 7598 6987 7567 6987 7597 6988 7598 6988 7566 6988 7525 6989 7599 6989 7572 6989 7526 6990 7600 6990 7527 6990 7527 6991 7601 6991 7573 6991 7571 6992 7599 6992 7525 6992 7572 6942 7600 6993 7526 6879 7528 6882 7602 6994 7529 6883 7600 6993 7601 6995 7527 6881 7529 6883 7603 6996 7575 6946 7574 6945 7602 6994 7528 6882 7602 6994 7603 6996 7529 6883 7530 6884 7604 6997 7578 6949 7531 6998 7605 6998 7579 6998 7577 6948 7604 6997 7530 6884 7579 6999 7533 6999 7532 6999 7605 7000 7531 6887 7578 6949 7605 7000 7606 7001 7579 6951 7580 7002 7534 6893 7533 6892 7533 7003 7606 7003 7607 7003 7498 6827 7537 6896 7581 6953 7534 6893 7580 7002 7608 7004 7535 6894 7608 7004 7609 7005 7536 6895 7609 7005 7610 7006 7537 6896 7610 7006 7611 7007 7543 6900 7612 7008 7538 7009 7611 7007 7581 6953 7537 6896 7539 6952 7613 7010 7540 6897 7614 7011 7542 6899 7541 6898 7612 7008 7543 6900 7542 6899 5292 7012 7615 7013 5297 4569 7543 6900 7538 7009 7539 6952 5298 4570 5296 6901 5293 6831 7544 7014 7424 6732 5296 6901 7540 6897 7613 7010 7582 6954 7616 7015 7617 7016 7583 6955 7617 7016 7618 7017 7545 6902 5298 4570 5293 6831 5294 4571 7620 7018 7547 6904 7619 7019 7544 7014 5296 6901 5298 4570 7549 6956 7548 6905 7650 7020 7505 6837 7549 6956 7621 7021 7583 6955 7423 6731 7424 6732 7583 6955 7545 6902 7502 6832 7504 6836 7342 6957 7429 6738 7546 6903 7547 6904 7467 6779 7293 6595 7021 6323 7342 6957 7293 6595 7020 6322 7021 6323 7294 6596 7550 7022 7430 6739 7236 7023 7237 7023 7472 7023 7472 7024 7584 7024 7236 7024 7585 7025 7472 7025 7624 7025 7472 7026 7585 7026 7584 7026 7586 7027 5017 7027 7624 7027 7509 7028 7586 7028 4875 7028 7586 7029 7624 7029 4875 7029 5025 7030 7625 7030 7654 7030 7587 7031 7508 7031 7509 7031 7588 7032 7559 7032 7587 7032 7509 7033 7625 7033 7587 7033 7588 7034 7560 7034 7559 7034 7588 7035 7626 7035 7627 7035 7589 7036 7561 7036 7560 7036 7590 7037 7627 7037 7628 7037 7590 7038 7628 7038 7591 7038 7591 7039 7629 7039 7592 7039 7591 7040 7628 7040 7629 7040 7593 7041 7592 7041 7630 7041 7592 7042 7629 7042 7630 7042 7594 7043 7593 7043 7631 7043 7593 7044 7630 7044 7631 7044 7564 7045 7632 7045 7597 7045 7564 7046 7596 7046 7632 7046 7598 7047 7633 7047 7567 7047 7598 7048 7597 7048 7633 7048 7567 7049 7634 7049 7568 7049 7568 7050 7635 7050 7569 7050 7567 7051 7633 7051 7634 7051 7569 7052 7636 7052 7570 7052 7570 7053 7637 7053 7571 7053 7568 7054 7634 7054 7635 7054 7571 7055 7638 7055 7599 7055 7569 7056 7635 7056 7636 7056 7572 7057 7639 7057 7600 7057 7570 7058 7636 7058 7637 7058 7571 7059 7637 7059 7638 7059 7573 7060 7640 7060 7574 7060 7572 7061 7599 7061 7639 7061 7574 6945 7641 7062 7602 6994 7573 6944 7601 6995 7640 7063 7575 6946 7642 7064 7576 6947 7574 6945 7640 7063 7641 7062 7576 6947 7643 7065 7577 6948 7577 6948 7644 7066 7604 6997 7575 6946 7603 6996 7642 7064 7578 6949 7645 7067 7605 7000 7576 6947 7642 7064 7643 7065 7577 6948 7643 7065 7644 7066 7645 7067 7578 6949 7604 6997 7606 7068 7533 7068 7579 7068 7607 7069 7580 7069 7533 7069 7606 7070 7605 7070 7646 7070 7608 7004 7535 6894 7534 6893 7609 7005 7536 6895 7535 6894 7610 7006 7537 6896 7536 6895 7580 7071 7607 7071 7647 7071 7614 7011 7541 6898 7581 6953 7612 7008 7542 6899 7614 7011 7581 6953 7611 7007 7648 7072 7538 7009 7649 7073 7539 6952 7648 7072 7614 7011 7581 6953 5295 7074 5294 4571 7582 6954 5297 4569 7682 7075 5298 4570 7682 7075 7683 7076 7544 7014 7613 7010 7539 6952 7649 7073 7616 7015 7583 6955 7424 6732 7613 7010 5295 7074 7582 6954 5295 7074 5297 4569 5294 4571 7619 7019 7547 6904 7546 6903 7544 7014 7616 7015 7424 6732 7650 7020 7715 7077 7621 7021 7715 7077 7716 7078 7505 6837 7545 6902 7619 7019 7546 6903 7650 7020 7548 6905 7547 6904 7621 7021 7549 6956 7650 7020 7552 6906 7388 6694 7550 7022 7623 7079 7472 7079 7237 7079 7623 7080 7556 7080 7472 7080 7556 7081 7653 7081 7624 7081 7624 7082 7472 7082 7556 7082 7653 7083 7654 7083 4875 7083 4875 7084 7624 7084 7653 7084 7625 7085 7509 7085 4875 7085 7625 7086 4875 7086 7654 7086 7626 7087 7587 7087 7625 7087 7626 7088 7588 7088 7587 7088 7626 7089 7655 7089 7656 7089 7627 7090 7589 7090 7588 7090 7627 7091 7590 7091 7589 7091 7627 7092 7656 7092 7657 7092 7628 7093 7657 7093 7658 7093 7629 7094 7628 7094 7694 7094 7628 7095 7658 7095 7694 7095 7631 7096 7630 7096 7660 7096 7630 7097 7629 7097 7659 7097 7630 7098 7659 7098 7660 7098 7595 7099 7594 7099 7661 7099 7596 7100 7595 7100 7662 7100 7594 7101 7631 7101 7661 7101 7632 7102 7596 7102 7663 7102 7595 7103 7661 7103 7662 7103 7596 7104 7662 7104 7663 7104 7633 7105 7597 7105 7664 7105 7597 7106 7632 7106 7664 7106 7634 7107 7633 7107 7665 7107 7633 7108 7664 7108 7665 7108 7639 7109 7599 7109 7666 7109 7601 7110 7600 7110 7667 7110 7640 7063 7601 6995 7668 7111 7599 7112 7638 7112 7666 7112 7600 7113 7639 7113 7667 7113 7603 6996 7602 6994 7669 7114 7601 7115 7667 7115 7668 7115 7642 7064 7603 6996 7670 7116 7602 6994 7641 7062 7669 7114 7603 6996 7669 7114 7670 7116 7645 7067 7604 6997 7671 7117 7646 7118 7605 7118 7672 7118 7604 6997 7644 7066 7671 7117 7646 7119 7607 7119 7606 7119 7645 7067 7672 7120 7605 7000 7646 7121 7672 7121 7673 7121 7647 7122 7608 7004 7580 7002 7607 7123 7646 7123 7674 7123 7608 7124 7647 7124 7675 7124 7609 7005 7675 7125 7676 7126 7614 7011 7648 7072 7677 7127 7676 7126 7678 7128 7610 7006 7612 7008 7677 7127 7679 7129 7680 7130 7611 7007 7678 7128 7538 7009 7679 7129 7681 7131 7649 7073 5291 4568 7613 7010 7677 7127 7612 7008 7614 7011 5291 4568 5292 7012 5295 7074 7612 7008 7679 7129 7538 7009 7681 7131 7649 7073 7538 7009 7613 7010 5291 4568 5295 7074 7684 7132 7685 7133 7617 7016 7685 7133 7686 7134 7618 7017 7618 7017 7714 7135 7619 7019 5298 4570 7682 7075 7544 7014 7683 7076 7616 7015 7544 7014 7583 6955 7617 7016 7545 6902 7545 6902 7618 7017 7619 7019 7547 6904 7620 7018 7650 7020 7342 6957 7504 6836 7622 7136 7470 6781 7551 7137 7294 6596 7342 7138 7622 7138 7293 7138 7717 7139 7551 7137 7470 6781 7430 6739 7388 6694 7135 6434 7556 7140 7623 7140 7555 7140 7623 7141 7651 7141 7555 7141 7556 7142 7555 7142 7557 7142 7557 7143 7653 7143 7556 7143 7690 7144 7653 7144 7557 7144 7691 7145 7654 7145 7690 7145 5024 7146 5025 7146 7691 7146 7653 7147 7690 7147 7654 7147 7655 7148 7625 7148 5025 7148 5025 7149 7654 7149 7691 7149 5025 7150 5024 7150 7655 7150 7655 7151 7626 7151 7625 7151 7656 7152 7627 7152 7626 7152 7657 7153 7628 7153 7627 7153 7657 7154 7656 7154 7693 7154 7693 7155 7658 7155 7657 7155 7658 7156 7693 7156 7694 7156 7629 7157 7694 7157 7727 7157 7659 7158 7629 7158 7695 7158 7629 7159 7727 7159 7695 7159 7661 7160 7631 7160 7696 7160 7631 7161 7660 7161 7696 7161 7632 7162 7663 7162 7697 7162 7664 7163 7632 7163 7698 7163 7665 7164 7664 7164 7699 7164 7632 7165 7697 7165 7698 7165 7664 7166 7698 7166 7699 7166 7635 7167 7634 7167 7700 7167 7636 7168 7635 7168 7701 7168 7634 7169 7665 7169 7700 7169 7637 7170 7636 7170 7702 7170 7638 7171 7637 7171 7702 7171 7635 7172 7700 7172 7701 7172 7666 7173 7638 7173 7703 7173 7636 7174 7701 7174 7702 7174 7667 7175 7639 7175 7704 7175 7638 7176 7702 7176 7703 7176 7641 7062 7640 7063 7705 7177 7639 7178 7666 7178 7704 7178 7669 7114 7641 7062 7706 7179 7640 7063 7668 7111 7705 7177 7643 7065 7642 7064 7707 7180 7641 7062 7705 7177 7706 7179 7644 7066 7643 7065 7708 7181 7671 7117 7644 7066 7709 7182 7642 7064 7670 7116 7707 7180 7672 7120 7645 7067 7710 7183 7643 7065 7707 7180 7708 7181 7644 7066 7708 7181 7709 7182 7710 7183 7645 7067 7671 7117 7674 7184 7647 7184 7607 7184 7675 7125 7609 7005 7608 7004 7676 7126 7610 7006 7609 7005 7678 7128 7611 7007 7610 7006 7647 7185 7674 7185 7711 7185 7680 7130 7648 7072 7611 7007 7680 7130 7712 7186 7648 7072 7681 7131 5289 4567 7649 7073 7712 7186 7677 7127 7648 7072 7649 7073 5289 4567 5291 4568 7683 7076 7684 7132 7616 7015 5295 7074 5292 7012 5297 4569 5297 4569 7615 7013 7682 7075 7781 7187 7650 7020 7713 7188 7616 7015 7684 7132 7617 7016 7754 7189 7504 6836 7716 7078 7619 7019 7714 7135 7620 7018 7470 7190 7293 7190 7622 7190 7505 6837 7621 7021 7715 7077 7505 6837 7716 7078 7504 6836 7550 7022 7388 6694 7430 6739 7555 7191 7651 7191 7720 7191 7555 7192 7720 7192 7721 7192 7557 7193 7555 7193 7721 7193 7721 7194 7722 7194 7557 7194 7722 7195 7723 7195 7690 7195 7723 7196 7724 7196 7691 7196 7722 7197 7690 7197 7557 7197 7723 7198 7691 7198 7690 7198 4884 7199 4881 7199 7725 7199 5024 7200 7691 7200 7724 7200 7692 7201 7656 7201 7655 7201 7692 7202 7725 7202 7726 7202 7694 7203 7693 7203 7727 7203 7729 7204 7695 7204 7727 7204 7659 7205 7695 7205 7730 7205 7660 7206 7730 7206 7731 7206 7730 7207 7660 7207 7659 7207 7731 7208 7696 7208 7660 7208 7661 7209 7696 7209 7732 7209 7662 7210 7732 7210 7733 7210 7732 7211 7662 7211 7661 7211 7663 7212 7733 7212 7697 7212 7733 7213 7663 7213 7662 7213 7734 7214 7699 7214 7698 7214 7665 7215 7699 7215 7735 7215 7665 7216 7735 7216 7736 7216 7736 7217 7700 7217 7665 7217 7667 7218 7704 7218 7737 7218 7668 7219 7737 7219 7738 7219 7737 7220 7668 7220 7667 7220 7738 7221 7705 7221 7668 7221 7669 7114 7706 7179 7739 7222 7670 7116 7739 7222 7740 7223 7739 7222 7670 7116 7669 7114 7740 7223 7707 7180 7670 7116 7709 7182 7741 7224 7671 7117 7710 7183 7742 7225 7672 7120 7742 7226 7743 7226 7673 7226 7741 7224 7710 7183 7671 7117 7673 7227 7674 7227 7646 7227 7673 7228 7672 7228 7742 7228 7711 7229 7675 7229 7647 7229 7674 7230 7673 7230 7743 7230 7674 7231 7743 7231 7711 7231 7680 7130 7678 7128 7744 7232 7711 7233 7745 7233 7675 7233 7712 7186 7680 7130 7746 7234 7747 7235 7676 7126 7745 7236 7677 7127 7712 7186 7748 7237 7678 7128 7747 7235 7744 7232 7679 7129 7748 7237 7749 7238 7680 7130 7744 7232 7746 7234 7681 7131 7749 7238 5288 4564 7677 7127 7748 7237 7679 7129 7749 7238 7681 7131 7679 7129 7751 7239 7682 7075 7750 7240 5289 4567 7681 7131 5288 4564 7752 7241 7683 7076 7751 7239 5291 4568 5290 4566 5292 7012 7620 7018 7714 7135 7713 7188 7618 7017 7617 7016 7685 7133 7618 7017 7686 7134 7714 7135 7753 7242 7622 7136 7754 7189 7620 7018 7713 7188 7650 7020 7470 7243 7622 7243 7753 7243 7504 6836 7754 7189 7622 7136 7551 7137 7550 7022 7294 6596 7719 7244 7652 7244 7651 7244 7720 7245 7651 7245 7652 7245 7652 7246 7755 7246 7720 7246 7721 7247 7755 7247 5020 7247 7755 7248 7721 7248 7720 7248 7756 7249 7722 7249 5020 7249 7722 7250 7721 7250 5020 7250 7757 7251 7723 7251 7756 7251 7758 7252 7724 7252 7757 7252 7723 7253 7722 7253 7756 7253 7757 7254 7724 7254 7723 7254 5024 7255 7758 7255 4884 7255 7724 7256 7758 7256 5024 7256 7725 7257 7655 7257 5024 7257 7725 7258 7692 7258 7655 7258 7726 7259 7656 7259 7692 7259 7726 7260 7693 7260 7656 7260 7759 7261 7728 7261 7727 7261 7727 7262 7693 7262 7759 7262 7728 7263 7729 7263 7727 7263 7760 7264 7695 7264 7729 7264 7730 7265 7695 7265 7760 7265 7761 7266 7696 7266 7731 7266 7732 7267 7696 7267 7761 7267 7763 7268 7698 7268 7762 7268 7734 7269 7698 7269 7763 7269 7697 7270 7733 7270 7762 7270 7698 7271 7697 7271 7762 7271 7735 7272 7699 7272 7764 7272 7699 7273 7734 7273 7764 7273 7736 7274 7735 7274 7765 7274 7766 7275 7700 7275 7765 7275 7700 7276 7736 7276 7765 7276 7767 7277 7701 7277 7766 7277 7701 7278 7700 7278 7766 7278 7768 7279 7702 7279 7767 7279 7769 7280 7703 7280 7768 7280 7702 7281 7701 7281 7767 7281 7770 7282 7666 7282 7769 7282 7703 7283 7702 7283 7768 7283 7666 7284 7703 7284 7769 7284 7704 7285 7666 7285 7770 7285 7771 7286 7705 7286 7738 7286 7772 7287 7706 7287 7771 7287 7706 7179 7705 7177 7771 7288 7773 7289 7707 7180 7740 7223 7739 7222 7706 7179 7772 7290 7708 7181 7773 7289 7774 7291 7709 7182 7774 7291 7775 7292 7773 7289 7708 7181 7707 7180 7774 7291 7709 7182 7708 7181 7710 7183 7741 7224 7776 7293 7775 7292 7741 7224 7709 7182 7710 7183 7776 7293 7742 7225 7745 7236 7676 7126 7675 7125 7747 7235 7678 7128 7676 7126 7933 7294 5268 7295 5269 4560 7746 7234 7778 7296 7712 7186 7712 7186 7778 7296 7748 7237 7615 7013 5292 7012 7750 7240 7615 7013 7750 7240 7682 7075 7780 7297 7714 7135 7686 7134 7715 7077 7650 7020 7781 7187 7719 7298 7689 7298 7652 7298 7755 7299 7652 7299 7689 7299 7755 7300 7689 7300 5021 7300 7785 7301 7756 7301 5021 7301 5020 7302 7755 7302 5021 7302 7756 7303 5020 7303 5021 7303 7757 7304 7756 7304 7785 7304 7725 7305 5024 7305 4884 7305 7758 7306 7757 7306 4884 7306 7725 7307 4881 7307 7786 7307 7786 7308 7787 7308 7726 7308 7726 7309 7759 7309 7693 7309 7759 7310 7726 7310 7787 7310 7788 7311 7728 7311 7787 7311 7728 7312 7759 7312 7787 7312 7789 7313 7729 7313 7788 7313 7729 7314 7728 7314 7788 7314 7790 7315 7730 7315 7760 7315 7760 7316 7729 7316 7789 7316 7791 7317 7731 7317 7790 7317 7731 7318 7730 7318 7790 7318 7761 7319 7731 7319 7791 7319 7793 7320 7733 7320 7792 7320 7762 7321 7733 7321 7793 7321 7732 7322 7761 7322 7792 7322 7733 7323 7732 7323 7792 7323 7734 7324 7763 7324 7794 7324 7764 7325 7734 7325 7794 7325 7735 7326 7764 7326 7795 7326 7765 7327 7735 7327 7795 7327 7796 7328 7704 7328 7770 7328 7737 7329 7704 7329 7796 7329 7797 7330 7739 7222 7772 7290 7798 7331 7740 7223 7797 7330 7740 7223 7739 7222 7797 7330 7773 7289 7740 7223 7798 7331 7745 7332 7711 7332 7777 7332 7711 7333 7743 7333 7800 7333 7777 7334 7711 7334 7800 7334 7746 7234 7744 7232 7801 7335 7745 7336 7777 7336 7802 7336 7744 7232 7747 7235 7801 7335 7827 7337 7684 7132 7752 7241 5290 4566 7803 4565 5292 7012 7683 7076 7682 7075 7751 7239 7684 7132 7683 7076 7752 7241 7806 7338 7807 7339 7754 7189 7717 7340 7470 7340 7753 7340 7388 6694 7552 6906 7292 6693 5372 4631 7292 6693 7553 6907 7783 7341 7809 7341 7689 7341 7689 7342 7719 7342 7783 7342 7689 7343 7809 7343 5022 7343 5021 7344 7689 7344 5022 7344 7810 7345 7785 7345 5023 7345 5023 7346 7785 7346 5021 7346 7811 7347 7757 7347 7810 7347 7810 7348 7757 7348 7785 7348 7812 7349 7757 7349 7811 7349 7757 7350 7812 7350 4884 7350 7812 7351 4881 7351 4884 7351 7786 7352 7726 7352 7725 7352 7786 7353 4881 7353 7813 7353 7815 7354 7760 7354 7789 7354 7815 7355 7790 7355 7760 7355 7792 7356 7761 7356 7791 7356 7816 7357 7762 7357 7793 7357 7817 7358 7763 7358 7816 7358 7816 7359 7763 7359 7762 7359 7795 7360 7764 7360 7794 7360 7817 7361 7794 7361 7763 7361 7819 7362 7765 7362 7795 7362 7820 7363 7766 7363 7765 7363 7821 7364 7767 7364 7820 7364 7820 7365 7767 7365 7766 7365 7821 7366 7768 7366 7767 7366 7822 7367 7737 7367 7796 7367 7823 7368 7738 7368 7822 7368 7822 7369 7738 7369 7737 7369 7823 7370 7771 7370 7738 7370 7824 7371 7742 7225 7776 7293 7742 7372 7799 7372 7743 7372 7799 7373 7800 7373 7743 7373 7799 7374 7742 7374 7824 7374 7802 7375 7747 7235 7745 7236 7777 7376 7800 7376 7825 7376 7826 7377 7778 7296 7746 7234 5289 4567 5288 4564 7779 7378 7778 7296 7826 7377 7748 7237 5292 7012 7803 4565 7804 7379 7803 4565 5289 4567 7779 7378 7750 7240 5292 7012 7804 7379 7780 7297 7830 7380 7713 7188 7684 7132 7827 7337 7685 7133 7715 7077 7781 7187 7805 7381 7716 7078 7805 7381 7806 7338 7713 7188 7714 7135 7780 7297 7716 7078 7715 7077 7805 7381 7754 7189 7716 7078 7806 7338 7718 7382 7808 7383 7550 7022 7783 7384 7833 7384 7809 7384 5022 7385 7809 7385 7833 7385 5026 7386 7810 7386 5023 7386 7834 7387 5030 7387 7812 7387 7812 7388 7811 7388 7834 7388 5030 7389 4881 7389 7812 7389 4881 7390 5030 7390 7835 7390 7813 7391 7787 7391 7786 7391 7813 7392 7814 7392 7787 7392 7814 7393 7813 7393 7836 7393 7814 7394 7837 7394 7787 7394 7837 7395 7838 7395 7788 7395 7837 7396 7788 7396 7787 7396 7838 7397 7815 7397 7789 7397 7838 7398 7789 7398 7788 7398 7815 7399 7839 7399 7790 7399 7839 7400 7840 7400 7791 7400 7840 7401 7841 7401 7792 7401 7839 7402 7791 7402 7790 7402 7840 7403 7792 7403 7791 7403 7841 7404 7793 7404 7792 7404 7817 7405 7842 7405 7794 7405 7842 7406 7843 7406 7794 7406 7843 7407 7818 7407 7795 7407 7843 7408 7795 7408 7794 7408 7818 7409 7819 7409 7795 7409 7819 7410 7820 7410 7765 7410 7770 7411 7844 7411 7796 7411 7844 7412 7822 7412 7796 7412 7771 7413 7845 7413 7772 7413 7845 7414 7797 7330 7772 7290 7775 7292 7846 7415 7741 7224 7741 7224 7846 7415 7776 7293 7802 7416 7777 7416 7825 7416 7800 7417 7799 7417 7847 7417 7848 7418 7825 7418 7800 7418 7849 7419 7801 7335 7747 7235 7826 7377 7746 7234 7850 7420 7747 7235 7802 7375 7849 7419 7748 7237 7826 7377 5287 7421 7749 7238 5287 7421 5265 4562 7801 7335 7850 7420 7746 7234 7779 7378 7851 7422 7803 4565 7748 7237 5287 7421 7749 7238 7804 7379 7852 7423 7750 7240 5288 4564 7749 7238 5265 4562 5264 4563 7779 7378 5288 4564 7685 7133 7827 7337 7828 7424 7686 7134 7828 7424 7829 7425 7686 7134 7685 7133 7828 7424 7780 7297 7686 7134 7829 7425 7807 7339 7831 7426 7753 7242 7781 7187 7713 7188 7830 7380 7551 7137 7717 7139 7718 7382 7753 7242 7754 7189 7807 7339 7831 7427 7717 7427 7753 7427 7550 7022 7551 7137 7718 7382 7832 7428 7688 7428 7783 7428 7833 7429 7783 7429 7688 7429 7688 7430 5028 7430 7833 7430 5028 7431 5022 7431 7833 7431 5028 7432 5026 7432 5022 7432 7810 7433 5026 7433 7855 7433 7811 7434 7855 7434 7856 7434 7834 7435 7856 7435 7857 7435 7855 7436 7811 7436 7810 7436 7834 7437 7857 7437 7858 7437 7856 7438 7834 7438 7811 7438 7834 7439 7858 7439 5030 7439 7835 7440 7813 7440 4881 7440 5030 7441 5029 7441 7835 7441 7835 7442 7836 7442 7813 7442 7836 7443 7837 7443 7814 7443 7861 7444 7839 7444 7815 7444 7841 7445 7862 7445 7793 7445 7862 7446 7863 7446 7816 7446 7862 7447 7816 7447 7793 7447 7863 7448 7817 7448 7816 7448 7864 7449 7842 7449 7817 7449 7818 7450 7866 7450 7819 7450 7819 7451 7867 7451 7820 7451 7867 7452 7868 7452 7821 7452 7868 7453 7869 7453 7821 7453 7869 7454 7870 7454 7768 7454 7867 7455 7821 7455 7820 7455 7870 7456 7871 7456 7769 7456 7871 7457 7872 7457 7770 7457 7869 7458 7768 7458 7821 7458 7870 7459 7769 7459 7768 7459 7844 7460 7873 7460 7822 7460 7871 7461 7770 7461 7769 7461 7873 7462 7874 7462 7823 7462 7872 7463 7844 7463 7770 7463 7874 7464 7875 7464 7771 7464 7873 7465 7823 7465 7822 7465 7845 7414 7876 7466 7797 7330 7874 7467 7771 7467 7823 7467 7876 7466 7877 7468 7798 7331 7875 7469 7845 7469 7771 7469 7877 7468 7878 7470 7773 7289 7878 7470 7879 7471 7774 7291 7876 7466 7798 7331 7797 7330 7879 7471 7880 7472 7775 7292 7877 7468 7773 7289 7798 7331 7878 7470 7774 7291 7773 7289 7846 7415 7881 7473 7776 7293 7879 7471 7775 7292 7774 7291 7880 7472 7846 7415 7775 7292 7824 7474 7847 7474 7799 7474 7824 7371 7776 7293 7881 7473 7847 7475 7848 7475 7800 7475 7882 7476 7849 7419 7802 7375 7802 7477 7825 7477 7882 7477 5287 7421 5286 7478 5265 4562 7827 7337 7885 7479 7886 7480 7751 7239 7750 7240 7852 7423 7781 7187 7830 7380 7853 7481 7805 7381 7781 7187 7853 7481 7552 6906 7808 7383 7782 7482 7832 7483 7887 7483 7688 7483 5028 7484 7688 7484 7887 7484 5028 7485 7887 7485 5027 7485 7888 7486 5026 7486 5027 7486 5027 7487 5026 7487 5028 7487 5029 7488 7836 7488 7835 7488 5029 7489 7859 7489 7836 7489 7859 7490 7837 7490 7836 7490 7889 7491 7890 7491 7838 7491 7889 7492 7838 7492 7837 7492 7815 7493 7838 7493 7890 7493 7890 7494 7861 7494 7815 7494 7841 7495 7840 7495 7891 7495 7839 7496 7891 7496 7840 7496 7891 7497 7892 7497 7841 7497 7863 7498 7864 7498 7817 7498 7843 7499 7842 7499 7893 7499 7864 7500 7893 7500 7842 7500 7818 7501 7843 7501 7894 7501 7893 7502 7894 7502 7843 7502 7894 7503 7865 7503 7818 7503 7866 7504 7818 7504 7865 7504 7867 7505 7819 7505 7895 7505 7866 7506 7895 7506 7819 7506 7896 7507 7847 7507 7824 7507 7897 7508 7848 7508 7847 7508 7850 7420 7801 7335 5270 4559 5270 4559 7801 7335 7849 7419 7898 7509 5264 4563 5265 4562 7779 7378 5264 4563 7899 7510 7804 7379 7851 7422 7883 7511 7751 7239 7852 7423 7884 7512 7752 7241 7884 7512 7885 7479 7851 7422 7804 7379 7803 4565 7828 7424 7900 7513 7829 7425 7829 7425 7901 7514 7902 7515 7752 7241 7751 7239 7884 7512 7827 7337 7752 7241 7885 7479 7903 7516 7853 7481 7830 7380 7805 7381 7853 7481 7904 7517 7806 7338 7904 7517 7905 7518 7808 7383 7552 6906 7550 7022 7718 7382 7906 7519 7808 7383 7887 7520 7784 7520 5031 7520 5027 7521 7887 7521 5031 7521 7888 7522 7907 7522 5026 7522 7907 7523 7908 7523 7855 7523 7908 7524 7909 7524 7856 7524 7907 7525 7855 7525 5026 7525 7908 7526 7856 7526 7855 7526 7909 7527 5036 7527 7858 7527 7909 7528 7857 7528 7856 7528 7909 7529 7858 7529 7857 7529 5030 7530 7858 7530 5036 7530 5030 7531 5036 7531 4877 7531 7859 7532 5029 7532 7910 7532 7837 7533 7859 7533 7910 7533 7860 7534 7889 7534 7837 7534 7912 7535 7860 7535 7911 7535 7841 7536 7892 7536 7862 7536 7863 7537 7913 7537 7864 7537 7863 7538 7862 7538 7913 7538 7867 7539 7914 7539 7868 7539 7867 7540 7895 7540 7914 7540 7846 7415 7915 7541 7881 7473 7846 7415 7880 7472 7915 7541 7897 7542 7847 7542 7896 7542 7916 7543 7824 7371 7881 7473 7917 7544 7882 7544 7825 7544 7825 7545 7848 7545 7917 7545 5267 7546 7826 7377 7850 7420 5267 7546 5287 7421 7826 7377 7852 7423 7918 7547 7884 7512 7851 7422 7779 7378 7899 7510 7883 7511 7852 7423 7804 7379 7780 7297 7829 7425 7902 7515 7886 7480 7828 7424 7827 7337 7830 7380 7780 7297 7902 7515 7806 7338 7805 7381 7904 7517 7807 7339 7806 7338 7905 7518 7832 7548 7784 7548 7887 7548 7784 7549 5032 7549 5031 7549 7888 7550 5027 7550 5032 7550 7907 7551 7888 7551 7921 7551 5032 7552 7921 7552 7888 7552 5041 7553 7910 7553 4877 7553 4877 7554 7910 7554 5029 7554 7910 7555 7911 7555 7837 7555 7837 7556 7911 7556 7860 7556 7860 7557 7912 7557 7889 7557 7889 7558 7912 7558 7922 7558 7922 7559 7890 7559 7889 7559 7861 7560 7890 7560 7923 7560 7890 7561 7922 7561 7923 7561 7839 7562 7861 7562 7923 7562 7891 7563 7839 7563 7924 7563 7839 7564 7923 7564 7924 7564 7864 7565 7913 7565 7893 7565 7894 7566 7893 7566 7925 7566 7865 7567 7894 7567 7926 7567 7894 7568 7925 7568 7926 7568 7865 7569 7926 7569 7927 7569 7866 7570 7865 7570 7928 7570 7865 7571 7927 7571 7928 7571 7914 7572 7895 7572 7929 7572 7895 7573 7866 7573 7929 7573 7873 7574 7844 7574 7930 7574 7844 7575 7872 7575 7930 7575 7876 7466 7845 7414 7931 7576 7845 7577 7875 7577 7931 7577 7824 7578 7916 7578 7896 7578 7897 7579 7932 7579 7848 7579 7932 7580 7917 7580 7848 7580 7933 7294 5270 4559 7849 7419 5267 7546 7850 7420 5266 4561 7933 7294 7849 7419 7882 7476 5266 4561 7850 7420 5270 4559 7934 7581 7899 7510 5264 4563 5267 7546 5286 7478 5287 7421 5286 7478 7898 7509 5265 4562 7898 7509 7934 7581 5264 4563 7885 7479 7935 7582 7886 7480 7900 7513 7828 7424 7886 7480 7936 7583 7904 7517 7853 7481 7900 7513 7901 7514 7829 7425 7902 7515 7903 7516 7830 7380 7919 7584 7831 7426 7807 7339 7905 7518 7919 7584 7807 7339 7552 6906 7782 7482 7553 6907 7687 7585 7854 7585 7784 7585 7854 7586 5032 7586 7784 7586 7854 7587 5033 7587 5032 7587 5032 7588 7938 7588 7921 7588 5032 7589 5033 7589 7938 7589 7921 7590 7938 7590 7907 7590 7908 7591 7907 7591 7909 7591 7909 7592 7907 7592 7939 7592 7909 7593 7940 7593 5036 7593 7939 7594 7940 7594 7909 7594 5036 7595 4878 7595 4877 7595 4878 7596 5041 7596 4877 7596 7941 7597 5036 7597 7940 7597 5036 7598 7941 7598 4878 7598 7912 7599 7942 7599 7922 7599 7912 7600 7910 7600 7942 7600 7942 7601 7943 7601 7922 7601 7892 7602 7891 7602 7944 7602 7862 7603 7892 7603 7945 7603 7892 7604 7944 7604 7945 7604 7913 7605 7862 7605 7946 7605 7862 7606 7945 7606 7946 7606 7893 7607 7913 7607 7948 7607 7913 7608 7946 7608 7947 7608 7913 7609 7947 7609 7948 7609 7925 7610 7893 7610 7949 7610 7929 7611 7866 7611 7951 7611 7866 7612 7928 7612 7950 7612 7866 7613 7950 7613 7951 7613 7868 7614 7914 7614 7953 7614 7914 7615 7929 7615 7952 7615 7869 7616 7868 7616 7954 7616 7914 7617 7952 7617 7953 7617 7868 7618 7953 7618 7954 7618 7955 7619 7869 7619 7954 7619 7956 7620 7870 7620 7955 7620 7957 7621 7871 7621 7956 7621 7958 7622 7872 7622 7957 7622 7959 7623 7873 7623 7930 7623 7960 7624 7875 7624 7959 7624 7961 7625 7876 7466 7931 7576 7962 7626 7877 7468 7961 7625 7963 7627 7878 7470 7962 7626 7964 7628 7879 7471 7963 7627 7965 7629 7880 7472 7964 7628 7915 7541 7966 7630 7881 7473 7967 7631 7933 7294 7882 7476 7882 7632 7917 7632 7967 7632 7883 7511 7851 7422 8000 7633 7885 7479 7884 7512 7968 7634 7883 7511 7918 7547 7852 7423 7969 7635 7903 7516 7902 7515 7903 7516 7936 7583 7853 7481 7910 7636 5041 7636 7970 7636 7911 7637 7910 7637 7912 7637 7972 7638 7922 7638 7971 7638 7922 7639 7943 7639 7971 7639 7973 7640 7922 7640 7972 7640 7974 7641 7922 7641 7973 7641 7975 7642 7922 7642 7974 7642 7976 7643 7922 7643 7975 7643 7977 7644 7923 7644 7976 7644 7923 7645 7922 7645 7976 7645 7978 7646 7923 7646 7977 7646 7979 7647 7923 7647 7978 7647 7924 7648 7923 7648 7979 7648 7980 7649 7891 7649 7924 7649 7891 7650 7980 7650 7981 7650 7981 7651 7944 7651 7891 7651 7893 7652 7948 7652 7982 7652 7982 7653 7949 7653 7893 7653 7983 7654 7927 7654 7926 7654 7984 7655 7928 7655 7927 7655 7928 7656 7984 7656 7985 7656 7928 7657 7985 7657 7986 7657 7986 7658 7950 7658 7928 7658 7953 7659 7987 7659 7954 7659 7988 7660 7955 7660 7954 7660 7870 7661 7869 7661 7955 7661 7989 7662 7956 7662 7955 7662 7871 7663 7870 7663 7956 7663 7990 7664 7957 7664 7956 7664 7872 7665 7871 7665 7957 7665 7991 7666 7958 7666 7957 7666 7930 7667 7872 7667 7958 7667 7992 7668 7930 7668 7958 7668 7993 7669 7959 7669 7930 7669 7874 7670 7873 7670 7959 7670 7875 7671 7874 7671 7959 7671 7994 7672 7960 7672 7959 7672 7931 7673 7875 7673 7960 7673 7877 7468 7876 7466 7961 7625 7878 7470 7877 7468 7962 7626 7879 7471 7878 7470 7963 7627 7880 7472 7879 7471 7964 7628 7915 7541 7880 7472 7965 7629 7916 7543 7881 7473 7966 7630 7897 7674 7996 7674 7997 7674 7896 7675 7916 7675 7996 7675 7897 7676 7997 7676 7998 7676 7996 7677 7897 7677 7896 7677 7998 7678 7932 7678 7897 7678 7998 7679 7917 7679 7932 7679 7899 7510 8000 7633 7851 7422 7900 7513 7886 7480 8002 7680 7918 7547 7968 7634 7884 7512 7885 7479 7968 7634 7935 7582 7718 7382 7717 7139 8005 7681 7687 7682 5034 7682 7854 7682 5034 7683 5033 7683 7854 7683 5033 7684 8006 7684 7938 7684 5034 7685 8006 7685 5033 7685 7938 7686 8007 7686 7907 7686 8006 7687 8007 7687 7938 7687 7907 7688 8008 7688 7939 7688 8007 7689 8008 7689 7907 7689 7939 7690 8009 7690 7940 7690 8008 7691 8009 7691 7939 7691 7940 7692 8010 7692 7941 7692 7941 7693 8010 7693 4878 7693 8009 7694 8010 7694 7940 7694 5040 7695 7970 7695 4878 7695 4878 7696 8010 7696 5040 7696 4878 7697 7970 7697 5041 7697 7910 7698 7970 7698 8011 7698 7942 7699 7910 7699 8011 7699 7973 7700 8012 7700 7974 7700 8012 7701 8013 7701 7974 7701 7974 7702 8013 7702 7975 7702 8013 7703 8014 7703 7975 7703 7975 7704 8014 7704 7976 7704 8014 7705 8015 7705 7976 7705 7976 7706 8015 7706 7977 7706 8015 7707 8016 7707 7977 7707 7977 7708 8016 7708 7978 7708 8016 7709 8017 7709 7978 7709 7978 7710 8017 7710 7979 7710 8017 7711 8018 7711 7979 7711 7979 7712 8018 7712 7924 7712 8018 7713 8019 7713 7924 7713 7924 7714 8019 7714 7980 7714 7980 7715 8019 7715 7981 7715 8019 7716 8020 7716 7981 7716 7981 7717 8020 7717 7944 7717 8020 7718 8021 7718 7944 7718 7944 7719 8021 7719 7945 7719 8021 7720 8022 7720 7945 7720 7945 7721 8022 7721 7946 7721 7946 7722 8022 7722 7947 7722 8022 7723 8023 7723 7947 7723 7947 7724 8023 7724 7948 7724 8023 7725 8024 7725 7948 7725 7948 7726 8024 7726 7982 7726 8024 7727 8025 7727 7982 7727 7982 7728 8025 7728 7949 7728 8025 7729 8026 7729 7949 7729 7949 7730 8026 7730 7925 7730 8026 7731 8027 7731 7925 7731 7925 7732 8027 7732 7926 7732 8027 7733 8028 7733 7926 7733 7926 7734 8028 7734 7983 7734 8028 7735 8029 7735 7983 7735 7983 7736 8029 7736 7927 7736 8029 7737 8030 7737 7927 7737 7927 7738 8030 7738 7984 7738 8030 7739 8031 7739 7984 7739 7984 7740 8031 7740 7985 7740 8031 7741 8032 7741 7985 7741 7985 7742 8032 7742 7986 7742 8032 7743 8033 7743 7986 7743 7986 7744 8033 7744 7950 7744 8033 7745 8034 7745 7950 7745 7950 7746 8034 7746 7951 7746 8034 7747 8035 7747 7951 7747 7951 7748 8035 7748 7929 7748 8035 7749 8036 7749 7929 7749 7929 7750 8036 7750 7952 7750 8036 7751 8037 7751 7952 7751 7952 7752 8037 7752 7953 7752 8037 7753 7987 7753 7953 7753 7987 7754 7988 7754 7954 7754 7988 7755 7989 7755 7955 7755 7989 7756 7990 7756 7956 7756 7990 7757 7991 7757 7957 7757 7991 7758 7992 7758 7958 7758 7992 7759 7993 7759 7930 7759 7993 7760 7994 7760 7959 7760 7994 7761 8038 7761 7960 7761 7960 7762 8038 7762 7931 7762 8038 7763 8039 7763 7931 7763 7931 7576 8039 7764 7961 7625 8039 7764 8040 7765 7961 7625 7961 7625 8040 7765 7962 7626 8040 7765 8041 7766 7962 7626 7962 7626 8041 7766 7963 7627 8041 7766 8042 7767 7963 7627 7963 7627 8042 7767 7964 7628 8042 7767 8043 7768 7964 7628 7964 7628 8043 7768 7965 7629 8043 7768 8044 7769 7965 7629 7965 7629 8044 7769 7915 7541 8044 7769 7995 7770 7915 7541 7915 7541 7995 7770 7966 7630 7996 7771 7916 7771 8045 7771 7916 7543 7966 7630 8045 7772 8046 7773 7967 7773 7917 7773 7998 7774 8046 7774 7917 7774 5269 4560 5270 4559 7933 7294 7934 7581 7898 7509 8047 7775 8048 7776 8000 7633 7899 7510 8001 7777 7918 7547 7883 7511 7899 7510 7934 7581 8048 7776 8000 7633 8001 7777 7883 7511 8069 7778 8049 7779 7900 7513 7935 7582 8002 7680 7886 7480 7902 7515 7901 7514 7969 7635 8050 7780 7905 7518 7904 7517 8003 7781 7919 7584 7905 7518 7904 7517 7936 7583 8050 7780 8004 7782 7717 7782 7831 7782 7905 7518 8050 7780 8003 7781 7919 7584 8004 7783 7831 7426 5061 7784 7970 7784 5040 7784 8011 7785 8052 7785 7942 7785 7942 7786 8052 7786 7943 7786 8052 7787 8053 7787 7943 7787 7943 7788 8053 7788 7971 7788 8053 7789 8054 7789 7971 7789 7971 7790 8054 7790 7972 7790 8054 7791 8055 7791 7972 7791 7972 7792 8055 7792 7973 7792 8055 7793 8012 7793 7973 7793 7999 7794 5267 7546 5266 4561 7933 7294 7967 7631 5268 7295 8068 7795 5286 7478 5267 7546 5266 4561 5269 4560 7999 7794 5267 7546 7999 7794 8068 7795 5286 7478 8047 7775 7898 7509 8049 7779 7969 7635 7901 7514 7901 7514 7900 7513 8049 7779 7717 7796 8004 7796 8005 7796 7906 7519 7782 7482 7808 7383 7687 7797 8051 7797 7920 7797 7920 7798 5034 7798 7687 7798 8006 7799 5034 7799 5035 7799 5034 7800 7920 7800 5035 7800 8006 7801 8058 7801 8007 7801 8006 7802 5035 7802 8058 7802 8007 7803 8059 7803 8008 7803 8007 7804 8058 7804 8059 7804 8008 7805 8060 7805 8009 7805 8008 7806 8059 7806 8060 7806 8009 7807 8061 7807 8010 7807 8009 7808 8060 7808 8061 7808 8010 7809 5039 7809 5040 7809 8010 7810 8061 7810 5039 7810 7970 7811 5062 7811 8062 7811 5039 7812 5061 7812 5040 7812 8063 7813 7966 7813 7995 7813 8063 7814 8045 7772 7966 7630 5273 7815 5268 7295 7967 7631 8046 7816 5273 7816 7967 7816 8077 7817 8047 7775 5286 7478 8056 7818 8048 7776 7934 7581 5286 7478 8068 7795 8077 7817 7934 7581 8047 7775 8056 7818 7900 7513 8002 7680 8069 7778 8057 7819 7936 7583 7903 7516 7903 7516 7969 7635 8057 7819 7937 7820 7906 7519 7718 7382 5061 7821 5062 7821 7970 7821 7970 7822 8062 7822 8011 7822 5269 4560 8067 7823 7999 7794 8064 7824 7935 7582 7968 7634 7968 7634 7918 7547 8064 7824 7937 7820 7718 7382 8005 7681 7553 6907 7782 7482 8070 7825 5037 7826 8082 7826 5038 7826 7920 7827 8051 7827 5037 7827 5037 7828 5035 7828 7920 7828 8071 7829 8058 7829 5035 7829 5035 7830 5037 7830 8071 7830 8072 7831 8059 7831 8058 7831 8058 7832 8071 7832 8072 7832 8060 7833 8059 7833 8073 7833 8059 7834 8072 7834 8073 7834 5039 7835 8061 7835 8074 7835 8061 7836 8060 7836 8074 7836 5061 7837 5039 7837 5063 7837 5039 7838 8074 7838 5063 7838 5062 7839 5061 7839 8065 7839 5062 7840 5066 7840 8075 7840 5063 7841 8065 7841 5061 7841 8076 7842 8063 7842 7995 7842 8066 7843 5268 7295 5273 7815 8056 7818 8047 7775 8078 7844 8050 7780 8108 7845 8080 7846 7919 7584 8085 7847 8004 7783 8065 7848 5066 7848 5062 7848 5062 7849 8075 7849 8062 7849 8095 7850 5269 4560 8066 7843 5269 4560 5268 7295 8066 7843 8067 7823 8068 7795 7999 7794 8064 7824 7918 7547 8079 7851 7936 7583 8057 7819 8108 7845 8108 7845 8050 7780 7936 7583 8004 7783 8085 7847 8086 7852 7919 7584 8003 7781 8085 7847 8082 7853 8087 7853 5038 7853 8051 7854 8082 7854 5037 7854 8071 7855 5037 7855 5038 7855 8072 7856 8071 7856 8088 7856 8088 7857 8089 7857 8072 7857 8073 7858 8072 7858 8089 7858 8089 7859 8090 7859 8060 7859 8060 7860 8073 7860 8089 7860 8090 7861 8091 7861 8060 7861 8091 7862 8092 7862 8060 7862 8074 7863 8060 7863 8092 7863 8075 7864 5066 7864 5069 7864 8083 7865 8075 7865 5069 7865 8062 7866 8075 7866 8083 7866 7996 7867 8045 7867 8093 7867 8045 7772 8063 7814 8093 7868 7997 7869 8094 7869 5274 7869 7996 7870 8093 7870 8094 7870 8094 7871 7997 7871 7996 7871 5274 7872 5275 7872 7998 7872 5275 7873 5271 7873 8046 7873 7997 7874 5274 7874 7998 7874 5271 7875 5272 7875 5273 7875 8046 7876 7998 7876 5275 7876 5271 7877 5273 7877 8046 7877 5272 7878 8066 7843 5273 7815 8095 7850 8067 7823 5269 4560 8048 7776 8078 7844 8096 7879 8097 7880 8000 7633 8096 7879 8084 7881 8001 7777 8097 7880 8078 7844 8048 7776 8056 7818 8001 7777 8079 7851 7918 7547 8049 7779 8069 7778 8106 7882 7969 7635 8106 7882 8100 7883 8101 7884 8003 7781 8080 7846 8080 7846 8003 7781 8050 7780 8004 7885 8086 7885 8005 7885 7906 7519 8081 7886 7782 7482 5063 7887 8074 7887 8092 7887 8077 7817 8103 7888 8104 7889 8096 7879 8000 7633 8048 7776 8097 7880 8001 7777 8000 7633 8001 7777 8084 7881 8079 7851 7935 7582 8064 7824 8098 7890 8002 7680 8098 7890 8099 7891 8098 7890 8002 7680 7935 7582 8099 7891 8069 7778 8002 7680 8100 7883 8107 7892 8057 7819 8106 7882 7969 7635 8049 7779 8100 7883 8057 7819 7969 7635 8101 7884 8085 7847 8003 7781 8005 7893 8086 7893 8102 7893 8110 7894 8071 7894 8087 7894 8087 7895 8071 7895 5038 7895 8110 7896 8088 7896 8071 7896 8111 7897 8089 7897 8110 7897 8110 7898 8089 7898 8088 7898 8111 7899 8090 7899 8089 7899 8112 7900 8092 7900 8091 7900 8112 7901 5063 7901 8092 7901 5069 7902 8065 7902 8112 7902 8112 7903 8065 7903 5063 7903 8065 7904 5069 7904 5066 7904 8076 7905 8113 7905 8063 7905 8113 7906 8093 7868 8063 7814 8066 7843 5272 7878 8114 7907 8067 7823 8095 7850 8115 7908 8068 7795 8067 7823 8103 7888 8047 7775 8077 7817 8105 7909 8068 7795 8103 7888 8077 7817 8096 7879 8078 7844 8116 7910 8097 7880 8116 7910 8117 7911 8047 7775 8105 7909 8078 7844 8084 7881 8117 7911 8118 7912 8119 7913 8064 7824 8079 7851 8069 7778 8099 7891 8120 7914 8101 7884 8080 7846 8121 7915 8102 7916 7937 7820 8005 7681 8122 7917 7906 7519 7937 7820 5372 4631 7553 6907 8070 7825 8109 7918 8124 7918 8087 7918 8109 7919 8087 7919 8082 7919 8124 7920 8110 7920 8087 7920 8124 7921 8125 7921 8111 7921 8124 7922 8111 7922 8110 7922 8125 7923 8090 7923 8111 7923 8090 7924 8112 7924 8091 7924 8126 7925 5069 7925 8112 7925 5069 7926 5075 7926 8083 7926 5275 7927 8128 7927 5271 7927 5271 7928 8128 7928 5272 7928 5272 7878 8129 7929 8114 7907 8066 7843 8114 7907 8095 7850 8115 7908 8103 7888 8067 7823 8077 7817 8104 7889 8105 7909 8079 7851 8130 7930 8119 7913 8119 7913 8131 7931 8132 7932 8132 7932 8133 7933 8099 7891 8064 7824 8119 7913 8098 7890 8134 7934 8106 7882 8120 7914 8135 7935 8100 7883 8134 7934 8120 7914 8106 7882 8069 7778 8057 7819 8107 7892 8108 7845 8102 7916 8122 7917 7937 7820 8123 7936 7906 7519 8122 7917 8081 7886 8138 7937 8139 7938 7782 7482 8081 7886 8070 7825 5042 7939 8141 7939 8124 7939 5042 7940 8124 7940 8109 7940 8141 7941 8142 7941 8124 7941 8142 7942 8125 7942 8124 7942 8142 7943 8143 7943 8090 7943 8142 7944 8090 7944 8125 7944 8143 7945 8144 7945 8112 7945 8143 7946 8112 7946 8090 7946 8144 7947 8145 7947 8126 7947 8144 7948 8126 7948 8112 7948 8145 7949 5075 7949 5069 7949 8145 7950 5069 7950 8126 7950 8076 7951 8146 7951 8113 7951 5276 7952 8094 7952 8093 7952 5276 7953 5277 7953 5275 7953 5274 7954 8094 7954 5276 7954 5274 7955 5276 7955 5275 7955 8104 7889 8103 7888 8149 7956 8105 7909 8104 7889 8150 7957 8078 7844 8105 7909 8151 7958 8116 7910 8078 7844 8152 7959 8097 7880 8096 7879 8116 7910 8097 7880 8117 7911 8084 7881 8084 7881 8118 7912 8079 7851 8098 7890 8119 7913 8132 7932 8153 7960 8133 7933 8154 7961 8098 7890 8132 7932 8099 7891 8099 7891 8133 7933 8120 7914 8108 7845 8107 7892 8155 7962 8106 7882 8134 7934 8100 7883 8080 7846 8108 7845 8156 7963 8100 7883 8135 7935 8107 7892 8121 7915 8080 7846 8157 7964 8085 7847 8158 7965 8136 7966 8086 7852 8085 7847 8136 7966 8101 7884 8121 7915 8085 7847 8086 7967 8136 7967 8102 7967 7906 7519 8123 7936 8081 7886 8140 7968 5045 7968 5042 7968 5045 7969 8141 7969 5042 7969 5045 7970 8142 7970 8141 7970 8142 7971 5045 7971 8160 7971 8143 7972 8160 7972 8161 7972 8144 7973 8143 7973 8161 7973 8161 7974 8162 7974 8144 7974 8145 7975 8144 7975 8162 7975 8162 7976 8127 7976 8145 7976 5075 7977 8145 7977 8127 7977 5075 7978 8127 7978 5076 7978 5075 7979 5076 7979 8083 7979 8146 7980 8093 7868 8113 7906 5276 7981 8093 7868 8164 7982 8093 7868 8146 7980 8164 7982 5276 7981 8164 7982 5277 7983 8128 7984 5277 7983 5278 7985 8129 7929 8128 7984 8165 7986 5275 7987 5277 7987 8128 7987 8129 7988 5272 7988 8128 7988 8166 7989 8095 7850 8114 7907 8166 7989 8114 7907 8129 7929 8148 7990 8115 7908 8095 7850 8148 7990 8095 7850 8166 7989 8147 7991 8103 7888 8115 7908 8147 7991 8115 7908 8148 7990 8149 7956 8103 7888 8147 7991 8104 7889 8149 7956 8150 7957 8105 7909 8150 7957 8151 7958 8117 7911 8116 7910 8167 7992 8078 7844 8151 7958 8152 7959 8118 7912 8117 7911 8168 7993 8130 7930 8118 7912 8169 7994 8079 7851 8118 7912 8130 7930 8133 7933 8132 7932 8170 7995 8131 7931 8119 7913 8130 7930 8153 7960 8134 7934 8120 7914 8153 7960 8120 7914 8133 7933 8155 7962 8135 7935 8171 7996 8107 7892 8135 7935 8155 7962 8108 7845 8155 7962 8156 7963 8080 7846 8156 7963 8157 7964 8085 7847 8121 7915 8158 7965 8137 7997 8102 7997 8136 7997 8137 7998 8122 7917 8102 7916 8159 7999 8172 8000 5045 8001 5045 8001 8173 8002 8160 8003 8172 8000 8173 8002 5045 8001 8142 8004 8160 8004 8143 8004 8160 8003 8173 8002 8174 8005 8174 8005 8161 8006 8160 8003 8161 8006 8174 8005 8175 8007 8162 8008 8161 8006 8175 8007 8162 8008 8175 8007 8176 8009 8162 8008 8176 8009 8127 8010 8127 8010 8176 8009 8177 8011 8127 8010 8177 8011 5076 8012 5084 8013 5076 8012 8177 8011 8178 8014 8164 7982 8146 7980 5277 7983 8164 7982 5278 7985 5278 8015 5282 8015 8165 8015 8165 8016 8179 8016 8129 8016 8165 7986 8128 7984 5278 7985 8129 7929 8180 8017 8166 7989 8166 7989 8181 8018 8148 7990 8148 7990 8182 8019 8147 7991 8147 7991 8183 8020 8149 7956 8149 7956 8184 8021 8150 7957 8151 7958 8185 8022 8152 7959 8152 7959 8186 8023 8167 7992 8167 7992 8187 8024 8168 7993 8168 7993 8188 8025 8169 7994 8167 7992 8116 7910 8152 7959 8169 7994 8189 8026 8130 7930 8168 7993 8117 7911 8167 7992 8130 7930 8190 8027 8131 7931 8169 7994 8118 7912 8168 7993 8131 7931 8191 8028 8170 7995 8170 7995 8192 8029 8154 7961 8154 7961 8193 8030 8153 7960 8132 7932 8131 7931 8170 7995 8153 7960 8194 8031 8195 8032 8133 7933 8170 7995 8154 7961 8195 8032 8196 8033 8171 7996 8135 7935 8134 7934 8195 8032 8195 8032 8134 7934 8153 7960 8155 7962 8197 8034 8156 7963 8171 7996 8135 7935 8195 8032 8156 7963 8198 8035 8157 7964 8157 7964 8199 8036 8121 7915 8121 7915 8200 8037 8158 7965 8158 7965 8201 8038 8136 7966 8136 7966 8202 8039 8137 7998 8137 7998 8203 8040 8122 7917 8122 7917 8204 8041 8123 7936 8123 7936 8138 7937 8081 7886 8081 7886 8139 7938 8070 7825 8140 8042 8159 7999 5045 8001 8159 8043 5050 8043 8172 8043 5050 8044 8205 8044 8172 8044 8172 8045 8205 8045 8173 8045 8205 8046 8206 8046 8173 8046 8206 8047 8207 8047 8173 8047 8173 8048 8207 8048 8174 8048 8207 8049 8208 8049 8174 8049 8174 8050 8208 8050 8175 8050 8208 8051 8209 8051 8175 8051 8209 8052 8176 8052 8175 8052 5084 8053 8177 8053 8163 8053 8163 8054 8210 8054 5084 8054 5084 8013 8210 8055 5076 8012 8146 8056 8211 8056 8178 8056 8211 8057 8212 8058 8178 8014 8212 8058 8164 7982 8178 8014 8164 8059 8213 8059 5278 8059 8212 8058 8213 8060 8164 7982 5282 8061 5278 8061 8213 8061 8179 8062 8165 8062 5282 8062 8180 8063 8129 8063 8179 8063 8181 8018 8166 7989 8180 8017 8182 8019 8148 7990 8181 8018 8183 8020 8147 7991 8182 8019 8183 8020 8184 8021 8149 7956 8215 8064 8151 7958 8150 7957 8184 8021 8215 8064 8150 7957 8215 8064 8185 8022 8151 7958 8186 8023 8152 7959 8185 8022 8187 8024 8167 7992 8186 8023 8188 8025 8168 7993 8187 8024 8189 8026 8169 7994 8188 8025 8190 8027 8130 7930 8189 8026 8191 8028 8131 7931 8190 8027 8192 8029 8170 7995 8191 8028 8193 8030 8154 7961 8192 8029 8194 8031 8153 7960 8193 8030 8194 8031 8196 8033 8195 8032 8216 8065 8155 7962 8171 7996 8196 8033 8216 8065 8171 7996 8216 8065 8197 8034 8155 7962 8198 8035 8156 7963 8197 8034 8199 8036 8157 7964 8198 8035 8200 8037 8121 7915 8199 8036 8201 8038 8158 7965 8200 8037 8202 8039 8136 7966 8201 8038 8204 8041 8122 7917 8203 8040 8138 7937 8123 7936 8204 8041 5050 8066 5049 8067 5052 8068 5050 8066 5052 8068 8205 8069 8205 8069 5052 8068 8217 8070 8205 8069 8217 8070 8206 8071 8206 8071 8217 8070 8207 8072 8217 8070 8218 8073 8207 8072 8207 8072 8218 8073 8208 8074 8218 8073 8209 8075 8208 8074 8209 8075 8219 8076 8176 8009 8176 8009 8219 8076 8177 8011 8220 8077 8163 8078 8177 8011 8177 8011 8219 8076 8220 8077 8163 8078 8220 8077 5086 8079 5086 8079 8221 8080 8163 8078 8163 8081 8221 8081 8210 8081 8211 8057 8222 8082 8212 8058 8222 8082 8223 8083 8212 8058 8223 8083 8213 8060 8212 8058 8224 8084 8225 8085 5280 4554 5282 8086 8214 8087 8179 8088 8228 8089 8229 8090 8225 8085 8230 8091 8231 8092 8229 8090 8232 8093 8231 8092 8233 8094 8234 8095 8232 8093 8235 8096 8236 8097 8234 8095 8237 8098 8238 8099 8239 8100 8240 8101 8240 8101 8241 8102 8185 8022 8242 8103 8243 8104 8244 8105 8245 8106 8246 8107 8243 8104 8247 8108 8248 8109 8246 8107 8249 8110 8250 8111 8248 8109 8251 8112 8252 8113 8250 8111 8253 8114 8254 8115 8252 8113 8255 8116 8254 8115 8256 8117 8257 8118 8255 8116 8258 8119 8259 8120 8257 8118 8260 8121 8261 8122 8262 8123 8263 8124 8263 8124 8264 8125 8197 8034 8265 8126 8267 8127 8266 8128 8268 8129 8266 8128 8269 8130 8270 8131 8269 8130 8201 8038 8271 8132 8201 8038 8202 8039 8272 8133 8202 8039 8273 8134 8202 8039 8203 8040 8137 7998 8275 8135 8273 8134 8204 8041 8138 7937 8276 8136 8204 8041 8139 7938 8277 8137 8138 7937 8278 8138 8280 8139 8279 8140 8278 8138 8070 7825 8139 7938 8070 7825 8278 8138 5372 4631 5051 8141 8281 8141 5052 8141 8281 8142 8282 8142 5052 8142 8217 8143 5052 8143 8282 8143 8283 8144 8217 8144 8282 8144 8218 8145 8217 8145 8283 8145 8284 8146 8218 8146 8283 8146 8209 8147 8218 8147 8284 8147 8285 8148 8209 8148 8284 8148 8219 8149 8209 8149 8285 8149 8286 8150 8220 8150 8285 8150 8220 8151 8219 8151 8285 8151 5086 8152 8220 8152 8286 8152 5090 8153 5086 8153 8286 8153 5090 8154 5089 8154 5086 8154 5086 8079 5089 4383 8221 8080 8222 8155 5283 8155 8223 8155 5285 4558 8213 8060 8223 8083 5285 8156 8223 8156 5283 8156 8213 8060 5285 4558 5281 4555 5282 8157 8213 8157 5281 8157 5282 8158 5281 8158 5280 8158 8287 8159 8225 8085 8226 8160 5282 8161 5280 8161 8225 8161 8288 8162 8225 8085 8227 8163 8289 8164 8229 8090 8228 8089 8290 8165 8231 8092 8230 8091 8180 8017 8225 8085 8229 8090 8291 8166 8232 8093 8233 8094 8181 8018 8229 8090 8231 8092 8292 8167 8234 8095 8235 8096 8182 8019 8231 8092 8232 8093 8293 8168 8236 8097 8237 8098 8183 8020 8232 8093 8234 8095 8240 8101 8236 8097 8293 8168 8184 8021 8234 8095 8236 8097 8241 8102 8240 8101 8239 8100 8236 8097 8240 8101 8215 8064 8244 8105 8241 8102 8294 8169 8186 8023 8185 8022 8241 8102 8186 8023 8241 8102 8244 8105 8187 8024 8186 8023 8244 8105 8187 8024 8244 8105 8243 8104 8188 8025 8187 8024 8243 8104 8295 8170 8248 8109 8247 8108 8188 8025 8243 8104 8246 8107 8296 8171 8250 8111 8249 8110 8189 8026 8246 8107 8248 8109 8297 8172 8252 8113 8251 8112 8190 8027 8248 8109 8250 8111 8298 8173 8254 8115 8253 8114 8191 8028 8250 8111 8252 8113 8299 8174 8255 8116 8256 8117 8192 8029 8252 8113 8254 8115 8300 8175 8257 8118 8258 8119 8193 8030 8254 8115 8255 8116 8301 8176 8259 8120 8260 8121 8194 8031 8255 8116 8257 8118 8261 8122 8263 8124 8259 8120 8196 8033 8257 8118 8259 8120 8264 8125 8263 8124 8262 8123 8259 8120 8263 8124 8216 8065 8267 8127 8264 8125 8302 8177 8198 8035 8197 8034 8264 8125 8198 8035 8264 8125 8267 8127 8199 8036 8198 8035 8267 8127 8199 8036 8267 8127 8266 8128 8200 8037 8199 8036 8266 8128 8200 8037 8266 8128 8269 8130 8201 8038 8200 8037 8269 8130 8303 8178 8271 8132 8202 8039 8304 8179 8272 8133 8273 8134 8305 8180 8274 8181 8273 8134 8203 8182 8202 8182 8273 8182 8306 8183 8275 8135 8204 8041 8307 8184 8276 8136 8138 7937 8308 8185 8277 8137 8139 7938 8279 8140 8139 7938 8278 8138 5056 4362 8309 8186 5051 4363 8309 8186 8281 8187 5051 4363 8309 8186 8310 8188 8281 8187 8310 8188 8311 8189 8281 8187 8311 8189 8282 8190 8281 8187 8311 8189 8312 8191 8282 8190 8312 8191 8313 8192 8282 8190 8313 8192 8314 8193 8282 8190 8314 8193 8283 8194 8282 8190 8314 8193 8315 8195 8283 8194 8315 8195 8316 8196 8283 8194 8316 8196 8317 8197 8283 8194 8317 8197 8318 8198 8283 8194 8318 8198 8284 8199 8283 8194 8318 8198 8319 8200 8284 8199 8319 8200 8320 8201 8284 8199 8320 8201 8321 8202 8285 8203 8320 8201 8285 8203 8284 8199 8321 8202 8322 8204 8285 8203 8322 8204 8323 8205 8285 8203 8323 8205 8324 8206 8285 8203 8324 8206 8325 8207 8285 8203 8285 8203 8325 8207 8286 8208 8325 8207 8326 8209 8286 8208 8326 8209 8327 8210 8286 8208 8286 8208 8327 8210 5090 4384 8327 8210 5091 4385 5090 4384 5284 4557 5279 4553 5281 4555 5279 4553 8224 8084 5280 4554 8224 8084 8328 8211 8225 8085 8226 8160 8225 8085 8328 8211 8214 8212 5282 8212 8225 8212 8227 8163 8225 8085 8287 8159 8179 8213 8214 8213 8225 8213 8228 8089 8225 8085 8288 8162 8180 8017 8179 8088 8225 8085 8230 8091 8229 8090 8289 8164 8181 8018 8180 8017 8229 8090 8233 8094 8231 8092 8290 8165 8182 8019 8181 8018 8231 8092 8235 8096 8232 8093 8291 8166 8183 8020 8182 8019 8232 8093 8237 8098 8234 8095 8292 8167 8184 8021 8183 8020 8234 8095 8240 8101 8293 8168 8238 8099 8215 8064 8184 8021 8236 8097 8241 8102 8239 8100 8329 8214 8185 8022 8215 8064 8240 8101 8329 8214 8294 8169 8241 8102 8294 8169 8330 8215 8244 8105 8330 8215 8242 8103 8244 8105 8242 8103 8331 8216 8243 8104 8331 8216 8245 8106 8243 8104 8245 8106 8332 8217 8246 8107 8247 8108 8246 8107 8332 8217 8189 8026 8188 8025 8246 8107 8249 8110 8248 8109 8295 8170 8190 8027 8189 8026 8248 8109 8251 8112 8250 8111 8296 8171 8191 8028 8190 8027 8250 8111 8253 8114 8252 8113 8297 8172 8192 8029 8191 8028 8252 8113 8256 8117 8254 8115 8298 8173 8193 8030 8192 8029 8254 8115 8258 8119 8255 8116 8299 8174 8194 8031 8193 8030 8255 8116 8260 8121 8257 8118 8300 8175 8196 8033 8194 8031 8257 8118 8261 8122 8259 8120 8301 8176 8216 8065 8196 8033 8259 8120 8264 8125 8262 8123 8333 8218 8197 8034 8216 8065 8263 8124 8333 8218 8302 8177 8264 8125 8302 8177 8334 8219 8267 8127 8334 8219 8267 8127 8265 8126 8265 8126 8266 8128 8335 8220 8335 8220 8266 8128 8268 8129 8268 8129 8269 8130 8336 8221 8336 8221 8269 8130 8270 8131 8270 8131 8201 8038 8337 8222 8271 8132 8337 8222 8201 8038 8272 8133 8303 8178 8202 8039 8274 8181 8304 8179 8273 8134 8275 8135 8305 8180 8273 8134 8204 8041 8203 8040 8273 8134 8276 8136 8306 8183 8204 8041 8277 8137 8307 8184 8138 7937 8279 8140 8308 8185 8139 7938 8280 8139 8338 8223 8278 8138 5372 4631 8338 8223 8278 8138 8339 8224 8340 8224 8341 8224 8342 8225 8343 8225 8344 8225 8344 8226 8345 8226 8342 8226 8343 8227 8346 8227 8347 8227 8346 8228 8343 8228 8342 8228 8348 8229 8347 8229 8349 8229 8346 8230 8349 8230 8347 8230 8350 8231 8351 8231 8348 8231 8348 8232 8349 8232 8350 8232 8351 8233 8340 8233 8339 8233 8340 8234 8351 8234 8350 8234 8352 8235 8353 8235 8354 8235 8341 8236 8355 8236 8356 8236 8357 8237 8358 8237 8359 8237 8360 8238 8361 8238 8362 8238 8363 8239 8364 8239 8365 8239 8366 8240 8367 8240 8368 8240 8369 8241 8370 8241 8371 8241 8372 8242 8373 8242 8374 8242 8374 8243 8375 8243 8376 8243 8367 8244 8376 8244 8375 8244 8376 8245 8372 8245 8374 8245 8368 8246 8367 8246 8375 8246 8369 8247 8366 8247 8370 8247 8370 8248 8366 8248 8368 8248 8360 8249 8362 8249 8371 8249 8371 8250 8362 8250 8369 8250 8365 8251 8364 8251 8361 8251 8360 8252 8365 8252 8361 8252 8363 8253 8359 8253 8358 8253 8364 8254 8363 8254 8358 8254 8357 8255 8352 8255 8354 8255 8357 8256 8359 8256 8352 8256 8355 8257 8353 8257 8356 8257 8355 8258 8354 8258 8353 8258 8356 8259 8339 8259 8341 8259 8377 8260 8378 8260 8379 8260 8380 8261 8381 8261 8382 8261 8383 8262 8384 8262 8385 8262 8382 8263 8386 8263 8387 8263 8384 1451 8383 1451 8382 1451 8388 8264 8382 8264 8381 8264 8386 8265 8382 8265 8389 8265 8390 597 8391 597 8392 597 8392 8254 8393 8254 8390 8254 8394 8266 8395 8266 8385 8266 8392 8267 8391 8267 8377 8267 8395 8268 8394 8268 8396 8268 8397 8269 8390 8269 8398 8269 8399 8270 8396 8270 8400 8270 8402 8271 8396 8271 8399 8271 8378 8272 8377 8272 8391 8272 8378 8273 8403 8273 8379 8273 8403 8274 8404 8274 8405 8274 8378 8275 8404 8275 8403 8275 8406 8276 8403 8276 8405 8276 8405 8277 8407 8277 8406 8277 8408 8278 8396 8278 8409 8278 8400 8279 8396 8279 8410 8279 8411 8280 8382 8280 8412 8280 8396 8281 8413 8281 8414 8281 8410 8282 8396 8282 8414 8282 8384 8283 8382 8283 8415 8283 8413 8284 8396 8284 8408 8284 8416 8285 8396 8285 8417 8285 8416 8286 8409 8286 8396 8286 8417 8287 8396 8287 8394 8287 8395 8288 8383 8288 8385 8288 8411 8289 8415 8289 8382 8289 8382 8290 8418 8290 8412 8290 8418 8291 8382 8291 8387 8291 8388 8292 8389 8292 8382 8292 8382 8293 8390 8293 8380 8293 8390 8294 8397 8294 8380 8294 8419 8295 8420 8295 8421 8295 8398 8296 8390 8296 8401 8296 8422 8297 8390 8297 8393 8297 8390 8298 8422 8298 8401 8298 8423 8299 8393 8299 8419 8299 8423 8300 8422 8300 8393 8300 8419 8301 8393 8301 8420 8301 8424 8302 8425 8302 8421 8302 8421 8303 8420 8303 8424 8303 8426 8304 8425 8304 8402 8304 8424 8305 8402 8305 8425 8305 8427 8306 8428 8306 8402 8306 8402 8307 8428 8307 8426 8307 8429 8308 8430 8308 8402 8308 8402 8309 8430 8309 8427 8309 8431 8310 8432 8310 8402 8310 8402 8311 8432 8311 8429 8311 8399 8312 8433 8312 8402 8312 8402 8313 8433 8313 8431 8313 8434 8314 8435 8315 8436 8316 8437 8317 8438 8318 8439 8319 8440 2135 8441 8320 8442 8321 8443 8322 8444 8323 8445 8324 8446 8325 8447 8326 8448 8327 8449 2143 8450 2143 8451 8328 8452 8329 8453 8330 8454 8331 8455 8332 8456 8333 8457 8334 8458 2145 8459 8335 8460 8328 8461 8336 8462 8337 8463 8338 8464 8339 8465 8340 8466 8341 8467 8342 8468 8343 8469 499 8470 8344 8471 8345 8472 8346 8473 8347 8474 8348 8475 8349 8476 8350 8477 8351 8478 8352 8479 8353 8480 8354 8481 8355 8482 8356 8483 8357 8484 8358 8485 8359 8486 8360 8487 8361 8488 8362 8489 8363 8490 8364 8491 8365 8492 8366 8493 8367 8492 8366 8491 8365 8494 2114 8495 8368 8496 8369 8493 8367 8493 8367 8492 8366 8495 8368 8497 8370 8496 8369 8498 8371 8495 8368 8498 8371 8496 8369 8497 8370 8499 8372 8500 8373 8499 8372 8497 8370 8498 8371 8501 8374 8502 8375 8500 8373 8500 8373 8499 8372 8501 8374 8503 8376 8502 8375 8504 8377 8501 8374 8504 8377 8502 8375 8503 8376 8505 8378 8506 8379 8505 8378 8503 8376 8504 8377 8507 8380 8508 8381 8506 8379 8506 8379 8505 8378 8507 8380 8435 8315 8508 8381 8509 8382 8507 8380 8509 8382 8508 8381 8436 8316 8435 8315 8509 8382 8494 2114 8487 8361 8486 8360 8491 8365 8487 8361 8494 2114 8488 8362 8490 8364 8485 8359 8485 8359 8490 8364 8486 8360 8479 8353 8489 8363 8480 8354 8480 8354 8489 8363 8488 8362 8483 8357 8481 8355 8484 8358 8483 8357 8479 8353 8481 8355 8482 8356 8473 8347 8475 8349 8482 8356 8484 8358 8473 8347 8474 8348 8477 8351 8476 8350 8475 8349 8474 8348 8476 8350 8469 499 8468 8343 8478 8352 8477 8351 8469 499 8478 8352 8470 8344 8472 8346 8467 8342 8467 8342 8472 8346 8468 8343 8461 8336 8471 8345 8462 8337 8462 8337 8471 8345 8470 8344 8465 8340 8461 8336 8463 8338 8464 8339 8466 8341 8455 8332 8465 8340 8463 8338 8466 8341 8457 8334 8456 8333 8458 2145 8464 8339 8455 8332 8457 8334 8459 8335 8451 8328 8460 8328 8456 8333 8459 8335 8458 2145 8449 2143 8454 8331 8450 2143 8451 8328 8450 2143 8460 8328 8444 8323 8453 8330 8452 8329 8452 8329 8454 8331 8449 2143 8447 8326 8443 8322 8445 8324 8443 8322 8453 8330 8444 8323 8446 8325 8448 8327 8437 8317 8447 8326 8445 8324 8448 8327 8439 8319 8438 8318 8442 8321 8446 8325 8437 8317 8439 8319 8440 2135 8434 8314 8441 8320 8438 8318 8440 2135 8442 8321 8436 8316 8441 8320 8434 8314 8510 8383 8512 8384 8511 8385 8513 8386 8515 8387 8514 8388 8516 8389 8518 8390 8517 8391 8519 8392 8521 8393 8520 8394 8522 8395 8524 8396 8523 8397 8525 8398 8527 8399 8526 8400 8528 8401 8530 8402 8529 8403 8531 8404 8533 8405 8532 8406 8534 8407 8536 8408 8535 8409 8537 8410 8539 8411 8538 8412 8540 8413 8542 8414 8541 8415 8541 8415 8536 8408 8540 8413 8543 8416 8542 8414 8544 8417 8540 8413 8544 8417 8542 8414 8543 8416 8546 8418 8545 8419 8546 8418 8543 8416 8544 8417 8547 8420 8548 8421 8545 8419 8545 8419 8546 8418 8547 8420 8536 8408 8541 8415 8535 8409 8547 8420 8549 8422 8548 8421 8534 8407 8535 8409 8538 8412 8539 8411 8537 8410 8528 8401 8534 8407 8538 8412 8539 8411 8530 8402 8533 8405 8529 8403 8537 8410 8530 8402 8528 8401 8532 8406 8523 8397 8531 8404 8533 8405 8531 8404 8529 8403 8525 8398 8524 8396 8522 8395 8522 8395 8523 8397 8532 8406 8518 8390 8526 8400 8527 8399 8526 8400 8524 8396 8525 8398 8516 8389 8517 8391 8519 8392 8518 8390 8527 8399 8517 8391 8520 8394 8521 8393 8511 8385 8516 8389 8519 8392 8520 8394 8510 8383 8515 8387 8512 8384 8521 8393 8510 8383 8511 8385 8513 8386 8512 8384 8515 8387 8550 8423 8552 8423 8551 8423 8553 8424 8552 8424 8554 8424 8552 8425 8550 8425 8555 8425 8552 8426 8555 8426 8554 8426 8556 8427 8558 8427 8557 8427 8559 8428 8556 8428 8560 8428 8557 8429 8560 8429 8556 8429 8561 8430 8559 8430 8560 8430 8562 8431 8564 8431 8563 8431 8562 8432 8565 8432 8564 8432 8566 8433 8568 8433 8567 8433 8566 8434 8569 8434 8568 8434 8566 8435 8567 8435 8570 8435 8571 8436 8568 8436 8569 8436 8572 8437 8574 8437 8573 8437 8575 8438 8577 8438 8576 8438 8578 8439 8579 8439 8573 8439 8579 8440 8578 8440 8580 8440 8581 8441 8583 8441 8582 8441 8573 8442 8574 8442 8578 8442 8572 8443 8584 8443 8574 8443 8581 8444 8582 8444 8574 8444 8575 8445 8586 8445 8585 8445 8574 8446 8585 8446 8581 8446 8574 8447 8584 8447 8585 8447 8575 8448 8585 8448 8584 8448 8587 8449 8577 8449 8575 8449 8584 8450 8587 8450 8575 8450 8588 8451 8590 8451 8589 8451 8591 8452 8593 8452 8592 8452 8594 8453 8596 8453 8595 8453 8597 8454 8599 8454 8598 8454 8600 8455 8602 8455 8601 8455 8603 8456 8602 8456 8600 8456 8604 8457 8606 8457 8605 8457 8601 8458 8607 8458 8606 8458 8608 8459 8609 8459 8593 8459 8610 8460 8605 8460 8609 8460 8611 8461 8613 8461 8612 8461 8592 8462 8612 8462 8614 8462 8611 8463 8616 8463 8615 8463 8615 8464 8616 8464 8617 8464 8618 8465 8620 8465 8619 8465 8619 8466 8617 8466 8621 8466 8622 8467 8624 8467 8623 8467 8623 8468 8620 8468 8625 8468 8624 8469 8627 8469 8626 8469 8627 8470 8624 8470 8622 8470 8627 8471 8628 8471 8626 8471 8623 8472 8625 8472 8622 8472 8620 8473 8618 8473 8625 8473 8619 8474 8621 8474 8618 8474 8617 8475 8616 8475 8621 8475 8613 8476 8611 8476 8615 8476 8593 8477 8612 8477 8592 8477 8612 8478 8613 8478 8614 8478 8593 8479 8591 8479 8608 8479 8610 8480 8609 8480 8608 8480 8604 8481 8605 8481 8610 8481 8607 8482 8605 8482 8606 8482 8602 8483 8607 8483 8601 8483 8600 8484 8594 8484 8603 8484 8629 8485 8595 8485 8596 8485 8595 8486 8603 8486 8594 8486 8629 8487 8597 8487 8598 8487 8597 8488 8629 8488 8596 8488 8588 8489 8589 8489 8599 8489 8589 8490 8598 8490 8599 8490 8630 8491 8632 8491 8631 8491 8633 8492 8635 8492 8634 8492 8630 8493 8636 8493 8632 8493 8637 8494 8633 8494 8638 8494 8635 8495 8633 8495 8637 8495 8639 8496 8640 8496 8634 8496 8641 8497 8634 8497 8640 8497 8633 8498 8634 8498 8641 8498 8636 8499 8642 8499 8632 8499 8643 8500 8637 8500 8638 8500 8632 8501 8642 8501 8643 8501 8643 8502 8642 8502 8637 8502 8644 8503 8646 8503 8645 8503 8645 8504 8647 8504 8644 8504 8648 8505 8650 8505 8649 8505 8649 8506 8651 8506 8648 8506 8652 8507 8654 8507 8653 8507 8653 8508 8655 8508 8652 8508 8656 8509 8658 8509 8657 8509 8657 8510 8659 8510 8656 8510 8660 8511 8662 8511 8661 8511 8661 8512 8663 8512 8660 8512 8664 8513 8666 8513 8665 8513 8667 2189 8668 2189 8664 2189 8669 8514 8666 8514 8670 8514 8669 8515 8665 8515 8666 8515 8664 8516 8665 8516 8667 8516 8671 8517 8673 8517 8672 8517 8672 8518 8674 8518 8671 8518 8675 1101 8677 1101 8676 1101 8675 2860 8679 2860 8678 2860 8676 8519 8681 8519 8680 8519 8676 8520 8677 8520 8681 8520 8679 8521 8675 8521 8682 8521 8675 8522 8678 8522 8677 8522 8683 2525 8685 2525 8684 2525 8684 8434 8686 8434 8683 8434 8687 2472 8689 2472 8688 2472 8688 8523 8690 8523 8687 8523 8688 8514 8689 8514 8691 8514 8692 8524 8694 8524 8693 8524 8695 8525 8694 8525 8692 8525 8696 8526 8698 8526 8697 8526 8699 8527 8700 8527 8694 8527 8698 8528 8702 8528 8701 8528 8693 8529 8694 8529 8700 8529 8703 8530 8705 8530 8704 8530 8696 8531 8706 8531 8699 8531 8699 8532 8694 8532 8696 8532 8707 8533 8696 8533 8697 8533 8706 8534 8696 8534 8707 8534 8698 8535 8709 8535 8708 8535 8697 8536 8698 8536 8708 8536 8709 8537 8698 8537 8701 8537 8702 8538 8711 8538 8710 8538 8701 8539 8702 8539 8710 8539 8704 8540 8712 8540 8702 8540 8711 8541 8702 8541 8712 8541 8704 8542 8705 8542 8713 8542 8704 8543 8713 8543 8712 8543 8714 2651 8715 2651 8704 2651 8703 8544 8704 8544 8715 8544 8716 8545 8717 8545 8714 8545 8714 8546 8717 8546 8715 8546 8714 8547 8718 8547 8716 8547 8714 8548 8719 8548 8718 8548 8720 8549 8722 8549 8721 8549 8721 8550 8723 8550 8720 8550 8721 1180 8722 1180 8724 1180 8725 2495 8727 2495 8726 2495 8726 8551 8728 8551 8725 8551 8729 8552 8731 8552 8730 8552 8730 8553 8732 8553 8729 8553 8733 8554 8735 8554 8734 8554 8734 8555 8736 8555 8733 8555 8737 8556 8739 8556 8738 8556 8738 2404 8742 2404 8741 2404 8742 8557 8738 8557 8739 8557 8740 8558 8739 8558 8737 8558 8743 8559 8745 8559 8744 8559 8746 8560 8748 8560 8747 8560 8749 8561 8743 8561 8744 8561 8748 8562 8751 8562 8750 8562 8752 8563 8754 8563 8753 8563 8755 8564 8752 8564 8756 8564 8757 8565 8744 8565 8758 8565 8757 8566 8749 8566 8744 8566 8746 8567 8759 8567 8758 8567 8758 8568 8744 8568 8746 8568 8760 8569 8746 8569 8747 8569 8759 8570 8746 8570 8760 8570 8761 8571 8748 8571 8750 8571 8747 8572 8748 8572 8761 8572 8751 8573 8763 8573 8762 8573 8750 8574 8751 8574 8762 8574 8752 8575 8755 8575 8751 8575 8763 8576 8751 8576 8755 8576 8752 8577 8753 8577 8756 8577 8764 8578 8766 8578 8765 8578 8764 8579 8754 8579 8766 8579 8767 8580 8766 8580 8768 8580 8767 8581 8765 8581 8766 8581 8766 8582 8754 8582 8752 8582 8769 8583 8771 8583 8770 8583 8771 8584 8769 8584 8772 8584 8773 8585 8772 8585 8774 8585 8769 8586 8774 8586 8772 8586 8774 8587 8775 8587 8773 8587 8776 8588 8778 8588 8777 8588 8777 8589 8779 8589 8776 8589 8780 8590 8782 8590 8781 8590 8781 8591 8783 8591 8780 8591 8784 8592 8786 8593 8785 8594 8787 8595 8789 8596 8788 749 8790 750 8787 8595 8788 749 8791 8597 8793 8598 8792 8599 8790 750 8794 8600 8787 8595 8793 8598 8791 8597 8795 8601 8784 8592 8797 8602 8796 8603 8797 8602 8784 8592 8785 8594 8786 8593 8795 8601 8785 8594 8786 8593 8793 8598 8795 8601 8798 745 8800 8604 8799 8605 8801 8606 8803 8607 8802 739 8804 8608 8806 748 8805 8609 8807 8610 8809 743 8808 8611 8788 749 8789 8596 8810 752 8811 8612 8813 8613 8812 8614 8814 756 8816 8615 8815 8616 8794 8600 8790 750 8814 756 8817 8617 8819 8618 8818 8619 8820 8620 8816 8615 8821 8621 8822 8622 8824 8623 8823 8624 8817 8617 8824 8623 8825 8625 8823 8624 8827 8626 8826 8627 8826 8627 8822 8622 8823 8624 8828 8628 8829 8629 8827 8626 8826 8627 8827 8626 8829 8629 8830 8630 8828 8628 8831 8631 8828 8628 8830 8630 8829 8629 8825 8625 8824 8623 8822 8622 8822 8622 8821 8621 8825 8625 8820 8620 8821 8621 8822 8622 8824 8623 8817 8617 8818 8619 8814 756 8815 8616 8794 8600 8816 8615 8820 8620 8815 8616 8819 8618 8833 8632 8832 8633 8832 8633 8818 8619 8819 8618 8834 8631 8832 8633 8833 8632 8789 8596 8813 8613 8810 752 8835 747 8811 8612 8812 8614 8811 8612 8810 752 8813 8613 8805 8609 8806 748 8835 747 8835 747 8812 8614 8805 8609 8808 8611 8836 744 8804 8608 8836 744 8806 748 8804 8608 8807 8610 8798 745 8809 743 8808 8611 8809 743 8836 744 8837 8634 8799 8605 8800 8604 8800 8604 8798 745 8807 8610 8837 8634 8801 8606 8802 739 8802 739 8799 8605 8837 8634 8792 8599 8803 8607 8791 8597 8791 8597 8803 8607 8801 8606 8838 8635 8792 8599 8839 8636 8792 8599 8838 8635 8803 8607 8839 8636 8841 8637 8840 8638 8840 8638 8838 8635 8839 8636 8840 8638 8841 8637 8842 8639 8841 8637 8843 8603 8842 8639 8844 8640 8846 8640 8845 8640 8844 8641 8847 8641 8846 8641 8846 8642 8847 8642 8848 8642 8844 8643 8845 8643 8849 8643 8850 8644 8852 8644 8851 8644 8850 8645 8853 8645 8852 8645 8854 8646 8856 8646 8855 8646 8857 8647 8859 8647 8858 8647 8857 8648 8856 8648 8859 8648 8859 8649 8856 8649 8854 8649 8860 8650 8862 8650 8861 8650 8863 8651 8865 8652 8864 8653 8866 8654 8868 8655 8867 8656 8861 8657 8862 8657 8869 8657 8862 8658 8870 8658 8868 8658 8871 8659 8873 8660 8872 8661 8874 8662 8876 8663 8875 8664 8873 8665 8878 8665 8877 8665 8879 8666 8863 8666 8880 8666 8881 8667 8883 8668 8882 8669 8873 8670 8877 8670 8884 8670 8885 8671 8886 8671 8880 8671 8880 8672 8888 8672 8887 8672 8869 8673 8890 8674 8889 8675 8891 8676 8868 8655 8866 8654 8892 8677 8893 8678 8871 8659 8892 8677 8894 8679 8891 8676 8866 8680 8895 8680 8891 8680 8875 8664 8896 8681 8882 8669 8897 8682 8899 8682 8898 8682 8895 8683 8892 8677 8891 8676 8891 8676 8890 8674 8868 8655 8900 8684 8902 8685 8901 8686 8903 8687 8905 8688 8904 8689 8906 8690 8908 8691 8907 8692 8907 8692 8905 8688 8906 8690 8889 8675 8890 8674 8903 8687 8906 8690 8905 8688 8903 8687 8904 8689 8889 8675 8903 8687 8909 8693 8872 8661 8884 8694 8910 8695 8885 8695 8880 8695 8898 8696 8911 8696 8897 8696 8897 8697 8912 8697 8899 8697 8880 8698 8914 8698 8913 8698 8915 8699 8917 8700 8916 8701 8897 8702 8919 8702 8918 8702 8911 8703 8919 8703 8897 8703 8920 8704 8921 8704 8880 8704 8897 8705 8922 8705 8916 8705 8918 8706 8922 8706 8897 8706 8880 8707 8924 8708 8923 8709 8897 8710 8916 8701 8917 8700 8924 8708 8917 8700 8925 8711 8915 8699 8925 8711 8917 8700 8924 8708 8926 8712 8923 8709 8924 8708 8925 8711 8926 8712 8880 8713 8923 8713 8920 8713 8880 8714 8921 8714 8914 8714 8910 8715 8880 8715 8927 8715 8880 8716 8913 8716 8927 8716 8928 8717 8879 8717 8880 8717 8880 8718 8887 8718 8928 8718 8909 8693 8930 8719 8929 8720 8874 8662 8875 8664 8931 8721 8863 8651 8875 8664 8882 8669 8932 8722 8875 8664 8876 8663 8875 8664 8863 8651 8879 8723 8865 8652 8863 8651 8882 8669 8873 8724 8884 8724 8872 8724 8929 8720 8933 8725 8909 8693 8934 8726 8897 8710 8909 8693 8893 8678 8873 8660 8871 8659 8935 8727 8936 8727 8897 8727 8897 8728 8934 8728 8935 8728 8937 8729 8897 8729 8936 8729 8938 8730 8897 8730 8939 8730 8897 8731 8937 8731 8939 8731 8912 8732 8897 8732 8938 8732 8881 8667 8882 8669 8896 8681 8875 8664 8940 8733 8931 8721 8930 8719 8909 8693 8941 8734 8896 8681 8875 8664 8884 8694 8884 8694 8875 8664 8909 8693 8941 8734 8909 8693 8875 8664 8871 8659 8872 8661 8909 8693 8865 8652 8882 8669 8883 8668 8941 8734 8875 8664 8932 8722 8933 8725 8934 8726 8909 8693 8909 8693 8897 8710 8942 8735 8871 8659 8909 8693 8942 8735 8893 8678 8892 8677 8895 8683 8943 8736 8871 8659 8942 8735 8943 8736 8892 8677 8871 8659 8894 8679 8892 8677 8943 8736 8868 8655 8890 8674 8869 8673 8862 8737 8868 8737 8869 8737 8868 8738 8870 8738 8867 8738 8904 8689 8944 8739 8889 8675 8888 8740 8880 8740 8886 8740 8875 8664 8879 8723 8940 8733 8897 8741 8945 8741 8942 8741 8942 8735 8945 8742 8943 8736 8945 8742 8946 8743 8943 8736 8943 8736 8946 8743 8894 8679 8894 8679 8946 8743 8947 8744 8891 8676 8894 8679 8890 8674 8947 8744 8948 8745 8890 8674 8906 8690 8903 8687 8949 8746 8903 8687 8890 8674 8948 8745 8906 8690 8949 8746 8908 8691 8948 8745 8947 8744 8950 8747 8947 8744 8890 8674 8894 8679 8902 8685 8949 8746 8950 8747 8903 8687 8948 8745 8949 8746 8949 8746 8948 8745 8950 8747 8908 8691 8949 8746 8951 8748 8900 8684 8949 8746 8902 8685 8949 8746 8900 8684 8951 8748 8952 8749 8954 8749 8953 8749 8955 8750 8957 8750 8956 8750 8958 8751 8959 8751 8953 8751 8960 8752 8953 8752 8961 8752 8962 8753 8964 8753 8963 8753 8965 8754 8966 8754 8953 8754 8953 8755 8966 8755 8952 8755 8967 8756 8968 8756 8953 8756 8953 8757 8968 8757 8965 8757 8969 8758 8970 8758 8953 8758 8953 8759 8970 8759 8967 8759 8953 8760 8959 8760 8971 8760 8953 8761 8971 8761 8969 8761 8972 6 8958 6 8963 6 8953 8762 8963 8762 8958 8762 8973 6 8974 6 8963 6 8963 6 8974 6 8972 6 8975 8763 8976 8763 8963 8763 8963 6 8976 6 8973 6 8977 8764 8978 8764 8963 8764 8963 6 8978 6 8975 6 8963 8765 8964 8765 8977 8765 8962 8766 8963 8766 8955 8766 8957 8767 8980 8767 8979 8767 8963 8768 8957 8768 8955 8768 8981 8769 8982 8769 8957 8769 8957 8770 8982 8770 8956 8770 8983 8771 8984 8771 8957 8771 8957 8772 8984 8772 8981 8772 8957 8773 8979 8773 8983 8773 8960 8774 8985 8774 8957 8774 8980 8775 8957 8775 8985 8775 8986 6 8987 6 8960 6 8960 8776 8987 8776 8985 8776 8988 6 8989 6 8960 6 8960 8777 8989 8777 8986 8777 8990 8778 8991 8778 8960 8778 8960 8779 8991 8779 8988 8779 8961 8780 8992 8780 8960 8780 8960 8781 8992 8781 8990 8781 8953 8782 8954 8782 8961 8782 8993 8783 8995 8784 8994 8785 8995 8784 8997 8786 8996 8787 8994 8785 8995 8784 8996 8787 8998 8788 8997 8786 8999 8789 8995 8784 8999 8789 8997 8786 8998 8788 9001 8790 9000 8791 9001 8790 8998 8788 8999 8789 9002 8792 9003 8793 9000 8791 9000 8791 9001 8790 9002 8792 9004 8794 9003 8793 9005 8795 9002 8792 9005 8795 9003 8793 9004 8794 9007 8796 9006 8797 9007 8796 9004 8794 9005 8795 9008 8798 9009 8799 9006 8797 9006 8797 9007 8796 9008 8798 9010 8800 9012 8801 9011 8802 9008 8798 9012 8801 9009 8799 9013 8803 9011 8802 9014 8804 9011 8802 9013 8803 9010 8800 9015 8805 9013 8803 9014 8804 9010 8800 9009 8799 9012 8801 8993 8783 8994 8785 9016 8806 9017 8807 9016 8806 9018 8808 9016 8806 9017 8807 8993 8783 9018 8808 9020 8809 9019 8810 9019 8810 9017 8807 9018 8808 9021 8811 9022 8812 9020 8809 9019 8810 9020 8809 9022 8812 9023 8813 9021 8811 9024 8814 9021 8811 9023 8813 9022 8812 9024 8814 9026 8815 9025 8816 9025 8816 9023 8813 9024 8814 9027 8817 9028 8818 9026 8815 9025 8816 9026 8815 9028 8818 9029 8819 9027 8817 9030 8820 9027 8817 9029 8819 9028 8818 9030 8820 9032 8821 9031 8822 9031 8822 9029 8819 9030 8820 9031 8822 9032 8821 9033 8823 9032 8821 9034 8824 9033 8823 9035 8825 9037 8826 9036 8827 9038 8828 9040 8829 9039 8830 9041 8831 9043 8832 9042 8833 9044 8834 9046 8835 9045 8836 9047 8837 9049 8838 9048 8839 9050 8840 9052 516 9051 8841 9053 8842 9055 8843 9054 8844 9056 8845 9058 8846 9057 8847 9059 8848 9061 8849 9060 8850 9062 8851 9064 8852 9063 8853 9065 8854 9063 8853 9064 8852 9062 8851 9067 8855 9066 8856 9067 8855 9062 8851 9063 8853 9068 8857 9069 8858 9066 8856 9066 8856 9067 8855 9068 8857 9070 8859 9069 8858 9071 8860 9068 8857 9071 8860 9069 8858 9072 8861 9070 8859 9071 8860 9065 8854 9056 8845 9057 8847 9065 8854 9064 8852 9056 8845 9058 8846 9061 8849 9059 8848 9057 8847 9058 8846 9059 8848 9051 8841 9052 516 9060 8850 9061 8849 9051 8841 9060 8850 9053 8842 9054 8844 9050 8840 9050 8840 9054 8844 9052 516 9044 8834 9055 8843 9046 8835 9046 8835 9055 8843 9053 8842 9049 8838 9045 8836 9048 8839 9049 8838 9044 8834 9045 8836 9047 8837 9038 8828 9039 8830 9047 8837 9048 8839 9038 8828 9040 8829 9041 8831 9042 8833 9039 8830 9040 8829 9042 8833 9035 8825 9036 8827 9043 8832 9041 8831 9035 8825 9043 8832 9073 8862 9074 8863 9075 8864 9076 8865 9077 8866 9078 8867 9079 8868 9075 8864 9080 8869 9074 8863 9080 8869 9075 8864 9081 8870 9082 8871 9079 8868 9079 8868 9080 8869 9081 8870 9082 8871 9083 8872 9084 8873 9083 8872 9082 8871 9081 8870 9085 8874 9084 8873 9086 8875 9083 8872 9086 8875 9084 8873 9087 8876 9088 8877 9085 8874 9085 8874 9086 8875 9087 8876 9088 8877 9089 8878 9090 8879 9089 8878 9088 8877 9087 8876 9091 8880 9090 8879 9092 8881 9089 8878 9092 8881 9090 8879 9093 8882 9094 8883 9091 8880 9091 8880 9092 8881 9093 8882 9095 8884 9094 8883 9093 8882 9095 8884 9096 8885 9094 8883 9074 8863 9073 8862 9097 8886 9098 8887 9099 8888 9097 8886 9097 8886 9073 8862 9098 8887 9099 8888 9100 8889 9101 8890 9100 8889 9099 8888 9098 8887 9102 8891 9101 8890 9103 8892 9100 8889 9103 8892 9101 8890 9104 8893 9105 8894 9102 8891 9102 8891 9103 8892 9104 8893 9105 8894 9106 8895 9107 8896 9106 8895 9105 8894 9104 8893 9108 8897 9107 8896 9109 8898 9106 8895 9109 8898 9107 8896 9110 8899 9111 8900 9108 8897 9108 8897 9109 8898 9110 8899 9111 8900 9112 8901 9113 8902 9112 8901 9111 8900 9110 8899 9112 8901 9077 8866 9113 8902 9114 8903 9115 8867 9116 8903 9113 8902 9077 8866 9076 8865 9117 8904 9118 8905 9119 8906 9120 8907 9121 8907 9122 8905 9123 8908 9124 8909 9125 8909 9126 8910 9127 8908 9128 8910 9129 8911 9130 8911 9131 8912 9132 8912 9133 8913 9134 8913 9135 8914 9136 8915 9137 8914 9138 8916 9139 8916 9140 8915 9141 8917 9142 8918 9143 8919 9135 8914 9143 8919 9142 8918 9141 8917 9144 8920 9145 8921 9145 8921 9142 8918 9141 8917 9146 8922 9144 8920 9147 8923 9144 8920 9146 8922 9145 8921 9096 8885 9148 8923 9147 8923 9146 8922 9147 8923 9148 8923 9095 8884 9148 8923 9096 8885 9136 8915 9140 8915 9137 8914 9135 8914 9137 8914 9143 8919 9138 8916 9130 8911 9139 8916 9136 8915 9138 8916 9140 8915 9129 8911 9131 8912 9132 8912 9139 8916 9130 8911 9129 8911 9134 8913 9133 8913 9125 8909 9132 8912 9131 8912 9133 8913 9127 8908 9124 8909 9123 8908 9124 8909 9134 8913 9125 8909 9117 8904 9126 8910 9128 8910 9128 8910 9127 8908 9123 8908 9118 8905 9122 8905 9119 8906 9117 8904 9119 8906 9126 8910 9120 8907 9114 8903 9121 8907 9118 8905 9120 8907 9122 8905 9116 8903 9115 8867 9078 8867 9121 8907 9114 8903 9116 8903 9076 8865 9078 8867 9115 8867 9149 8924 9150 8924 9151 8924 9152 8925 9153 8925 9154 8925 9155 8926 9150 8926 9156 8926 9157 8927 9158 8927 9149 8927 9159 8928 9156 8928 9160 8928 9161 8929 9158 8929 9162 8929 9163 8930 9161 8930 9164 8930 9165 8931 9163 8931 9166 8931 9167 8932 9168 8932 9160 8932 9165 8933 9169 8933 9170 8933 9171 8934 9167 8934 9172 8934 9173 8935 9174 8935 9175 8935 9176 8936 9177 8936 9170 8936 9178 8937 9179 8937 9153 8937 9180 8938 9181 8938 9182 8938 9183 8939 9184 8939 9185 8939 9186 8940 9152 8940 9187 8940 9188 8941 9189 8941 9190 8941 9191 8942 9192 8942 9193 8942 9189 8943 9194 8943 9195 8943 9196 8944 9197 8944 9194 8944 9180 8945 9182 8945 9198 8945 9199 8946 9196 8946 9181 8946 9185 8947 9200 8947 9201 8947 9202 8948 9200 8948 9188 8948 9203 8949 9204 8949 9205 8949 9206 8950 9207 8950 9208 8950 9209 8951 9210 8951 9211 8951 9184 8952 9212 8952 9186 8952 9213 8953 9214 8953 9178 8953 9211 8954 9215 8954 9209 8954 9174 8955 9216 8955 9213 8955 9217 8956 9218 8956 9177 8956 9219 8957 9217 8957 9220 8957 9171 8958 9221 8958 9222 8958 9175 8959 9222 8959 9223 8959 9210 8960 9224 8960 9211 8960 9224 8961 9210 8961 9205 8961 9215 8962 9219 8962 9220 8962 9215 8963 9220 8963 9209 8963 9219 8964 9218 8964 9217 8964 9177 8965 9176 8965 9217 8965 9170 8966 9169 8966 9176 8966 9165 8967 9166 8967 9169 8967 9163 8968 9164 8968 9166 8968 9161 8969 9162 8969 9164 8969 9158 8970 9157 8970 9162 8970 9149 8971 9151 8971 9157 8971 9150 8972 9155 8972 9151 8972 9156 8973 9159 8973 9155 8973 9160 8974 9168 8974 9159 8974 9160 8975 9172 8975 9167 8975 9172 8976 9221 8976 9171 8976 9221 8977 9223 8977 9222 8977 9223 8978 9173 8978 9175 8978 9173 8979 9216 8979 9174 8979 9216 8980 9214 8980 9213 8980 9214 8981 9179 8981 9178 8981 9179 8982 9154 8982 9153 8982 9154 8983 9187 8983 9152 8983 9186 8984 9212 8984 9152 8984 9184 8985 9183 8985 9212 8985 9185 8986 9201 8986 9183 8986 9200 8987 9202 8987 9201 8987 9188 8988 9190 8988 9202 8988 9189 8989 9195 8989 9190 8989 9194 315 9197 315 9195 315 9196 8990 9199 8990 9197 8990 9181 8991 9180 8991 9199 8991 9182 8992 9193 8992 9198 8992 9191 8993 9206 8993 9192 8993 9182 8994 9191 8994 9193 8994 9208 8995 9207 8995 9203 8995 9192 8996 9206 8996 9208 8996 9205 8997 9204 8997 9224 8997 9203 8998 9207 8998 9204 8998 9225 8999 9226 8999 9227 8999 9228 9000 9229 9000 9230 9000 9231 9001 9232 9001 9227 9001 9233 9002 9234 9002 9226 9002 9231 9003 9235 9003 9236 9003 9234 9004 9237 9004 9238 9004 9239 9005 9238 9005 9240 9005 9241 9006 9239 9006 9242 9006 9243 9007 9235 9007 9244 9007 9245 9008 9242 9008 9246 9008 9247 9009 9248 9009 9244 9009 9249 9010 9250 9010 9251 9010 9247 9011 9251 9011 9252 9011 9253 9012 9254 9012 9255 9012 9256 9013 9257 9013 9258 9013 9259 9014 9260 9014 9261 9014 9262 9015 9263 9015 9229 9015 9264 9016 9265 9016 9266 9016 9267 9017 9268 9017 9269 9017 9270 9018 9271 9018 9272 9018 9273 9019 9274 9019 9271 9019 9275 9020 9264 9020 9276 9020 9277 9021 9276 9021 9270 9021 9269 9022 9278 9022 9279 9022 9280 9023 9273 9023 9279 9023 9281 9024 9282 9024 9283 9024 9284 9025 9285 9025 9286 9025 9255 9026 9287 9026 9288 9026 9267 9027 9289 9027 9290 9027 9291 9028 9263 9028 9292 9028 9288 9029 9253 9029 9255 9029 9256 9030 9291 9030 9293 9030 9294 9031 9295 9031 9250 9031 9265 9032 9264 9032 9296 9032 9246 9033 9297 9033 9298 9033 9258 9034 9299 9034 9297 9034 9261 9035 9288 9035 9287 9035 9230 9036 9289 9036 9300 9036 9254 9037 9295 9037 9294 9037 9254 9038 9253 9038 9295 9038 9294 9039 9250 9039 9249 9039 9251 9040 9250 9040 9252 9040 9247 9041 9252 9041 9248 9041 9244 9042 9248 9042 9243 9042 9235 9043 9243 9043 9236 9043 9231 9044 9236 9044 9232 9044 9227 9045 9232 9045 9225 9045 9226 9046 9225 9046 9233 9046 9234 9047 9233 9047 9237 9047 9238 9048 9237 9048 9240 9048 9238 9049 9239 9049 9241 9049 9241 9050 9242 9050 9245 9050 9245 9051 9246 9051 9298 9051 9298 9052 9297 9052 9299 9052 9299 9053 9258 9053 9257 9053 9257 9054 9256 9054 9293 9054 9293 9055 9291 9055 9292 9055 9292 9056 9263 9056 9262 9056 9262 9057 9229 9057 9228 9057 9228 9058 9230 9058 9300 9058 9289 9059 9230 9059 9290 9059 9267 9060 9290 9060 9268 9060 9269 9061 9268 9061 9278 9061 9279 9062 9278 9062 9280 9062 9273 9063 9280 9063 9274 9063 9271 9064 9274 9064 9272 9064 9270 9065 9272 9065 9277 9065 9276 9066 9277 9066 9275 9066 9264 9067 9275 9067 9296 9067 9266 9068 9265 9068 9285 9068 9284 9069 9286 9069 9281 9069 9266 9070 9285 9070 9284 9070 9282 9071 9260 9071 9283 9071 9286 9072 9282 9072 9281 9072 9261 9073 9287 9073 9259 9073 9260 9074 9259 9074 9283 9074 9301 8901 9302 9075 9303 9075 9304 9076 9305 8898 9306 8898 9307 9077 9308 8901 9309 9077 9310 9078 9311 8889 9312 9078 9313 8895 9314 9079 9315 9079 9316 9080 9317 9080 9318 8864 9319 9081 9320 8889 9321 8887 9322 9082 9323 8871 9324 8871 9325 9083 9326 9083 9327 8864 9328 8877 9329 8879 9330 8877 9331 9082 9332 8874 9333 8874 9334 9084 9335 9084 9336 8885 9337 8880 9338 8879 9339 9085 9340 9086 9341 9087 9342 9088 9343 9089 9344 9089 9345 8885 9346 9090 9347 9091 9348 9092 9349 9093 9350 9094 9351 9095 9352 9096 9353 9097 9354 9098 9355 9099 9356 9100 9357 9101 9358 9102 9359 9103 9360 9104 9359 9103 9358 9102 9361 9105 9362 9106 9363 9107 9360 9104 9360 9104 9359 9103 9362 9106 9364 9108 9363 9107 9365 9109 9362 9106 9365 9109 9363 9107 9364 9108 9366 9110 9367 9111 9366 9110 9364 9108 9365 9109 9368 9112 9369 9113 9367 9111 9367 9111 9366 9110 9368 9112 9370 9114 9369 9113 9371 9115 9368 9112 9371 9115 9369 9113 9370 9114 9372 9116 9373 9117 9372 9116 9370 9114 9371 9115 9374 9118 9375 9119 9373 9117 9373 9117 9372 9116 9374 9118 9302 9075 9375 9119 9376 9119 9374 9118 9376 9119 9375 9119 9303 9075 9302 9075 9376 9119 9361 9105 9354 9098 9353 9097 9358 9102 9354 9098 9361 9105 9355 9099 9357 9101 9352 9096 9352 9096 9357 9101 9353 9097 9346 9090 9356 9100 9347 9091 9347 9091 9356 9100 9355 9099 9350 9094 9348 9092 9351 9095 9350 9094 9346 9090 9348 9092 9349 9093 9340 9086 9342 9088 9349 9093 9351 9095 9340 9086 9341 9087 9344 9089 9343 9089 9342 9088 9341 9087 9343 9089 9336 8885 9335 9084 9345 8885 9344 9089 9336 8885 9345 8885 9337 8880 9339 9085 9334 9084 9334 9084 9339 9085 9335 9084 9328 8877 9338 8879 9329 8879 9329 8879 9338 8879 9337 8880 9332 8874 9328 8877 9330 8877 9331 9082 9333 8874 9322 9082 9332 8874 9330 8877 9333 8874 9324 8871 9323 8871 9325 9083 9331 9082 9322 9082 9324 8871 9326 9083 9318 8864 9327 8864 9323 8871 9326 9083 9325 9083 9316 9080 9321 8887 9317 9080 9318 8864 9317 9080 9327 8864 9311 8889 9320 8889 9319 9081 9319 9081 9321 8887 9316 9080 9314 9079 9310 9078 9312 9078 9310 9078 9320 8889 9311 8889 9313 8895 9315 9079 9304 9076 9314 9079 9312 9078 9315 9079 9306 8898 9305 8898 9309 9077 9313 8895 9304 9076 9306 8898 9307 9077 9301 8901 9308 8901 9305 8898 9307 9077 9309 9077 9303 9075 9308 8901 9301 8901

+
+ + + +

2056 1584 2057 1584 2058 1584 2059 1585 2058 1585 2057 1585 2060 1586 2056 1586 2058 1586 2057 1587 2061 1587 2059 1587 2062 1588 2063 1588 2064 1588 2062 1589 2065 1589 2063 1589 2066 1590 2067 1590 2068 1590 2066 1591 2069 1591 2067 1591 2070 1592 2071 1592 2072 1592 2070 1593 2073 1593 2071 1593 2074 1594 2075 1594 2076 1594 2074 1595 2077 1595 2075 1595 2078 1596 2079 1596 2080 1596 2078 1597 2081 1597 2079 1597 2082 1598 2083 1598 2084 1598 2082 1599 2085 1599 2083 1599 2086 1600 2087 1600 2088 1600 2089 1601 2090 1601 2091 1601 2087 1602 2092 1602 2088 1602 2086 28 2093 28 2087 28 2092 28 2087 28 2094 28 2093 1603 2086 1603 2095 1603 2095 1604 2096 1604 2093 1604 2097 1605 2093 1605 2096 1605 2098 28 2094 28 2087 28 2097 28 2099 28 2093 28 2100 28 2087 28 2101 28 2090 1606 2102 1606 2103 1606 2090 1607 2104 1607 2101 1607 2089 1608 2105 1608 2090 1608 2106 28 2107 28 2108 28 2091 1609 2109 1609 2110 1609 2111 1610 2106 1610 2112 1610 2091 1611 2113 1611 2114 1611 2115 1612 2116 1612 2117 1612 2118 1613 2091 1613 2115 1613 2119 1614 2118 1614 2115 1614 2117 28 2120 28 2115 28 2119 1615 2115 1615 2120 1615 2109 1616 2091 1616 2121 1616 2121 1617 2091 1617 2114 1617 2106 1618 2111 1618 2115 1618 2106 1619 2122 1619 2112 1619 2110 1620 2089 1620 2091 1620 2123 1621 2124 1621 2090 1621 2125 1622 2122 1622 2106 1622 2124 1623 2102 1623 2090 1623 2106 1624 2126 1624 2127 1624 2106 1625 2127 1625 2107 1625 2090 1626 2101 1626 2087 1626 2103 1627 2104 1627 2090 1627 2099 28 2128 28 2093 28 2093 28 2128 28 2126 28 2098 1628 2087 1628 2100 1628 2105 1629 2123 1629 2090 1629 2118 1630 2113 1630 2091 1630 2111 1631 2129 1631 2115 1631 2116 1632 2115 1632 2129 1632 2093 1633 2126 1633 2106 1633 2125 28 2106 28 2108 28 2130 1634 2131 1635 2132 1635 2133 1636 2134 1636 2135 1637 2136 1638 2132 1635 2137 1638 2131 1635 2137 1638 2132 1635 2138 1639 2139 1639 2136 1638 2136 1638 2137 1638 2138 1639 2139 1639 2140 1640 2141 1640 2140 1640 2139 1639 2138 1639 2142 1641 2141 1640 2143 1641 2140 1640 2143 1641 2141 1640 2144 1642 2145 1642 2142 1641 2142 1641 2143 1641 2144 1642 2145 1642 2146 1643 2147 1643 2146 1643 2145 1642 2144 1642 2148 1644 2147 1643 2149 1644 2146 1643 2149 1644 2147 1643 2150 1645 2151 1645 2148 1644 2148 1644 2149 1644 2150 1645 2152 1646 2151 1645 2150 1645 2152 1646 2153 1646 2151 1645 2131 1635 2130 1634 2154 1634 2155 1647 2156 1647 2154 1634 2154 1634 2130 1634 2155 1647 2156 1647 2157 1648 2158 1648 2157 1648 2156 1647 2155 1647 2159 1649 2158 1648 2160 1649 2157 1648 2160 1649 2158 1648 2161 1650 2162 1650 2159 1649 2159 1649 2160 1649 2161 1650 2162 1650 2163 1651 2164 1651 2163 1651 2162 1650 2161 1650 2165 1652 2164 1651 2166 1652 2163 1651 2166 1652 2164 1651 2167 1653 2168 1653 2165 1652 2165 1652 2166 1652 2167 1653 2168 1653 2169 1654 2170 1654 2169 1654 2168 1653 2167 1653 2169 1654 2134 1636 2170 1654 2171 1655 2172 1637 2173 1655 2170 1654 2134 1636 2133 1636 2174 1656 2175 1657 2176 1656 2177 1658 2178 1658 2179 1657 2180 1583 2181 1659 2182 1659 2183 499 2184 1583 2185 499 2186 1660 2187 1660 2188 1661 2189 1661 2190 1097 2191 1097 2192 1662 2193 1663 2194 1662 2195 1664 2196 1664 2197 1663 2198 1665 2199 1666 2200 1666 2192 1662 2200 1666 2199 1666 2198 1665 2201 1667 2202 1665 2202 1665 2199 1666 2198 1665 2203 1667 2201 1667 2204 1668 2201 1667 2203 1667 2202 1665 2153 1646 2205 1668 2204 1668 2203 1667 2204 1668 2205 1668 2152 1646 2205 1668 2153 1646 2193 1663 2197 1663 2194 1662 2192 1662 2194 1662 2200 1666 2195 1664 2187 1660 2196 1664 2193 1663 2195 1664 2197 1663 2186 1660 2188 1661 2189 1661 2196 1664 2187 1660 2186 1660 2191 1097 2190 1097 2182 1659 2189 1661 2188 1661 2190 1097 2184 1583 2181 1659 2180 1583 2181 1659 2191 1097 2182 1659 2174 1656 2183 499 2185 499 2185 499 2184 1583 2180 1583 2175 1657 2179 1657 2176 1656 2174 1656 2176 1656 2183 499 2177 1658 2171 1655 2178 1658 2175 1657 2177 1658 2179 1657 2173 1655 2172 1637 2135 1637 2178 1658 2171 1655 2173 1655 2133 1636 2135 1637 2172 1637 2206 6 2207 6 2208 6 2209 6 2210 6 2211 6 2210 6 2212 6 2213 6 2209 6 2214 6 2215 6 2216 1669 2212 1669 2217 1669 2218 1670 2219 1670 2215 1670 2220 1671 2217 1671 2221 1671 2222 6 2219 6 2223 6 2224 1672 2225 1672 2221 1672 2222 6 2226 6 2206 6 2227 6 2224 6 2228 6 2229 1673 2230 1673 2231 1673 2232 1674 2233 1674 2234 1674 2235 1675 2236 1675 2237 1675 2238 1676 2239 1676 2240 1676 2241 1677 2242 1677 2243 1677 2244 6 2245 6 2246 6 2247 1678 2248 1678 2242 1678 2249 1679 2247 1679 2250 1679 2251 1680 2252 1680 2253 1680 2250 1681 2254 1681 2255 1681 2256 1682 2241 1682 2257 1682 2258 6 2259 6 2260 6 2256 1683 2261 1683 2237 1683 2240 1684 2262 1684 2238 1684 2263 1685 2262 1685 2264 1685 2240 6 2239 6 2229 6 2265 1686 2266 1686 2267 1686 2268 1687 2269 1687 2270 1687 2229 1688 2239 1688 2230 1688 2231 6 2271 6 2272 6 2233 6 2273 6 2274 6 2275 1689 2234 1689 2276 1689 2277 1690 2208 1690 2272 1690 2278 1691 2276 1691 2227 1691 2236 1692 2279 1692 2280 1692 2280 6 2265 6 2281 6 2251 1693 2253 1693 2254 1693 2230 1694 2271 1694 2231 1694 2271 6 2277 6 2272 6 2208 1695 2207 1695 2272 1695 2206 6 2226 6 2207 6 2222 1696 2223 1696 2226 1696 2219 6 2218 6 2223 6 2215 1697 2214 1697 2218 1697 2209 1698 2211 1698 2214 1698 2210 1699 2213 1699 2211 1699 2212 6 2216 6 2213 6 2217 1700 2220 1700 2216 1700 2221 1701 2225 1701 2220 1701 2221 1702 2228 1702 2224 1702 2228 1703 2278 1703 2227 1703 2278 1704 2275 1704 2276 1704 2275 6 2232 6 2234 6 2232 1705 2273 1705 2233 1705 2273 1706 2269 1706 2274 1706 2269 6 2268 6 2274 6 2270 1707 2267 1707 2266 1707 2270 1708 2266 1708 2268 1708 2267 1709 2281 1709 2265 1709 2280 1710 2279 1710 2265 1710 2236 1711 2235 1711 2279 1711 2237 1712 2261 1712 2235 1712 2256 1713 2257 1713 2261 1713 2241 1714 2243 1714 2257 1714 2242 1715 2248 1715 2243 1715 2247 1716 2249 1716 2248 1716 2250 1717 2255 1717 2249 1717 2254 1718 2253 1718 2255 1718 2251 6 2246 6 2252 6 2244 6 2259 6 2245 6 2251 6 2244 6 2246 6 2258 6 2260 6 2264 6 2245 1719 2259 1719 2258 1719 2262 1720 2263 1720 2238 1720 2264 6 2260 6 2263 6 2282 1661 2283 1661 2284 1097 2285 1654 2286 1636 2287 1636 2283 1661 2288 1721 2289 1721 2288 1721 2283 1661 2282 1661 2290 1722 2289 1721 2291 1722 2288 1721 2291 1722 2289 1721 2292 1663 2293 1663 2290 1722 2290 1722 2291 1722 2292 1663 2293 1663 2294 1662 2295 1662 2294 1662 2293 1663 2292 1663 2296 1666 2295 1662 2297 1666 2294 1662 2297 1666 2295 1662 2298 1665 2299 1665 2296 1666 2296 1666 2297 1666 2298 1665 2299 1665 2300 1667 2301 1667 2300 1667 2299 1665 2298 1665 2302 1668 2301 1667 2303 1668 2300 1667 2303 1668 2301 1667 2304 1646 2305 1646 2302 1668 2302 1668 2303 1668 2304 1646 2282 1661 2284 1097 2306 1097 2307 1659 2308 1659 2306 1097 2306 1097 2284 1097 2307 1659 2308 1659 2309 1723 2310 1723 2309 1723 2308 1659 2307 1659 2311 499 2310 1723 2312 499 2309 1723 2312 499 2310 1723 2313 1656 2314 1656 2311 499 2311 499 2312 499 2313 1656 2314 1656 2315 1724 2316 1725 2315 1724 2314 1656 2313 1656 2317 1726 2316 1725 2318 1726 2315 1724 2318 1726 2316 1725 2319 1655 2320 1655 2317 1726 2317 1726 2318 1726 2319 1655 2320 1655 2321 1637 2322 1637 2321 1637 2320 1655 2319 1655 2321 1637 2287 1636 2322 1637 2322 1637 2287 1636 2286 1636 2323 1727 2324 1728 2325 1729 2326 1653 2327 1730 2328 1731 2329 1732 2330 1733 2331 1734 2332 1735 2333 1736 2334 1075 2335 1737 2336 1738 2337 1739 2338 1740 2339 1741 2340 1742 2341 1743 2342 1744 2343 1745 2344 1746 2345 1747 2346 1748 2347 1749 2348 1750 2349 1751 2350 516 2351 1752 2348 1750 2352 1753 2353 1754 2347 1749 2347 1749 2349 1751 2352 1753 2353 1754 2354 1644 2355 1755 2354 1644 2353 1754 2352 1753 2356 1756 2355 1755 2357 1645 2354 1644 2357 1645 2355 1755 2305 1646 2304 1646 2356 1756 2356 1756 2357 1645 2305 1646 2341 1743 2351 1752 2350 516 2348 1750 2351 1752 2349 1751 2342 1744 2344 1746 2343 1745 2350 516 2342 1744 2341 1743 2346 1748 2345 1747 2336 1738 2343 1745 2344 1746 2346 1748 2335 1737 2337 1739 2339 1741 2336 1738 2345 1747 2337 1739 2331 1734 2338 1740 2340 1742 2338 1740 2335 1737 2339 1741 2334 1075 2330 1733 2329 1732 2329 1732 2331 1734 2340 1742 2332 1735 2323 1727 2333 1736 2334 1075 2333 1736 2330 1733 2324 1728 2327 1730 2325 1729 2332 1735 2324 1728 2323 1727 2326 1653 2328 1731 2285 1654 2325 1729 2327 1730 2326 1653 2286 1636 2285 1654 2328 1731 2358 1757 2359 1757 2360 1757 2361 1758 2362 1758 2363 1758 2364 1759 2361 1759 2365 1759 2366 1760 2367 1760 2368 1760 2369 6 2370 6 2371 6 2367 6 2372 6 2373 6 2370 1761 2374 1761 2375 1761 2376 6 2377 6 2378 6 2374 6 2379 6 2380 6 2381 1762 2382 1762 2383 1762 2379 1763 2360 1763 2384 1763 2385 1764 2386 1764 2387 1764 2359 1765 2388 1765 2389 1765 2390 1766 2391 1766 2392 1766 2393 1767 2394 1767 2395 1767 2396 6 2397 6 2398 6 2399 1768 2400 1768 2401 1768 2402 1769 2403 1769 2404 1769 2405 6 2406 6 2407 6 2406 6 2408 6 2409 6 2410 1770 2399 1770 2411 1770 2405 1771 2412 1771 2411 1771 2408 6 2413 6 2414 6 2401 1772 2415 1772 2416 1772 2404 6 2417 6 2413 6 2402 1773 2418 1773 2419 1773 2420 6 2416 6 2395 6 2393 6 2421 6 2422 6 2369 6 2364 6 2365 6 2397 1774 2396 1774 2387 1774 2423 1775 2421 1775 2392 1775 2424 1776 2425 1776 2390 1776 2385 1777 2387 1777 2396 1777 2426 1778 2386 1778 2427 1778 2428 1779 2424 1779 2429 1779 2426 1780 2430 1780 2431 1780 2427 1781 2386 1781 2385 1781 2389 1782 2432 1782 2429 1782 2418 1783 2398 1783 2419 1783 2419 1784 2398 1784 2397 1784 2403 1785 2402 1785 2419 1785 2417 6 2404 6 2403 6 2414 6 2413 6 2417 6 2409 6 2408 6 2414 6 2407 6 2406 6 2409 6 2412 1786 2405 1786 2407 1786 2410 1787 2411 1787 2412 1787 2400 1788 2399 1788 2410 1788 2415 1789 2401 1789 2400 1789 2420 6 2401 6 2416 6 2394 1790 2420 1790 2395 1790 2422 6 2394 6 2393 6 2423 1791 2422 1791 2421 1791 2391 1792 2423 1792 2392 1792 2425 1793 2391 1793 2390 1793 2428 1794 2425 1794 2424 1794 2432 6 2428 6 2429 6 2388 1795 2432 1795 2389 1795 2358 1796 2388 1796 2359 1796 2384 1797 2360 1797 2359 1797 2380 6 2379 6 2384 6 2375 6 2374 6 2380 6 2371 6 2370 6 2375 6 2364 6 2369 6 2371 6 2361 1798 2363 1798 2365 1798 2362 1799 2368 1799 2363 1799 2433 1800 2367 1800 2366 1800 2366 1801 2368 1801 2362 1801 2373 6 2372 6 2378 6 2367 1802 2433 1802 2372 1802 2377 1803 2376 1803 2381 1803 2373 6 2378 6 2377 6 2382 1804 2431 1804 2383 1804 2376 1805 2382 1805 2381 1805 2426 1806 2427 1806 2430 1806 2431 1807 2430 1807 2383 1807 2434 1808 2435 1808 2436 1808 2437 1809 2438 1809 2439 1809 2440 1810 2441 1810 2436 1810 2434 6 2436 6 2441 6 2440 6 2442 6 2443 6 2443 1811 2441 1811 2440 1811 2443 6 2442 6 2444 6 2445 1812 2446 1812 2444 1812 2444 1813 2442 1813 2445 1813 2446 6 2447 6 2448 6 2447 1814 2446 1814 2445 1814 2449 6 2450 6 2451 6 2447 6 2449 6 2448 6 2452 1815 2453 1815 2454 1815 2455 6 2456 6 2457 6 2437 1816 2439 1816 2458 1816 2459 6 2460 6 2438 6 2461 6 2462 6 2463 6 2464 1817 2465 1817 2466 1817 2467 1818 2468 1818 2469 1818 2470 1819 2467 1819 2471 1819 2471 1820 2462 1820 2470 1820 2467 6 2470 6 2468 6 2463 1821 2465 1821 2461 1821 2471 6 2463 6 2462 6 2464 6 2466 6 2458 6 2461 6 2465 6 2464 6 2439 6 2438 6 2460 6 2458 1822 2466 1822 2437 1822 2453 6 2452 6 2459 6 2459 1823 2452 1823 2460 1823 2453 1824 2455 1824 2454 1824 2456 1825 2450 1825 2457 1825 2455 1826 2457 1826 2454 1826 2449 1827 2451 1827 2448 1827 2456 6 2451 6 2450 6 2472 1097 2473 1097 2474 1661 2475 1645 2476 1646 2477 1646 2473 1097 2478 1659 2479 1659 2478 1659 2473 1097 2472 1097 2480 1583 2479 1659 2481 1583 2478 1659 2481 1583 2479 1659 2482 499 2483 499 2480 1583 2480 1583 2481 1583 2482 499 2483 499 2484 1656 2485 1656 2484 1656 2483 499 2482 499 2486 1657 2485 1656 2487 1657 2484 1656 2487 1657 2485 1656 2488 1726 2489 1726 2486 1657 2486 1657 2487 1657 2488 1726 2489 1726 2490 1655 2491 1655 2490 1655 2489 1726 2488 1726 2492 1637 2491 1655 2493 1637 2490 1655 2493 1637 2491 1655 2494 1636 2495 1636 2492 1637 2492 1637 2493 1637 2494 1636 2472 1097 2474 1661 2496 1661 2497 1721 2498 1721 2496 1661 2496 1661 2474 1661 2497 1721 2498 1721 2499 1722 2500 1722 2499 1722 2498 1721 2497 1721 2501 1663 2500 1722 2502 1663 2499 1722 2502 1663 2500 1722 2503 1662 2504 1662 2501 1663 2501 1663 2502 1663 2503 1662 2504 1662 2505 1666 2506 1666 2505 1666 2504 1662 2503 1662 2507 1665 2506 1666 2508 1665 2505 1666 2508 1665 2506 1666 2509 1667 2510 1667 2507 1665 2507 1665 2508 1665 2509 1667 2510 1667 2511 1668 2512 1668 2511 1668 2510 1667 2509 1667 2511 1668 2477 1646 2512 1668 2512 1668 2477 1646 2476 1646 2513 1828 2514 1829 2515 1830 2516 1831 2517 1644 2518 1645 2519 1640 2520 1832 2521 1833 2522 1642 2523 1834 2524 1641 2525 1835 2526 1836 2527 1837 2528 1838 2529 1638 2530 1639 2531 1839 2532 1648 2533 1840 2534 1647 2535 1634 2536 1841 2537 1842 2538 1650 2539 1843 2540 1649 2541 1844 2538 1650 2542 1845 2543 1652 2537 1842 2537 1842 2539 1843 2542 1845 2543 1652 2544 1846 2545 1653 2544 1846 2543 1652 2542 1845 2546 1654 2545 1653 2547 1654 2544 1846 2547 1654 2545 1653 2495 1636 2494 1636 2546 1654 2546 1654 2547 1654 2495 1636 2531 1839 2541 1844 2540 1649 2538 1650 2541 1844 2539 1843 2532 1648 2534 1647 2533 1840 2540 1649 2532 1648 2531 1839 2536 1841 2535 1634 2526 1836 2533 1840 2534 1647 2536 1841 2525 1835 2527 1837 2529 1638 2526 1836 2535 1634 2527 1837 2521 1833 2528 1838 2530 1639 2528 1838 2525 1835 2529 1638 2524 1641 2520 1832 2519 1640 2519 1640 2521 1833 2530 1639 2522 1642 2513 1828 2523 1834 2524 1641 2523 1834 2520 1832 2514 1829 2517 1644 2515 1830 2522 1642 2514 1829 2513 1828 2516 1831 2518 1645 2475 1645 2515 1830 2517 1644 2516 1831 2476 1646 2475 1645 2518 1645

+
+
+
+
+ + + + 0.890852 -0.05233098 -0.4512691 0.0607329 -0.4518879 4.57377e-8 -0.8920749 -0.161774 0.04668314 0.9986299 -0.02364771 0.0293801 0 0 0 1 + + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_wing_collision.stl b/Gazebo/models/mini_talon_vtail/meshes/mini_talon_right_wing_collision.stl new file mode 100644 index 0000000000000000000000000000000000000000..8013927d5a770672693607329a32e3322e5f98e0 GIT binary patch literal 64734 zcmbT9bzBuq`|#I7QN%{YLZxh_W9BTjn23sw1Jzn+>)sYlTFy6sAS2 z7{p4wI3_`lYksC0XzO$D32sS}VhbwBQ4PJ-qo?!9q?t2l`B&ELdF3J$OJQ1)&HynL zh$}$g8n5F9nqK;#X-SeEu<3GcnM3r;s$QBrV||#Gq!&Q!H#$VOuJ1*04bDIAF_IL~ z$4B8^(s56OjBVe4K9KshwPwaX+PFzllb$}xu&l=pEz1TbgM5@pYXcmc0nz7W2%Wgul674y zQA}%zpP-}Xre}^$K;W2Q0=FbdpL~3jp);GrI~O9bRLgTy=~+`N_8?ZGlJup&kD`k^ z72l!|fu*7*gj3U}R&1W06Z0V-qo+S`;IYD1VJVz{NqPcSwbMB{aX+wB%A8R8E8dz# zu9m2l2m>7@#~+Ay00QS6OJN#3@9m@1YjjBvIBS^J611NWeR!>ZyxpD%^|?BQ#`#*a zgn{ohJs)3blH}dnhjy)%!t8}|8d9QOlDdEPVhrO28v10da!Gy*&yJ$=xB z5qOl)&{7w$>e$Z!N9ZLguE9juM?)W*c$w!T1gt7Wo(dg!gu_ypmLzA0mD5Z$j(d)K z2_|q$k`%wxOg%G)s$~=Ruxhd4)cBzltCK3xIZ_ba9%;$ij*#f!^;2mSvt;|eajV)r zDWN_I?IkbU>cH+*45oL|tl6GGiDKHzIGi>eZOwd*_{{lr)&t$A>s?g0^H+3J4@{rpso~eU)w4x-_oiArRRx zpBJpt5?G2+1CeOMb&Q8qMgpudx?IfH;~GqaObDec&6dqbfrm$ttH9Up)w3dD)gS^`UTHa8I7W?ToX zedN|Ahv)_fkxE3O?)PR}>qL?w)F$h)}XJM7mk>wLy zg9)5}Nm>cSHXz=nYY8lcdygc2hpV>K`9N{iVyS1BM$+ZG>anFS-jXM$18CYo3zk)u z=VKrcL0{*IvHj?nxwQQnOIH3|9vK!smoARAW~VRa73zt;F#7D=u_TUuk#g-+oJQHYKSGST(WyAO}7V;=Y7wEzuFI zO3S(Bz^%ePyvwUdn%TM`%iR8f;Fct52t;>Sw;Ce44ZZ}^w|5(|M(f{eq%aMA7e?y+ ziEV^cSO?BWk9M=^neVo&woe|!su<|-aa(B5XJ;&hX?)E~lI5SdmS+&x?Cdm~u5DkB zk=}U(_XSC+4mm%wKP{FMI3_r{+6>+Y9b-E$iR015I&e0zKA4@s^P0&&MK8ew&N-%G z6%JN;O{yX0K^#Twxi(hc!K#Csmx<`&Jmak4JV{a&AVz;FY0q$00)i^0h7Zh(*Sz`Sx?b6EA^ntKiXXvOB1 z%y@Y*ibo7ddfwMZX?A_Q(BYCdjShzE`Hu&@jSXK3IZc-7w>TRTS*D4VjCBpU-0)8F>`yf`HCt=Vqb2Mt*^0M$1h)j^Rd-+c=g`+|1@qBkDco*} zCXsY(c0<-UjIXaua{9}s$4lx%^J^5>V50T+=~M@^L}~$FGX#1rVc+geQBU69p~p4% zx{acljt$t3^kSNpBqrfl?jxUT^K;&@uakz#itke8 zbMN7FZN2&|YWG`BthAn=eOp}hj_xNL$DAkL&Hbq3i2AGtj8QncxFt!7Iufo9d+|*f z-}R<~wPRXKTrdq+-Cx+TkYDL3n81EuT9SfhPnLHq?e6aQdb4i&-C;_%Mst+SY02dC z!jVcBD0e${ht%vaOqr0K%xcG61R9?F+Q#(lF7kQJ(~j4opkZo_%5J z+}VBI+n9PWY%iv@L{Ob;%<)%~l)QtZRV;;R90f^g?N~qQ_wNXq-*G?K@2hlzn9MfO zlMz!!Dqc{I4rjz!`eFtk5w({ko>zgky%5o_9OPb3SZQ!e63V!bH(Cs`=a_n4Z`zKxgO9!4M7rO_Gva`#1@}qH(DBE320-|M$G)L}v!J3Kom`L{u78cGkzoVgH z1rT82%&ls&e|gf57UPxn5TAy{VhN7Iuyzwg+zy2Cel_NFF&9p3+uPY0M-&sdB}pn? zp_I_k*DfIu#{}m9w*>3N>t=%B5y0`uP8==bHv4X-Ceo5Lt{8!R^hmjGOjT!0;7DUy zlI%<*p`(fW{kkCj^bW`Q$q7t_ywju9=zzPbiF zE|$9^tU9x%mdnLDDM-5UQ&0{-O@#LPrbgR$p@yjImcFEdvOM_e+GGOl~R41 z3-%UE;iwykzp=t`$F!EPT7K?7eHZ5d)Bl~1zp=tS1JgLO|NK~d_?Tj%e zHuXrtQaB%4!ehLmYk9V)`;uGZRiFN2MV{k#L(gzE^y76cE|5KzhFQY4)@|sCN#7T- zIr#-{gUy5F<_!&fw~{`V40vt0YID?N(x=)4F+Miw9|J_O3BhW~iACL02F_ww3hQgQ zc!bgw#(Zh!DIli1+o{L*R7vS~%2~zQu@t6Z+;#R)lRlnF{#3bvjJ0EZn1=n`%f|BJ z_T^HBu-@|Q_8~(1?SU%6KH-+&&MP)p4)|TdeM;vUIxK~095+e2e zA6N?0lGHUTn59&$OHG=E$fx!Upt~mZVME7UB&p*%)37R@>}L;^bWUq8eoy>y0%Fy5 z=?CWd?z?{6s-ZHL!gQQ&5SE_d2&vu< zFG$ST-a=o&jUuoL-@9bEd?>st&9!>WysGL1@pQsNf(hJ`B>m1G#4b16N*9$6RdHM6 zk_|qs4*Ej0MCQu~)$+@A5^-|0JGK}5foVy))g?&1Z#qh`oHw6g9hlYfCQ7Vs$Dwl{C!kEXsayNyL4$ zA?nfZ(jXs0j%12CiW9m#9o-2zPi~w+Og^~_qU7DHg$ORm$EzKawmF|1-djjnh3d)r zWBoHI~K9^@^`-ZOYFG5j-()a47PsIhPMjYRcu6XoZno|8K5WKnjx{00$e_d7eA z`VA5_HtT)_nibFgUZVYdgGSox$He&6|ouaN&* zWuM(dLtv=`r+h_A!6X|IoWwc6xxw@w6@O+}hWPxXG^D&IE3@||^sC;(Eo8Ry0#U}cS0{|^KpiW4vJhH? zIwrYNPoU$Ta7&UDeL!KJ?!9%Bw~W;2 z!0kGx45ndV)sHd!$7HXxa3nX=PdrfpP zttGtID!ScWdh7abA1UKlVFKq#k^<7F$nEWtNIhkV4ih+oIMR}|bjo0TVGRfO~O?wX5=4vzX@(h zk}^hm(wS=|_w~^cDsC4`^&D=Pcc;3if{xh}ymh7Lub_MGhpJf0#Ku?XxK-sM(GtrG zrpWWY?^G^j&0|<Y*A!2&HR%*4In-w+AN?w!UDLkxu!iZu&uzzq5nDbnD z9}+|De5c7+3e&L*`-vEKmHDpo$z>mOMZRoRirpL{V@t3UrX|UIWuUy)B9RuiU8ciQ zn8yCW^Ffn7^1CLV^*J?-<(NQM>IPS8qb3>T!MirJ&+^9XM>B;KUFAaiLU~O+J{#CH zs3d=QF@Sz7-d#gn>F6!!_73qHT9O)=4UjKgqSV8ss2Y06Q%Eh3C`qwCtq#x1uUS;& z?vxi}d^JReQk{fV%X=EpYJR?=>@oEtSXCsuqI%G&8ND*3yV~)kpU@Fl648L2m?3w4If7XN(|tV&THu>L{ols1XORa}FKWJh<}u}n)gP37yWj#E9=w(UGv zD}OT;*I=T&eiYT zRkC8nYW%?Jt06eJeu# zAe|#gr84!n1`{TOq4$7=V>bK-;$DLQwLR<1o~6vxMJYOJ4iP0geh};j_78S(HaAt* zZf~Ykc;Y4x>fuRmg1tMcm8O`$ElJV}hpVjfowjV!8b3Mmnit&(QEar>h+W zNl7HAL=W+MiGIf+R)2|Y2N{2a|k0o1w9sM5!tn_8w>Ai{Pmkbk9(a&#^xUs`U zxlN5r1nd5%gO`>*@DNhfE>T1qcmNK{MeSx!R>u$?@68@En zk#n5=H{x~DRs7y(=2Ot2zqU*4Y}XvT(&@*-k)md1g&cCIqG434+w~QhMurM{fN@cn z4W2xjE_9e!+b3cjL0ff#o&+adus&`J|7Wo3T0(mvRex4-n);}-DF3=_OcUN2GI-0H zKP9`nHsU{fuhGK?3GFRc|0GySYZcakGl>1b{z=jar$!>WMR%Aa;)vq-X!G$`$Nj-q zoN)$m{&AiR^1NS}EOvCky#e<`OdE*5vBCuI;h5GExR2t#i?0GLfn$Z^gK0Q(=e{Z7 zuT?mrI5*mSL^llkPX=+;Xwlvx=T+L2qFTaWm!X$n0{0S3YyH6e3im`z!}-L|cOAGN z`wl#D!UXQGnEt1uMOH~?b1NrdyXnrS1owR0V!D0o_@lrAB z*JP9^KQOvVK2_j29R#uLgW)nz{b#$B8PIS`_IibR2q7m?#?Pu8!-JM&{9`8lrezgY9}Hi(nd_ zc^&DbdVi^>cPm#zUHi*X#A=l7U4jX$TatEP?j8^QO6{=gl5@diC+ZGs9Jk?j$<0nq zhTJTBN=ElDC(2W%K7?3pta)7!yoceM4l4{&O}pG7xFr~=-wagu)O^U~+rccpQYfu3 z+LC44WRV8trqLN=t(ksB7TMV^oZ9WMW*Ma@=PPi^O~ExdAGjqr@e8M3Dk*DY`N(CN6f!KH4l%H;sdC%b59ieAng16+bun}7hElH9CoI-M}XUR{634-4hIRJt6X?2W- zw;%@9{SeR3colA!uYI_MS{-n5POKN&!nwGNRxZ>Yw7*GvN_d$QyqpwjDDPf#7p&sv zm3VX;5AdP5hL<_brEp8|UJ=|6gq!*B(^RU{bc2VU;deDTh?{AM$lIY@M-ez}$aV13 zhM3@GZdG9#PAlSt{YLOwcFZW_0<&*S=)uv zGmqg6(^O8Z_>)0S;2P(*aQ1wQC97+kCG_#Dfa{Z_+mOMz%bJL@wO9uxo_rV~tR2}h z1Bk6~wl?;CjyU~k{W*|cziq`rk7p7rg=yI91JBI1R)+p&1w6PrO4zl^tLD9BaBOI2(?S}gp`W3y*XPmJx!u`2wWv}m3h39woKOvab5)dn8^S2f} zRvO}yzaa-FJ8Eh0{ErS!Sa$anIj>gvkwyom;Y~f51wM6oB2G=VR}K9t^~Ga?X)RF~ z`GKVh(>%IdH&_L8lb45=I5pWj(Qr+Sc77ss{FTDABz=SE&R(=t%s5=fUnxxENK4Xi zIPuG)%X8ljqRX$&tUuBHn`cbJnIh2PaWq7nV#RG?TAPoz>9bh4?`Eaj+8{Y=r>C%L zjPY@j*QmRQbi%@T(s;)p@%yHh{7Kx!Xg76j*g4+uwW^*>dw3di79;P-OY(<9#zhiIv3>SoL!xv=BIA1Xv)amq`d@Isl=(aQFJE;dJ z*{G)Tt|>?E%c|b5n;>!&BZ_G)apB=b5@T_gW=QZB1Zpe%dP~u+_sF6Yw*;%#Qr7ac zjQ2{n*&ZtP1505VPG&{~$PURDsPmVN4A)@KaZ9{M@qdPUHN48eb2y$+4f32gdwF^y zCLUNDX8q0EpAt;}BY4Rpps$Ek+m4Kc_vs_bjrPTolfho198(4F`*31#SwB&8;QLt( zfm`Bo;t8)9<<_1YDu{a*uM$lEH}ThVEQM)2ml$;XC2-%xQkd2fc-+MVzBaW4mcsh} zZ=!J&6`nt@eu12Q;3CRn($ABvW^SU~zAj&j@_&3Uga6;$zP+f48Jj{T9hF6St4oT8 z=5qXBq#Vb5oH2oQVBH3JPVAd*m4tJPbAInp2cgeJJ@&^cPTZ`fCSU?fVcq|9@Di57 ze*8D_*K=$;?yvtHtG_wNQn2U^kucyvnC<;CYg5ssHTB z^xxP|)U-WgMBV%Q(uFX~_}Km;E1L8Yzvo=#r@W^fu;HhvbD;$M!hq?&Qrxz;?u`>KKjBvOH6U*lt zdSal6E+%kIv6hCcUDFq%xTSwO7Mz-%h@~*C&G}y)5v{vv2rPwr%s(CDAN+8_y$?&_ z{swzwS?zT8M+fU$m`{~6C$|+bX?)n2&K}f8%s7M?(`B`Wi1HVO&uX_T-O{P~U+Kex zBQyk-I`?I?XvuFYe?y^jiDB}Pid&SM)^Bt?YkURC`xTbLv?Lw*+FPx&pl3?fL}R&q zq@y4l*;9h88raKG==hP&$E(O^J=C_>hmtEB%W15_Qka&c8%1wBK`&8x)Oe=&eK_w8 zJU6_|GbqJ$61u4u->3eXc#rRLs`DM;#4M`8M8V}&g7}oj&v+$|>&$o0g$^uL#?4*m zn7Z#B(Gq`hE(o4AZizdL2AIGt{U_(@*nkp=SPIh*Vcz8}@p%{CU23?>nS0*1R$FIW zqaJn@w%@<_RHM(JgA*SbHAy@Ja|X|#Kg=1J*ay!k`0vx)0;QKZ{J9C2Hk^LiHD`lN=4c3QSf;;+JANg#cMo*ln@f>@rC9*P$i+qIk zf0W4QJ09I*f97*;36H{km}`02FxMVhK1Ar?_ThYBDV!U~M~jDIm-9?=AEx2n z`CLh1)w?V66R;G{2hP*KSan@$l7OXfPt<16y;Cu94VqSRcH#2}_k0b^cLZim?rqOM zGbb+_X3iOJ+{DPh=Z^s}*YX-Z*Wyuv&kX;FUeD}==Z$X0CgPC+OJVw-AH0NhU;2e2XP_;bm+b7i9MO4?uM1j z1DEHT^^TS}10J{Vts~wO#srqiIvz;<;7Ci-BiNbXp7UKC+)HrJXkBa?9R{&lVZm1!$KcK4 z2J>&l^DhET2C3AVNxuP%)-w^tkY#U*^4CONl`cwz@_Vj>hSrs9J2|Si(syVGi&lX&{;U-{>iC}A?Gi#8PO@Z< z6L@bw^|7z)-YJdk?2@R%Ql)Dfo_WPp%PB-`c+^E5V)BLcKYUDwt-|eM3&E<4?_}b5 ze>rPGoDR2(ZPyal*S*z+R`!u^d|An`RhYmn!A>e%QK9cs#C6`X-elSmzTKs>I7hno z3Z$pzSh8^*=ZLpk1RZ(ankD<42hR%;V49Vw1{^ucXqe+#2)bLz8`dFKe$4Nnw*MzaZxC(3~}SLs_! zGT0m7bdq3wS{=WCM6;nljGM0|wp=h+SZnqP4GrHs`!rQuJfMm0u4@m)!rS2acAt|P z&$U(s0r3q8cb%5N7HX}^3aYP0-fW{bD`l*lYB5!K8%Xx*^J6VxV4|97)~R!nY-SPZF#TXH$}@0#VB&lJAA9KGXf_8+aNP z6_u)qG}Z^-XawTc_RWqkQfr9oeFEs(?E1|7j+Ta9oImq9C$PdoIg6}PP z`B02f(w8V2*W$^i&uQD{Y zqbT6qz#0x>^>*=WK69$L2FFbsD|_&~?+#btIqrQpAFiGu^n_V`77)Zwn3{Y0(AT-G z;^C_i8qcxq*e7^bANhfG;C69DBxx-?QFN}kPJFEgw}quJElJJy_EZ=B(CfTM-C_kM zQ|Mi%`fOL76U1n!KXsjE%|hm-lA_Q2X@f`g*}$Ltn*$Zsw^BPEKfyd)OUk$g6W5=I z(%*^jWlUrKzS@`v@wx?b#>zvY8nBJ&GiVPdOV+IH4Pul$leRr+$&&A!Bv`j3b?~Ef zezS@4l$A$yxCZOPEx{A4>fUlYp9<=t)w3wpzHi1<>OBZ7xd=WXeUe0`L4c!rsvSFp zFl;*}a7&UDUapsX-uNZ6F0(_2wPPu*jy`|ZS9~S&_--WC=UcL6cdwHUBO~Y(oec}w ze4Q9oHe4&eYVvpWJHfX_c;DsgtH5rC9$v8FI>EG-NPzE`JpFx^=UkrOK8zliQJ?*) zq$O}m@O2mGdQruI#ht?^L&iRi9}}U-5NHOsp+$ z7`x10TqSGTO`<<mdoX+_^~-a|ra<64PrVx~#;77Ut`SVb*(m6V zz5EY3xdDNtFsVg1fIbmzuK~x)^6(P2wN4`V8S!TpQin`V&w|>=<}#jJ2~vNsjfjdk=Ex{e+(C<23va#$rx|zl*Ob2WUro|`JXFDZ+%EG2xIxA*YLw-B9g^Fu1 zp|z^}VXA&^w?$WDdo>x?U_Wq6aQX4OyXfb zi7GI5jq907Hq@Fz=P)Z4rf`CQj;9kEh%*!Y<3s5~_|j>tOBS&=4x&3w)n|=vXA<0! zBuxQgSd*Rn%Xl(w3+vEYwG;?GCh}3V*qEu*dP{v4G$M;&Z>K=Nnm*f-{dmbeuMN>< zQ^a@GWNZnx5Vs^r_Ap*`^*0tH9JU18j$48qFCfZpE}6hbI2=*zlh%(|*aPSo_12#I zf%A-MoF_?I1)f{^br;diI}lFiFS23P=WBb3mWTwxYy{yeOBweJtPi&&Nufa0obp86 zZR3byS{vP6;74;cLG%(FMI2q+67(w|3f{dCR?XfXNSnX1WWARd(`V%Z>9R)FEPk#r zjafKV^j-7U#;|((4KvQ=9yLTha1AC(-%kgVF_bmLPXmHK7R~a5kiyn*399Q zF~w4tmZY;V?si|*L_`-`h4p1T4xu%6TC%}sxsIj>BILLpZRowo75bJQ;q=-rYxX)k zi|l$bmF|Jvh#Hf#$kuJ)G(OjgZT`xMuY1bMr#^Yh#S;oBmU1Zu-!0y5$)>C{rdr}& zk2u|x*%Q>fb@4P8zPOjS!J4()U`(+-Em5JPk(za;w_1JYCk0Dkx_3|@eK^L76G%l zSxxB!85rnG1EE~qGn*`Q87zLcPUX*vVy2hoPXXk86H7T`!ez-&A$6_fM-44W6BDNh zqEe**=k*N+&|qkH-zSM;0=Fbd6ZUQ9`_#g!OFz2M$v~XhTZ9@t^rAsf&OTCt;+7=I zdi;F8>nyK4-_8XSJ07TtYq`c!2&e4(dQ$QhDl7OD(^^4Ik@ z$chF5iXW6S%Jb8o7PB_-Cnj>g(+3jGs*Mpf>)o>mrnN-P>epR3k=*!p(!~c8l@ZWZ z=&b`}VrM^P7?j67zD#EK^i{?{d9K3WgS7YGd;ACV_ENRVx?uuKef~H~=?jFn&k-Qr zPpBq54?k2%qhrsRP+_6}`Z$d~NqW8Pq{v6^L@O6;2_~?Aa36KBk0AK$iKVdTT4JZ^ zYzKbTn!a4<)WOn=eES%xJTp!tQmko80hHSrA0?4>8mCD4p~~VGd`GzZxu}F+K&fElJqf2!8Mu=1K=r6MkPe{uo$w=HNgZzK3#1qJ|sp@B`i$ zQHvL&j(M=+$2Ds}ipM7fq;N~HZeLwbonYJEy##BkdK@1@FK>ItUbW07`42jYvU$5= zG;N=^n6EZw@{={vsxET1Z9(o=7FScTRPjVguL50v_#?8jz(Wwpvp<7X$qz#1E%W8% zrECzxQh46g5;af9=zb>;Px6en`f_YJf+<1y%#AAa10OTVna%D{dF-!%={*K!J|?EA^u9avhfN6|p1GR%fu# z3d&=^LamN6(63fETO_Q)HJHHq;BEp4;+_5<9e@46w3avsM24SZEbr}D3VXf{qQE^5 zg(yhUHt@r_%Q|5djv|hmR>$d2!_<*2X1cw~%4JS9{iro~J84ul$(!aYa%1C`O%4?F z73E+3`8mt%`#sgbbxtY$9Zl77F}+2sKBO0?nAQ^2G6(9IC5XVAls zL7DfMN20g$p7^-ZUeOb=)DpPo;61zr+;eE}KYqgqS0Zzk$T=pkK3~v1#?_u}1>Nw) z6Uh0cg?mKKal4ov1O(T2P!Mf_XnT9VAUt%7L|bc9UlQCd|DE@%HSoJ6@%M3BwGhwG zRopHn{+EshLI;+@erR>9gEy*9#mwdJf2f?`*WgC57Zcj(cBty2KCYJJmY3Z^J}`8= zSh0rJK0tI zI>%Q}lb_C+B;&Sl+_bTJ(es;SWpnO%tN3=Z<$ZVe>=AXsI2RDD#$h`44eBgzvCu2u^e2Z6O-IxY*HEotf#K zV!Nxk>T%gDMcA7XLp=KLNapR{3fNCPa<(V)-ZN^&e$a7brn~xf<$X7I&!!qeYHyap ziF8Fv8{XrzIA1j3CG7u1ZmKM#PM(e-7F!yp@VF%y=MoPnbDEb89{;MJAHS;*F$8E% z6sF-_{R}U4?!r&xcUC2NNN=YUZtwg0xg<3%TlleK(r1#|u8Gjmqcqpy+rUws{H5GB(Tblm1a3*JER{d`kW)=uMMNjMd?S*>eW63Y8}7EC%ws6ZJcG)cc|XMo zAx!Wx_tw8KEk(67mv8SN?p3;WmJ7Oc5mITF@<>j3195cHH_~}#7oodNMjrUl+^CwY z7DOlCFX$rU8cbX*XRx-YA6P5?J{sltZM_JO)kpi|Bq!8(RA)ra%S2wao?7-@+vX99V^OXt@$2V z+Nq{;n<$dfy1cupyAmsix=k|)rnLmTQ!TC!K8kvT8`{lgS4qaRHG*#5_yWmhLUT_=?u8rt1caE=VkHs~v= z@Uu7@tE84d?NQQWw3YoSR;BH%Dml+enxan z^h!~lT!ZWIKh;!S3HexF-d!G;xKgycu4++=X)VzMuGX2w^gS$Q)O}x9LNA$CtcSX5YM#E2T3)_-@SvFKSDo5SFs&ud=2lW) zd>f`T4D?cQ4c1{^?4ZK^c;~Yiba?#Oz_{n$KPStTQx^$KJk!%i&~AgiQu8+x{yQi5 z@9-4h57Fy?5Zn(=U>fF+cU9$D1#T&B#$9FhY=Q8@VZK6|UN-1E=X!?dFBx<&^E05s zwV%0s#=VC7V)xE6mcn$K+yx?r#bzl$@Mm4z4+5)L%QXfa9onuXrOcv)l*>p(l=(=_ z%m0YCkaJA%GS5w6T9SOy9p%I?W;C>jgKF2qAa%3(TC!vMLJ=ST_(i1lx`iT!PDXr( zWz@^Aa^=c5^`F<7saOir$tw)j-fXiL2$oX;{tMq8_!$A;J~Q+Zr}>M?^-YF$=k8e| z%G?iLhI`IG#7H2x)ZZFT^Q>_iw`B0VXINUSGkA{gyxJ7A6{}*&eJL4H##Y=d?JUl9 z@aXQGb~ok~^mbf>?@x{Zal8J^~aK=X^S;?_lD7@-Oc*3`ysjnyiI~VfQDo#!8#^a zwWXb5|0={~5$O2q`AQ(L6pu9D<>EUxTB82p!+a-IpFkD!8Ifh%sqq{16X2MUn zTg5wRSPIjIcN*?{Hci+I{R&HAy5Qq*!#?9ZuH%m%a+k!S33%rYOJVvSv1fNNtM<6WzbNnOF+b2G29L-*Mny!N5{@FEsVgO0h5MQ+5I9XnOdt z*x$8}dFh0A0iP7N6}yAQek>uSj;AcMVjr ztHwu$)7SH3Rs&I3>hCV6mf#uTBLn~cp;@7#t;c3N3Erj9?i&0he)p}Oh}*)uc%RRJ zPhiz1&voF(;|}@!-9CBM&TX#g@GSK@)SQQBsc+$FAKw?vfv0`e@XV9@*BzdD!e71^ z)=litPi&|=j%zTH4Now6OY_86%(p-OEuI@}^e}VAHJD)VbeZe3f~U){rZ$%ZF{g^H z3$`6g;V8gg8ux53o|0J%oaut4FpYKdNb!G>a*w@l60j6*7f0P7&xvEVk2~QS98uho z=q0MWx^i48Sd-3w7%Fy(W?xuMO8g3?R|m~uQ69@RyGDj}`+Jug_Qvpc*6_X$ChTs9 z(#elbF-uq(7;c{;p!f6XEWj#BTUW6RX7`u~b34`yEa>CS* zcx)Bk{kq<1vG6Z_@OrT7FYz+|a6GOdf1>c{_Ub~O!}TGostmEh?c!ao^M7=>4dXiC z8dS|}OFOm#0@q-oQs>2D1rXl(uT{|7g&r)0_sA}Qg?#7E_r&Udey9yUu8PMsxLw?m z;oU3l{amo>44k3mcf2(cSCQyH?XEe!TC*o7)(q=m z?YwArX|M(D&^Ul{-It>q!(GvW6_&!P6)n~}53hQK)`yxPrzFCkRPuJ+;o0Vc$62%y zl)b<3`|~O;t3|9j*ZJafXx=>`b))8e4Z)vz@|CRN>1$%mufnR*?JLLM+;&3{Kle!# zOYvv7oG?5SzF291m~nXC2f^7G?rmi_8{-70Ubxf)IQ62&!6S37W!(;xuEe0PQC2BCahXA!X*I{wSOiG;&c7I1k>Dl{?Bl- z=46TvM~-e>}&z#W}|y?JdW+@G*Em-w^OEcQjW3ae_?I$**6%V~9rQ!GK(M`ds!>NHHgSz#lT`+-l zU|Nz^FL)sQa6Viy2}|MYTub=Q{v~v*Y!&2;M;wzrKlOaPa@bq0(0Em5MPG6DgJ+VT z1mdH?ML0XOBxr%cufeoy&j=pJVCF3ADXiiImcn!foJis=y@3-+aL#f;D-qphC+0gh zgmX(ggFk}dTh4G&ftUG71ufB|RlWniKK6gePQ+4}=4TtYj<;|!0?s;riu_N%;^!84 zyUXB|#gG_Nu}`g*Ix0?F@F?tq6Bm+nbBT#q`!pQk;)Ds@E-465_?UmY2H(@~=e8_? zUr~8ilU;hki48tabb}Kc{3OTUcITR#Fh07b?->F_e(G8gE3+=)iFnSyV>=%6;T;n* z7vXu2$}Wj`p1||f7&wc?bJGjXV!>Ag*ZT?2*LtsV#x*!=xFt#Izq_ums>IjG1l%() zfinwMwX_f?QpSDWnaJ;Jd35=cYHYi9jvBSHov`XvMrjuhI2FR}^@dX+1B$*=__Y#t zY$f5RNcbFOIK%R&Xo|4vdz-6?I3G9%IGgbNyv`>Wllr58LFOi59O;Cv)wVa5gIB`W8L!OXhJiG(84(iYnF+S5*1!Rh_ZzIRDz5ySZ15 z=e^|UQr9F*;3!~PlFDs<6U%%1)e2V=FoAo%Hdak4+X>I-e0mU%J$wwiLp;($^A?kJ zrfmuDm2IBzl}z5k&*D1w?qqfx*WkF}mL%z8o#YnWkF=DH3AkMxE8G&S;kJ!R;C?)~ z-`yG4U;;;7l5!n<#K_RUMk`mm^1^w>`In?gHm;&yRsFFi9uv5SV;bJzxj9b|^-k2+ z^maTx;+_xR>$CYFuEC1s`Z?n31CP6SmViBd2Mgi(<+F>O@jQWNA1zVuwZ9;4ztOwk zkpW*(S|Y7PcM&T-?&7rpo<;Fmg3IxLk@Ch?JDji-o}IOXE@P^Q)xyD#obZgi2~HUE z>th$3FxJk_b3YCh#GI2i;;|H-skOx0GDqxrzuI8F-3iaacx8cU7_WME6f1z$t^rB7 z2J6F-hQI0kvYa43ylj(%+vTSXxgY$rA#MroJGwR%`Ix)6qzfkS+6U9{mQa42I4^3^ zzE&dc;dnH_GXs1-@x>9Lg9X2E!o3>LI5W3}DHdR1%mn_|Hs4-)?8r0NHFk+3o+0tb zpdG2VbsQ)15wXeE0gokE3e)iQ?-T39tadfU)fsEYR^fS9k}3=w z5qKYUt6?`P+_YrknbYuRnZa<{+azsDwH4DP9%1NN;3ZYuCBwubADgj#&f%U z5{S-E{+y(Lr$_em$XD^jCyh`pO$+)w(upY{qc1 zr?Uy$0k+@kJBUP;F=2MMJlKU`KOjnkPIGU)b4_wE+;L+9OGUIXVd2nAKGz)vM6m&5 z-21-Xlsvx>fu+KizgF@a&QaQr^#x*BiLd1Qx!oy`9!01+*rDU6!oI;izDH$Cvcb3? zt2SajdGTjoe0vDrq2J&>h`#T6HQ9G7oKu856TSixN_ZP#N+^;3{3tmL1HS>p)O>pk9L*`t9_b;Pi2l5E)4o0uwJCJp6GE%#OM4WOX zRJ>d3)oqQ^$|;c@EI*#Sf<5aHI7jLg#CKBn1=#CO)G3vcU>vUYskccXcVDx%k6;dm zew6_ktUP-XX`}8}dX_xJLN<*D;$hwlDs{Za*3TKCel50+O6l*}j+${qx@1FN!7k3T z>gz~Bcqn}U|b0UW1; zJh)joq#S4~S`DcxsySMJ&d_N~|oATpiC%P0E#vLgdGvH?rh(>h1t54BIeLrkhJ zruUW`sil6UleD_?>E4)Rq3D-HKD#*PpU{Sh96hHFRQ24I#P+zFlkvS16?n|$|O0e0{MylJ~b|k{NBy$M-$=288S8eFPL!@QiUM0SA zgc_;rB(KMpQ&(M?L@rNga~ji+pKbgspThuX=~I2BO=yXcB%bjJ>c5Q6nRx z+&3kfsinp)Cw)rS&`-W)u6Al3O|t1{CG1F5H8*@F5M|edq?{X;=fbaZ59rmgFn*ND z7*Fu^q3!K%9y>|Gk4O5}SrIDMKD1LYW~(z%8=iM3*jjiBpx;KapEP3*R^ckvj{U&a z!e1FXzKwXynZrocU^VGjt}@ELhT7uTc8%@WC)oWkTS_*Ma3z;NfFEeY!9L;f5#Hd4 zP)Nq7Df&tH}KX;A6xx|HxVixEwQ&a|L_;U?i?kbhAz`5KGzaBZkU!N(|uD&!}^cd_*gTRci&-SD1Q8I?rT%qAyqYR3|6m6q6W zdN0{?PS3`_7_W&gzPhwmREeUoBsDuh@qaa4Gy0?s@*zEvDyjXx&C-lSl4LbHmb~r% zoBg_~%^>z1M+Dv<3_D25rTfqz@EqHVuOb`~Nh+vylr-&Jo0YyFt{LI*Sb{Bt9mrCL zNx2Fk?l0eKbB?bS?e)>2d<;1?DE{~?ASRc!rF`w28M#=qlF{~(AKi}-i^~)Bm0xME zLAw(o9|@yq;=XTe{F#(mf2&&i7X;fo8cuS$d- zBflHe)b9cvxGk&$U;przHl9ed&g7aY10HHU$2zcXNqX0@2z57I<{tk*YgKd&TRH$n zqOkCV1VT-IeqG;jJmJYQS;B)kBu#t608sQ@ta>DmCw4nuXqik4{8@%f>)f9 zG{@40RAE079p&AdS{yc38)imnW@LPI!P~MX z+v(3WmDGdwUMg-2kD?~C_Umiauux}?=FgpnH(5Z_hj(Sv|decQ=<+cGTNcB-0t!HhndTt)p^u!rFBL%WiR-H=V+&mGF{ zRt(V)c=dv5*i||Ff(GSpXFcjnQXg&aPHOh6p*G)lL9-&mG<*?%%x+z?DgkQ1`)W$( z$@}#yEiBZt<|Qfa8QOf5NL1(wn-}bKb6*vY;aH!R$oM&49`0I-b$xl1wRm`zw*Sc( zGkr!5mP(;3Ufp7!Epy1F=f~*PWsg{c_GcmI^>(zT{neiO!$%`jyz<8PHMlRp`D42v zdGerDDWke9V%zlh=)OL_%yU>S86v~|z|{`y=-bnpyBFBmJ~v5DoOe)}vTujRs%J+} z)1uu|SitHO(rd>ZdTGo`wk|FQtje4+MLuq4$p#gf$VS#aM%SFkW*2<4wqu{*30AYp zx*VEKlRg8d`;kc!)ZZj^mBtX>}AuV;JM|zV!DZT>s;$U zo~Gg&><4a1l1ddHE%%CZVH@u=<}dH2?ds&S_f?+~e21jXdF30oX}>F0bkdONn)_OO zMQKO4DeMb1-cglZZ>PPY@KuDbX80Q;bAM2yMO&G--6YL?j;}}Dk6||W*+Dm>;|6`7 zuVE_g8Q60i5!eH`Pjn-P{Lq&SpQ`Z#6SyT9;qG;p*Qh1cd9wzxU1MzNk`#o;Q+eCgPT0inX?beMqGjR`W z5}<0X3A7)8@4R88-aAkCVTO|YBr`}uU~h4cfv1+!R_ojjtWDW^Cs6HRa+98{w~8G% zJxMTub;C2rb?bC>ek{>9?V%-bd@wCZ^V;p#othb;^sO{W#r+3gMVN+@PR`AAdt6q! zr@Mr!_&yvHxFvWhQ!iLoWx}qMC*wmj1n!BLhUaRtmgu6!ZBaH(x-+FmsrA}b){NAeYa8WXk}gZ*+y6 zGv3jGO@mQmfuzem+8O{_Y@Yn@wQL`R0yrRf{xjog4)cC5!Ex`%$WmLXdtCTu0_&URR#)LNK z$yrrplm2$9`=ZMXU(cAvy+@LIY}M;tOzx(RZ2wY2;E_SoW27fm-E?hM4OA^xy<)fq zuK@5$4Mx!y*K{K@h(0oGv|PRQMf$MP0ye1<>_A!Ep?Z4{<}|q|Epzl7b-ve>-5bqU zmKP@5$vzfs^aJNQ%cTzArQ7a>u!*}~ld2K-Y2Iu%w&y9lU4>|PH^Zc+;?1gDT;f)4W|;iGl?j^;M4OPIgu?!}>5Z1GR)`;2 z)jUT$6YemPpFDGJ?kMl|pQSjOJIIaR-J+hk>sZL=7v#<1t8|3TM%FRwD>1uuiKf>) z#sXVC1LEPRs`A|AdCJSOTd0)X)Jbk#aEd&YQ?io-XWGx|fV=mK4mR3#gI0*Z(0IQF<*6t5sAz`HG*i7&yLx ze5z;=8+qPQ_Up5ldW0FNU2dgoq%aL%(lND`FIHa6)@^Z=am}7yGpOD1(rVrhmEe|O z54nk%Ov^52U-DbYSPIh_r$$kwx2c-TIy*~ch zi<$fMDLc>XIp)EBZ?u(xLyR8xoXxFuO0prRM;WWqoz3`O6<9L+klHHFSb@!kXwta27O9&h*IL9bT+4TB)%#Iqyo6Ak5*#{9g zHfc4eR!Vo?JJawV)=B4^ZEVWWG#>r@JBHDYXo`|%SF|nOV~oRPhDjp|(f77*WZ7$P z^U@c@cV0=+pS2&8bMp?n`smj}e`24NS;-=uM~+G?TDuND$`Lv*<(BJ7T;XQUKqzX z3KV6?j^|nx^%z$cx0QHcBw|d{uNgJ(Y7@@8m^U6)kzyAk5hIkwd9#KZh|6&Yfmk~R(Gg|wB1C55agQZAB z1X7|m$no2?dRgm?Tzx~NNW?gn5n)cT+N{ro%p07x&!6WMGlrb0YS#F%ERCox z85^{iq)O^f{X=!$c@KL+JAkn7D@uD2oL6Xu+qphcC{$4CeqABd)!Na{3gz@IHmpUEY3oNI9oMjO%%i1CxP?ddg4=PTZlbs&-y}J#d1)U`i*} ztbv2c#}{L0QAE>RQZHItX6wZ3MuqBV(PpkrHvL{j^ZtV((h5g8ut%2HE;vs&!sbQl zaWAH;m9$dk$P&33qS3STtxQfG?eMi{zFRv-N^wX{D?&RzD$=G^m?T*jV+k!yIp`b*Y3X(A7`MhvmTZOgL95f-_ToV8>eAK5?|CQd zL2j*>-}xL~(f!sW34xZDt!ucC)&>?X#h=s()6oZrkZm<0 zu&cH)xUH`_I$TGapyoK5>37bZL$s}r(+qvoB*}y58}ugCrDCs{`}8K}uA2>Y+<#z% zSM*;yfuf)**^!<79*X;IRPmQ5JMoOa=5pSCxQD>(WHa$v;?0Yxg=hl>AZ;S!&A|wR% zlH)4M)lK_lTD;+CM(EfJqeMpBzH^Q}iLUAUVQaL$p;j>K_{op2>R4YIsW^g3D%Xo_ z)rR^;SYWgsxve6*GUFz1=-|$9bfN$0PU^QJA3InKDJDh zw0PAym z*B^$rd$f+xx28)6^`24K%)PGw!|0)3!)rBS-h0~_XG3Ci?4>LYZrXZyadT&_{0w!X zC@DCX{oS>(U5MM;AR*=p|>kNJ(0u2RI%5*0gxmEc1S7eZhxAp)hP{JTF7Vjs4* zFzR=Tk=7`bU6NK=H$9%cI5jMFfG>S%3bNnP7u)XCE=RX>3V)-=`}hK^=InGfdtbDU zz0hm2=1Yz)S4$RpY|Ho~Mv5y$_$l*@qwAc_d6mSMFTqDzG39YF+mE|tpJOcb_o%_# z11IynyBiR~w@)Kh`FU&G1DlM%Ug&?SWY#@ajon$acWTz@;>XXW={wk2<6&9N8iq$o3L9aBTAmobi+G5W#7v8g}LEodgcqSFD0F*y?d zcKgE?`9kw~`5;E$Q}l@{zOMKwyB_l#zF)mtrzgKXyBFhq&Fy;ljHG$d((HpiK;E=QEt+Nw ztJzlTK>NgzYgEG{wxU_HRS|~Kj`ND5Bplsoc&(r5Tc(5@R|k8H@fEj!M-;2cWT`y; z*BVO1Y~LJ@7(HY!_YJ+Cz(bc-m&OEInkxOB-)6+W(6w6&!=<$r=SP&5a^wEG&ba$e zZrhuBG7qGS(L=uv*4Sq3%s0kYsYD*E^jqq)QGfBAQ7)2HC@tlBsdm7a8+yjp`VpAwR*Dj!M2S_Mvkd2Em)WdFQPOIFQ8Fj?Ut5dkrA%eG z$O5%{=^f*A`cG;1hDJ-)MQxjm4hmhLy^omgc=_{mbCPI8pE9h+`E z4KA%^?T(b91pOgP^*qmA+9N{^hn@y z3RYz30~xV)U|xP~bAV6d<54=&#YmJ9^`92x{W~A^y|gAuFS{___F(sYeqvKOhF(M7 z^!31Oh2IK(>ihnUEEOV9LYf&eZyNtJwApIX?p5LeenzyStnkdmc|vWifAer1{T%eJ ztKt1!Ni($a9aXk2f91w2opba_i;C2}SH8A=OzOffKPt*l+r=HP+r)TGU00lZUb1{K zzHQb_i!*>c{Q0B1X-7{-=_m z&t=UUoN?u?+AdG)H8)a1%m^=HB=k(=&8Ims+2?z5+Z0wL5vEVch&1{wD{H>~_)x_;O7`GsqZXgpx3F3&C{jmSSrN62RkiN&zY7&)7(I0B zKBF8jdU&%fmt&OfTz!}kb330oXUv}}T37Z*jq8oL7XHXqpK1i6MUgJ@BYz~-<3GNM zH44s)kUWTJX+i7Enc#uF%eRfpcQ1zPi^nP_f@IJoQi}?2-Kr1k2IVc6*Z$B z#h0vJ;qLtAus&M<5ZSsN)0Y~@hgCAqzW69vn!b#xSeHBP3ry=lCq)<~I9AZ=bndgd zKEKs?saB@MSZRhs9=Imbhze=WD-W%sR`ZR}(TYenP32hqCsPHi(v)7Jy(?nemm$HwpZ;KaE;V+KY@;~XQrc(J)gz3cvb#LD}G=$)wY zsH``(577~Ntxaor+$`HL?RAF;9ciH+XgB(OFsmic@oDHA zRW(A#-(?Yv64LJVb2GlR;ql}d!4dkFtZnq&^b8)b@q~)@L4I_fp>JCrot4~l{>yN^ z-Y=Vt6PcHJ_S*9*>Llxt{oao!`BpbNRgg7Di=q|iowGt~er-}nno?BO93_;cDiq_- zE0$=Y#11ZwQdmztoFZ-)%jS*Tj!U*e2`P(5HAgdd zGoQ4sce+b@AX-NJ^5bznGT?Mtzdj=*9%x8$+T0TtrplUko$JqAwf})zeqmgi(Q1^l`FmJChWt4t;{AH{RhyQI z(1(TQ=Ev_in(=FN6?MY7OHsl*w&O_&1GQI^$Lq))y&0GJ$Z*|X!OS?fg+^^wPN7~isHD7{QSG=bqoc8ZQMe=(N|Gx$56?d~uUS!VM?4OA zwB=)>nNe_8xQ@MWK9>^vdTs6`$aJ@hNt$qqbv!x`^enc+I#TfsRI=SmtM zzjxpdHZDjFCItE!5lD%?UjDuVUs12Vt;z{`L}65-ezXp@X~umn>}FXJwAR860i1C# z@~NhUS0_IF_*7$kUD<>48t3B!=*!820Yg>vCe;R95X2)|PSrXem&f3?^eiLbuPSEb z{2QultDlk^@w*XgH1=w=j=dTmI%eeYt7di|{`MP0_w8p>D65L;ck*#ca>ZmLV8K-0 zGG>G7y*)pX0L1fwgpY?{47L~TAn9?a{TuN$x%uJG2HuE}daX&ecrV(viV&Wg=2$$6h536c(1M8a-I9!*#N*hY zSVFYSI$|M$y2mCCp)*avz2CM`DoQ1+u$%tBl6*rqQsypBrmy?W2Cpi5V+$f=&CT6! zMfMBR@r_dwa!09=K%9oMgrJtM}Xyh^*>ezw^vm5>8DcvoE$F>X!ttd~|b~P)ssh{@wry_b|*3UvbFLzGen`p1|QZoLIgjSRniz4WL zSej3li%dg=XG41xjFdA}Hv`agQncg`-lu&o-;TCn5)YILrKS9m;dS*kTW9$;{a)2k zbL@pyppzoXP9UOC7YirY5Np zw>k>*ZqfBPTAaY74AH~9u_mq}zJ$+s`w z3uy@n1>Ica10j`o=A@q;L3-#Bq`9z(Xn8|c#9oM|8+25^_DR=m9#pYO$8nI=#*>MP zA==Cv*7y+lMGsly<7@S7;qw;cbCI7x{Sp~pr4l^E|AmBfUzBVWADLiz@DkCT^C*q$ zMAwhdf^I893*P_n$R@MSUC{r9w$$1l3(KMpav5*$S=ePqL3!6D--CNk8!{^ivd{0IEjYWSWPl z2#vI`7xJbmd{iTMx<1=O)W}5y>VarQ=}1z&n7{0Qq{3c^RumUPc&(dl)vv`!#OOo) z=q?V~YJ+1DiwDv|w2Tn(F2=_{;meW`fpMJlLbrSq6-?bkWa3x1M!KLQ{Rt#t+2a zM;Fq0*m_yL7Th~7(M5iAbKvLito&D*=cXr4m_5isxV*h6A&`=y%zHY^$`5z@e1304 z-02o*>Cq?Uj@rAmy#~{0Rop$FTCBZQ_jS{E^S!VaqE|KPZ)v`K@?}CCEXXV#g;$3s zVK0TBr{^6gz;mk?s@8}SW4+A|Oj zp|x0XLS5!qbl1Los3N~uAA9YpDrX;&RPVna#L9`1AOb1TSB->-qt!snS7I+BX0=_k z7r}jrtcT#SyTPy4s4YaAi&@lzG{;_uRuq#E8J#y;2$Td7NJ&u+ldYcBnrY1?XdfZF zu$8a^`iAo2P{nlbOItmtPMj`mB6cj5$tI|+Y%8(i6x{F7MA!;xArGWvpW%c*1Oi(S zf&A#4dh0b^}BWg~D6x2*C$ie1g2K)%nxrMc=GAqRP!i zy+xDjqz}>+tLWEtaAhGk>)GM-m-+_g^(~oAsJ?-LEyxck(XZht_RQQ4KEEA6y12@O zv~Far!A?ts9zT6S_?-H!3AP|Vq-4*3wP$xl&-J7S(!~|0d)r3VI#{E<;6X8KcJ`^{ z8AAwcL4HU{*i`&Yp=zEZ5|J*hwd0GpSv-E5C2VE?BgF1ip4fu?kdj?0ff`BHMY_0> zWqovIskB>K=eqcd9wYBf@_73V0(<>QQjMb>fI1PS%GK}50i=t&uqi*-Yg#m0AZ%s- zn_?!;-qi$K;y<`r`?id3i&dobpB^1ZD%|5D8uzI7T;6f(&NS)v4MIru^$p@RNhO}s z!-Z5Lc7^$DyD3B=fsv!cULbNz%u=B_u9w-UwB>w;P-N&B4y=%v{ z4SxMb50oAGeK9VrYE+dZ5qaR-ixc@=XuhMl@VWhOiay=-Nn>n59!SZqd7ZP%_Ln88 zkgj?E$sO-&R_8Sb{+h>_SL8Tig;FD zQARZ-tws|o!=K>u?uI=RTjSx&)DkoLTD|!GglVtH@}O&J%RGp&5DPOFkVkq5s0 z$_TMG35i6t8?-2{aJjSXnehtU6sKxpcOej!34twVD1V;NV^h+yZ}vW-x7fpF>u;MN zU0f4`THAB>f7fRvM7zLYOBhKa#>C^ZvEQucVm~5!e-za`U_BSlqVA{I@3;{U@!WZ| z;PF-SafHAYo!Zpi~k7xyUlF54?U1l<+35`W@6aa6>lCfI`fkdifv z>gi?9dx)B0wA#e0HyR+Qg24mTb0S5wz*Jf&eTL~l+Z^BVgbU32fd5)T=1t00DaDe z3JDF47t@h0o+skTB&|`~$Lsws9ZLNzK32n)T|~DnofHbX!|yk>OZdCsG3Dl9eRPXZ zwMXrT8nz%mq(txM)w<{{M-FKknORiQ9Hl}uWhC7?UeBIb+BWXjSPgrj6=cm9RTb^Cu!=G3g}e+DIonf3Wu#h_k76ypTI0kP_(;S%JmpE^1TH z#F+Tjh;MiJ#!7QZ+Xw96%_&Vw^@=v@&>L^Mc*FW*p}Nj!$aZK6e3NaFitljre!efA z)fj!nmSIMlNDFz)Ywyj<(;2cE@iW;f(`5+zXH>9l?GG`MRQLvgyMDUK@va7odQ!*tj^>*z04gP6Plq)PxiK(pI zqZ+)_p5@X`FZ5FkYkI(y*P9`JgG?_M!1iALoSe2b#w<}_GV^@q#^X-Ms@Uu6p2)t3 zt9oPr+Zz*@>Ps1Wkvr}asq!;B(ziNawm|Th^Q13Je(^RXZcU7dw2%kx0O_5x_8=CO z_d-gpRWT;g#a^f%&Fup_vA3hj`DSjH5!g$Xs{Z57Y~06lsqx!nJ+K#AopSufRb;{0 zE}OsWkk;Q<*a*;Ubbc}DQ6~(Z5;E6rth5_JJ?*@nyby<$uk4el@XtoM6vHX=(h7w zG7s#fPMd61EG+n53A;ih{XHDnq2Zv5WkEf;%QnCJF~4iU-RQd715LrnfAGP;-@5tw^c;6 zygH2W-8Fg1P8U@~({FdZ|NF%q5x6f!G@YK)@0_h(b+D>uW3L}bkN30OcoOL$BSfXb zhJF9As>>rHcegN>lgFKhk$n(ND<^5b@6(~ijYtn%opWkWVgB`M@?tkGt3x_RvjQ~l zuHGtsD=JPr#Huddx{(K>ksswYB!5I@&$B#;w6GVVDQg`eE+2HZ&h*jeD3y#5_Zd9K zY`1KM2=lubwy0}$KGSwtMKtB|27h2QAOb1TH$Sf;b^pp`w9iB98|{7!V(o`k=Lh;- zR2Rh$XMyG2xVGY=`uNE(_Tgy_{;r`I=L>Vy)1yaw>*n)98nz%}_O=Nu!o!_6nk3f2 zN6VA74@XDq4f>5r!xlu;EIOWD&+X2Ci51bF`-l2^w>@5FRP|gEk99$wIA-XbR>6uL4;KOh|kZwlzEgQzJ&UEJ?Q)1P6 zrN^`36j$EMFR8zMAI%*9cICylh$tERwyo*DuDo70Xd}ax9v!E$?PF^26UK5CDba1J zTSvI#t`X);x538KUD53O=PrEC{>$pclH)1Ifivw`FR4`@OklfaIdji2VXH`|x@K|} z)y%s$kRbwlAwT*q^>UPXVCofh_Z0_@Ehr&UqTg$aPBVJHZ|Q>TQdZN~yf!CC6T2xd*ar>NTO=lW!1J z#|+TRybMWM+U~W4sP!_?;^A}to{DHXV0pKmw`=slr|67O6M3M7o1g0zy87m`B$d1W z7*iXXp1QP5B2R9tS@L!^?y1-d(TZ~9U3;^?%ih%Re&zJZSDUe_r0tSHuT(@IOKolG z)MbnVee;vL$yZ-+=!{Q@b3J`y;{c1hpLZ^XvZGFP*Wm1BZEjibv>7#mbnJy_nTLAv zB)^&Q%x6pXa7ilcg=j^I-xp&Z3f%8A>0wKT+M*t)ADtmjYAH@}^cFu~OZ>Y`FIJW` zU(xlWdM#I=Wra#!kJPOldRzJxDj~AgHCxqBoOoI1mYq&^w_0Lt8S2EGA1uV2pO34T z7xuO&)yx#*qgtCCRt2z8gDNK%d)S(lCmyLzrzFIpD(#sY{l9c=aeno~)%KQD-R^cs zQY-hjcs$yir6NC>NABJ6)_sOSg%Uim1@%Bm^!<5cg7q8y^8zkO9XE8dDGOQQoDbVc+6kxXIVF2<$G%TW#6+}#Jg9*YvS?wMKN(RQ_p-jFljfn zh}g~Sds_AFs#(uUfm`Zd!~HG&8Y|g^I2k|E(u04BlMvVo{X}!g!CaP9L*2G`AzhRT z(TZ|)!a|G3_^mx9pQE2qTDrv=Xuta*)?17v^f{s_vr*h=D@uG@?vQ+rUPJ%W`R?@{ z);*aKI|_KC572|MKepeWY3VWPswVjZeSm1X!&0lDh47E>>4m+}R%k=A?(jN74>Rod zh~$co1FZR~UDu4RLsFw z!o-}2h&rr~)iUVFRW-6mZ+ou;$JK*0<^`haRdHT|hykbDS}mTA4$QNpeI87tu@dmQ zv-SV?O+~bC`RlfI58#CVgyb6(able)MsvpJt^QW8O?}_1wgdM0cmT~SG7qFxGoY7+ z7?kk0I%G>f>$!E|e*p31NU|5oi@i`kxL)JnDT^#9U&XMqvvg{{Pm+7DS+*=!9kWIm_q52IyPtg|R?4my5WGxH6|c{V5qE z1AC!2|FiD4PanJxfxTo~*)jIG!WOhH`o`Y>tF6$3h$!8{9>+^E66q z7bTSSm|vrjJ~3!<>iKLh6I)Pow41o4_f&gXVU>^n!$A@Pd!f~-4pv-i^Yp~Lz6A + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-04T16:26:40 + 2023-07-04T16:26:40 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.8980392 0.9176471 0.9294118 1 + + + 1.45 + + + + + + + + + + + + + + + + + 7.14974e-4 0.03261768 -0.01653522 3.97754e-5 0.03255385 -0.01671677 7.32845e-4 0.03254431 -0.01671463 7.43911e-4 0.03241652 -0.016851 3.59111e-5 0.0324406 -0.01684433 4.24825e-5 0.03231358 -0.01692205 7.30629e-4 0.03222239 -0.01693719 3.76381e-5 0.03217506 -0.01695573 0.001438438 0.03262174 -0.01641058 0.001428127 0.03257751 -0.01661622 0.001441657 0.03242778 -0.01680016 0.001436591 0.03222244 -0.01689362 0.002143085 0.03262233 -0.01632744 0.002106249 0.03259003 -0.01650863 0.002125501 0.03252434 -0.01662653 0.002140045 0.0323975 -0.01674777 0.002141058 0.0322104 -0.01682209 0.003537833 0.03262072 -0.01612609 0.002837061 0.03259742 -0.01638716 0.002858459 0.03250253 -0.01654744 0.002883017 0.03239989 -0.01663357 0.002866804 0.03229802 -0.01669007 0.002883672 0.03217488 -0.0167163 0.003537833 0.03260833 -0.01620125 0.003537774 0.03216242 -0.01659232 0.003537893 0.0325722 -0.01630991 0.003537833 0.03245788 -0.01646548 0.003537833 0.0322951 -0.01656424 -1.49253e-4 0.03262168 -0.002453804 1.46999e-4 0.03512167 -0.002457201 -4.16854e-4 0.03512167 -0.002425014 -5.64416e-4 0.03262168 -0.002386033 -9.75721e-4 0.03262168 -0.002247035 -0.001123964 0.03512167 -0.002181351 -0.001409173 0.03262168 -0.002000868 -0.001632094 0.03512167 -0.001823067 -0.001742184 0.03262168 -0.001715779 -0.002045989 0.03512167 -0.001354873 -0.002020776 0.03262168 -0.001382708 -0.002313077 0.03262168 -8.33956e-4 -0.002343654 0.03512167 -7.3794e-4 -0.002466917 0.03262168 -1.02103e-4 -0.002446591 0.03512167 -2.5321e-4 -0.00246185 0.03512167 1.84894e-4 -0.00241971 0.03262168 5.21113e-4 -0.002384006 0.03512167 6.77394e-4 -0.002230942 0.03262168 0.001113474 -0.00221014 0.03512167 0.001144707 -0.001984357 0.03512167 0.001515567 -0.001853525 0.03262168 0.001686453 -0.001697599 0.03512167 0.001847028 -0.001374363 0.03262168 0.002113699 -0.001358509 0.03512167 0.002118408 -9.18221e-4 0.03512167 0.002358913 -8.19001e-4 0.03262168 0.002396583 -3.35491e-4 0.03512167 0.002519667 -2.73589e-4 0.03262168 0.002527356 1.62613e-4 0.03512167 0.00254172 2.24979e-4 0.03262168 0.002538502 4.7253e-5 0.03262168 -0.01371061 1.3152e-4 0.03512167 -0.01370632 -1.58128e-4 0.03512167 -0.01369524 -3.2291e-4 0.03262168 -0.01366084 -5.16101e-4 0.03512167 -0.01358503 -6.3387e-4 0.03262168 -0.01351404 -8.68272e-4 0.03512167 -0.01332759 -8.75092e-4 0.03262168 -0.013318 -0.001088082 0.03262168 -0.01301062 -0.001096546 0.03512167 -0.01299315 -0.001212894 0.03262168 -0.01259285 -0.0011909 0.03512167 -0.01269692 -0.001214504 0.03512167 -0.01238536 -0.001185834 0.03262168 -0.01218795 -0.001155734 0.03512167 -0.01208013 -0.001054883 0.03262168 -0.01183813 -9.9592e-4 0.03512167 -0.01174062 -8.21294e-4 0.03262168 -0.01154547 -7.11203e-4 0.03512167 -0.01145309 -5.34667e-4 0.03262168 -0.01134079 -4.40163e-4 0.03512167 -0.01129931 -1.18462e-4 0.03262168 -0.0112099 -1.4886e-4 0.03512167 -0.01121896 1.3147e-4 0.03512167 -0.01120889 0.01248508 0.03262168 -0.001212656 0.01241302 0.03512167 -0.001204848 0.0121476 0.03262168 -0.00114715 0.01213085 0.03512167 -0.001141488 0.01189249 0.03262168 -0.001031696 0.01184916 0.03512167 -0.001006126 0.01160258 0.03262168 -7.96198e-4 0.01161414 0.03512167 -8.02624e-4 0.01144796 0.03512167 -5.75985e-4 0.01142823 0.03262168 -5.35286e-4 0.01132458 0.03262168 -2.76554e-4 0.01131981 0.03512167 -2.57749e-4 0.01128453 0.03262168 1.26405e-4 0.01128596 0.03512167 5.11812e-5 0.01132458 0.03512167 3.61272e-4 0.0113781 0.03262168 5.20698e-4 0.01147246 0.03512167 7.0472e-4 0.01157063 0.03262168 8.41273e-4 0.01167011 0.03512167 9.4472e-4 0.01187443 0.03262168 0.001109004 0.01189249 0.03512167 0.001116454 0.01225805 0.03512167 0.001268267 0.01219022 0.03262168 0.001245021 0.01246607 0.03262168 0.001293361 0.0126627 0.03512167 0.001289606 -1.48937e-5 0.03262168 0.01128727 -8.69368e-5 0.03512167 0.01129508 -3.52362e-4 0.03262168 0.01135283 -3.6913e-4 0.03512167 0.01135843 -6.34536e-4 0.03262168 0.01148331 -6.50815e-4 0.03512167 0.0114938 -8.73838e-4 0.03262168 0.01168441 -9.07816e-4 0.03512167 0.01172024 -0.001042544 0.03262168 0.01190769 -0.001096546 0.03512167 0.01200681 -0.001184523 0.03262168 0.01225316 -0.001209735 0.03512167 0.01239597 -0.001209735 0.03262168 0.01268869 -0.001184523 0.03512167 0.0128315 -0.001096546 0.03262168 0.01307785 -9.95922e-4 0.03512167 0.01325935 -9.07853e-4 0.03262168 0.01336437 -7.11193e-4 0.03512167 0.01354688 -5.91535e-4 0.03262168 0.01363247 -4.40137e-4 0.03512167 0.01370066 -1.18451e-4 0.03262168 0.01379001 -1.48845e-4 0.03512167 0.01378101 1.62747e-4 0.03512167 0.01378959 -0.01251488 0.03262168 -0.001212656 -0.01258689 0.03512167 -0.001204848 -0.01285231 0.03262168 -0.00114715 -0.01286906 0.03512167 -0.001141488 -0.01310747 0.03262168 -0.001031696 -0.01315081 0.03512167 -0.001006126 -0.01339739 0.03262168 -7.96196e-4 -0.01340782 0.03512167 -7.79703e-4 -0.01361113 0.03512167 -4.65223e-4 -0.01361429 0.03262168 -4.53837e-4 -0.01369869 0.03262168 -1.52968e-4 -0.01369541 0.03512167 -1.67123e-4 -0.01371449 0.03512167 1.14603e-4 -0.01371234 0.03262168 1.2664e-4 -0.01366096 0.03262168 4.02925e-4 -0.01365572 0.03512167 4.19817e-4 -0.01354765 0.03262168 6.69093e-4 -0.01354694 0.03512167 6.68678e-4 -0.01335942 0.03512167 9.17605e-4 -0.01333767 0.03262168 9.40081e-4 -0.01310741 0.03512167 0.001116454 -0.01306968 0.03262168 0.001138269 -0.01274192 0.03512167 0.001268267 -0.01280975 0.03262168 0.001245021 -0.0125339 0.03262168 0.001293361 -0.0123372 0.03512167 0.001289606 -0.01539564 0.03512173 -0.003207385 -0.01578032 0.03487169 -0.003457546 -0.01462143 0.03487169 -0.003483712 -0.01445305 0.03512167 -0.00324577 -0.01345324 0.03487169 -0.003623545 -0.01326853 0.03512167 -0.003402113 -0.01230424 0.03487169 -0.003877103 -0.01210463 0.03512167 -0.003673136 -0.01118546 0.03487169 -0.004241943 -0.01097261 0.03512167 -0.004056274 -0.01010763 0.03487169 -0.004714727 -0.009883165 0.03512167 -0.004547894 -0.009081542 0.03487169 -0.005290567 -0.008847177 0.03512167 -0.005143165 -0.008116543 0.03487169 -0.005964338 -0.007873833 0.03512167 -0.005836665 -0.007183969 0.03487169 -0.006763756 -0.00679475 0.03512167 -0.006790518 -0.006134092 0.03487169 -0.00789386 -0.005840957 0.03512167 -0.007869601 -0.005147635 0.03512167 -0.008842706 -0.005295097 0.03487169 -0.009077072 -0.004552304 0.03512167 -0.009878873 -0.004719197 0.03487169 -0.01010316 -0.004060745 0.03512167 -0.01096814 -0.004246532 0.03487169 -0.01118081 -0.003677606 0.03512167 -0.01210016 -0.003881633 0.03487169 -0.01229953 -0.003406584 0.03512167 -0.01326406 -0.003628015 0.03487169 -0.01344877 -0.003250241 0.03512167 -0.01444882 -0.003488183 0.03487169 -0.01461696 -0.003211855 0.03512173 -0.01539504 -0.003462016 0.03487175 -0.01577883 -0.01539784 0.03511989 0.003290116 -0.01563966 0.03512167 0.001858949 -3.83365e-4 0.03412419 -0.01745563 -8.02368e-4 0.03512167 -0.01572078 -0.01734793 0.03411763 0.002105593 -0.01715809 0.03412169 0.003289997 -0.01742875 0.03412079 0.001203596 -0.01746231 0.03412204 6.94941e-5 -0.01740604 0.03412044 -0.001422047 -0.01572972 0.03512167 -8.03927e-4 -0.01718139 0.0341193 -0.003108739 -0.01680916 0.03412294 -0.00471282 -0.01547884 0.03487163 -0.004631161 -0.01626306 0.03412288 -0.006338357 -0.01494193 0.03487163 -0.006139576 -0.0155605 0.03412288 -0.007902741 -0.0142588 0.03487163 -0.007587611 -0.01492124 0.03412169 -0.009039044 -0.01343619 0.03487163 -0.008961021 -0.0142067 0.03412038 -0.01013231 -0.01248216 0.03487163 -0.01024657 -0.01314312 0.0341205 -0.01147693 -0.01140594 0.03487163 -0.01143163 -0.01195317 0.03412055 -0.01271092 -0.01021808 0.03487163 -0.01250475 -0.01064831 0.03412061 -0.01382255 -0.008930265 0.03487163 -0.01345533 -0.009241044 0.03412073 -0.01480114 -0.007555007 0.03487163 -0.01427417 -0.007744789 0.03412079 -0.01563745 -0.006105661 0.03487163 -0.01495337 -0.006174266 0.03412091 -0.01632326 -0.00459659 0.03487163 -0.01548624 -0.004544675 0.03412097 -0.01685214 -0.002881646 0.03412169 -0.01721739 -0.001668691 0.03412115 -0.01737409 -3.22014e-4 0.03214669 0.01704156 3.78732e-5 0.03012168 0.01704233 -0.001253604 0.03012168 0.01699787 -0.002495825 0.03012168 0.01685243 -0.003462076 0.03112167 0.01667815 -0.00373733 0.03012168 0.0166217 -0.004716753 0.03112173 0.0163688 -0.005319952 0.03012168 0.01618105 -0.00627315 0.03112173 0.01583248 -0.006957828 0.03012168 0.01554346 -0.007695078 0.03112173 0.01518517 -0.008518338 0.03012168 0.01473778 -0.009063601 0.03112173 0.01440626 -0.009931981 0.03012168 0.01381802 -0.01041078 0.03112173 0.01345837 -0.01124727 0.03012168 0.01276302 -0.01166039 0.03112173 0.01238399 -0.01245111 0.03012168 0.01158344 -0.01280051 0.03112167 0.01119333 -0.01353168 0.03012168 0.01029121 -0.01382035 0.03112167 0.009897291 -0.01447921 0.03012168 0.008898377 -0.01470994 0.03112167 0.008508324 -0.01528406 0.03012168 0.00741887 -0.01546078 0.03112167 0.007039546 -0.01593858 0.03012168 0.005867063 -0.01606589 0.03112167 0.005504846 -0.01643645 0.03012168 0.004257917 -0.01660513 0.03112173 0.003545045 -0.01659595 0.03218406 0.003542363 -0.01675134 0.03212028 0.002719044 -0.01670384 0.03012168 0.002994358 -0.01687985 0.03012168 0.001764595 -0.01686286 0.03212064 0.001886546 -0.0169332 0.03212094 0.001050531 -0.01696723 0.03012168 7.46389e-5 -0.01696228 0.03212094 2.11316e-4 -0.01694989 0.032121 -6.28363e-4 -0.01688623 0.03012168 -0.001615703 -0.016896 0.03212094 -0.001466393 -0.01680082 0.03212094 -0.002300739 -0.01663756 0.03012168 -0.003289699 -0.01666456 0.03212094 -0.003129363 -0.01648771 0.03212141 -0.003949403 -0.01622378 0.03012168 -0.004930675 -0.01627045 0.03212141 -0.004760622 -0.01601332 0.03212141 -0.0055601 -0.0156489 0.03012168 -0.006522476 -0.01571708 0.03212136 -0.006345927 -0.01538282 0.03212207 -0.007115066 -0.01491862 0.03012168 -0.008049309 -0.01501053 0.03212201 -0.007867932 -0.01461291 0.03215301 -0.00857979 -0.01404023 0.03012168 -0.009495854 -0.01415675 0.03212201 -0.009313821 -0.01367735 0.03212195 -0.01000338 -0.01302218 0.03012168 -0.01084822 -0.01316529 0.03212296 -0.01066738 -0.01262021 0.03212296 -0.0113064 -0.01187485 0.03012168 -0.01209259 -0.01204425 0.03212291 -0.01191776 -0.01143878 0.03212285 -0.01249986 -0.0106095 0.03012168 -0.01321667 -0.0108065 0.0321244 -0.01305031 -0.01014649 0.03212428 -0.01357001 -0.009238362 0.03012168 -0.01420962 -0.0094617 0.03212416 -0.01405644 -0.008764445 0.03214788 -0.01450079 -0.007775545 0.03012168 -0.01506119 -0.008034229 0.0321477 -0.01491838 -0.00727415 0.03212237 -0.01530504 -0.006235182 0.03012168 -0.01576316 -0.00651592 0.03214132 -0.01564323 -0.005745291 0.0322144 -0.01593714 -0.004632532 0.03012168 -0.01630854 -0.004934132 0.03214085 -0.01621401 -0.004126667 0.03214895 -0.0164389 -0.002983391 0.03012168 -0.01669192 -0.003309786 0.03217631 -0.01662212 -0.001304328 0.03012168 -0.01690936 3.78732e-5 0.03012168 -0.01695758 3.78732e-5 0.03012168 -0.0174576 0.00120902 0.03412246 -0.01742309 0.001401066 0.03012168 -0.01740938 0.002444505 0.03412151 -0.01729154 0.002646088 0.03012168 -0.01726216 0.003537833 0.03112167 -0.01710402 0.003285527 0.03412169 -0.01715362 0.003537833 0.03379619 -0.01710402 0.003930628 0.03012168 -0.0170226 0.004367887 0.03112167 -0.01691347 0.005196034 0.03012168 -0.01668012 0.005592346 0.03112173 -0.01655608 0.006496071 0.03012168 -0.01622772 0.007117271 0.03112173 -0.01596707 0.008078515 0.03012168 -0.01550668 0.008645415 0.03112173 -0.01520007 0.009581387 0.03012168 -0.0146324 0.01009196 0.03112173 -0.01428735 0.01098978 0.03012168 -0.01361358 0.01144266 0.03112173 -0.01323765 0.01228976 0.03012168 -0.01246052 0.0126847 0.03112167 -0.01206082 0.01346915 0.03012168 -0.01118415 0.0138061 0.03112167 -0.01076811 0.01451575 0.03012168 -0.009797573 0.01479589 0.03112167 -0.009372115 0.01541996 0.03012168 -0.008313834 0.0156449 0.03112167 -0.007885575 0.0161724 0.03012168 -0.006748199 0.01634466 0.03112167 -0.006323277 0.01676601 0.03012168 -0.005115747 0.01688849 0.03112167 -0.004700005 0.01718425 0.03112167 -0.003457605 0.01718425 0.03379619 -0.003457605 0.01723384 0.03412169 -0.003205239 0.01741427 0.03411906 -0.002087295 0.01719367 0.03012168 -0.003437042 0.01745808 0.03012168 -0.001680314 0.01753634 0.03412139 -4.37706e-4 0.01754307 0.03012168 4.2365e-5 0.0175203 0.03412199 8.25836e-4 0.01748889 0.03012168 0.001350104 0.01741427 0.03411906 0.002172052 0.01734948 0.03012168 0.002646863 0.01718425 0.03112167 0.003542363 0.01723384 0.03412169 0.003289997 0.01718425 0.03379619 0.003542363 0.01700127 0.03012168 0.004364311 0.01688849 0.03112167 0.004784762 0.0164895 0.03012168 0.006024062 0.01634466 0.03112167 0.006408095 0.01581549 0.03012168 0.007625341 0.0156449 0.03112167 0.007970333 0.01498633 0.03012168 0.009151637 0.01479589 0.03112167 0.009456872 0.01400977 0.03012168 0.01058846 0.0138061 0.03112167 0.01085287 0.0128954 0.03012168 0.01192158 0.01268464 0.03112167 0.01214557 0.01165419 0.03012168 0.01313787 0.01144266 0.03112173 0.01332235 0.01029825 0.03012168 0.01422524 0.01009196 0.03112173 0.01437205 0.008840858 0.03012168 0.01517295 0.008645474 0.03112173 0.01528483 0.007296502 0.03012168 0.01597148 0.00711745 0.03112173 0.0160517 0.00560826 0.03012168 0.01663941 0.005592286 0.03112173 0.01664084 0.004367887 0.03112167 0.01699817 0.003930509 0.03012168 0.01710736 0.003537833 0.03112167 0.01718878 0.003285527 0.03412169 0.01723837 0.002116739 0.03411889 0.01742529 0.003537833 0.03379619 0.01718878 0.002646088 0.03012168 0.01734685 0.001401007 0.03012168 0.01749414 8.23353e-4 0.0341221 0.01752442 3.78732e-5 0.03012168 0.01754236 -4.47674e-4 0.03412246 0.01753866 -0.001325309 0.03012168 0.01749414 -0.002040982 0.03411889 0.01742529 -0.002570331 0.03012168 0.01734685 -0.003462076 0.03112167 0.01718878 -0.003209769 0.03412169 0.01723837 -0.003462076 0.03379619 0.01718878 -0.003854751 0.03012168 0.01710736 -0.00429213 0.03112167 0.01699817 -0.005532503 0.03012168 0.01663941 -0.005516588 0.03112173 0.01664084 -0.007041811 0.03112173 0.0160517 -0.007220685 0.03012168 0.01597154 -0.008569777 0.03112173 0.01528477 -0.008765101 0.03012168 0.01517295 -0.0100162 0.03112173 0.01437211 -0.01022249 0.03012168 0.01422524 -0.0113669 0.03112173 0.01332235 -0.01157844 0.03012168 0.01313787 -0.01260888 0.03112167 0.01214557 -0.01281958 0.03012168 0.01192164 -0.01373034 0.03112167 0.01085281 -0.01393395 0.03012168 0.01058852 -0.0147202 0.03112167 0.009456753 -0.01491057 0.03012168 0.009151697 -0.01556915 0.03112167 0.007970392 -0.01573985 0.03012168 0.007625162 -0.0162689 0.03112167 0.006408095 -0.01641374 0.03012168 0.006024122 -0.01681274 0.03112167 0.004784762 -0.01692557 0.03012168 0.004364252 -0.01710855 0.03112167 0.003542363 -0.01710855 0.03379619 0.003542363 -0.01727527 0.03012168 0.002637863 -0.01741319 0.03012168 0.001350104 -0.01746737 0.03012168 1.34588e-5 -0.01737827 0.03012168 -0.001722395 -0.01711738 0.03012168 -0.003440976 -0.01668739 0.03012168 -0.005124986 -0.01609253 0.03012168 -0.006758034 -0.01533871 0.03012168 -0.008324027 -0.01443326 0.03012168 -0.009807646 -0.01338517 0.03012168 -0.0111941 -0.01220452 0.03012168 -0.01246994 -0.01090312 0.03012168 -0.01362246 -0.009493768 0.03012168 -0.01464027 -0.007990062 0.03012168 -0.01551342 -0.006406962 0.03012168 -0.01623314 -0.004760026 0.03012168 -0.01679235 -0.003065526 0.03012168 -0.01718533 -0.001339912 0.03012168 -0.01740825 -0.01223462 0.03512167 -0.001191318 0.001097083 0.03512167 -0.01569175 4.1615e-4 0.03512167 -0.0136522 -0.01193904 0.03512167 -0.001094996 6.71439e-4 0.03512167 -0.01353734 -0.01164704 0.03512167 -9.13483e-4 9.43981e-4 0.03512167 -0.01332765 0.00230515 0.03512167 -0.01556706 -0.01136928 0.03512167 -5.77111e-4 -0.01124083 0.03512167 -2.36402e-4 0.003285825 0.03511983 -0.01539272 -0.01392281 0.03512167 0.003385782 0.003381311 0.03512167 -0.01391834 0.001137018 0.03512167 -0.01305615 -0.01274448 0.03512167 0.003593862 0.003589391 0.03512167 -0.01273995 0.001263141 0.03512167 -0.01273721 -0.01194489 0.03512167 0.001188457 0.001286685 0.03512167 -0.01235455 -0.01159185 0.03512167 0.003915965 0.003911435 0.03512167 -0.01158738 0.001213312 0.03512167 -0.01201945 -0.01159316 0.03512167 9.47188e-4 0.001013755 0.03512167 -0.01166665 -0.01047635 0.03512167 0.004348874 -0.01133298 0.03512167 5.9724e-4 0.004344344 0.03512167 -0.01047182 7.43475e-4 0.03512167 -0.01142257 -0.009408473 0.03512167 0.004888474 0.004884004 0.03512167 -0.009403884 4.46627e-4 0.03512167 -0.01127159 -0.01120883 0.03512167 1.36301e-4 6.38018e-4 0.03512167 -0.002390801 -0.008398056 0.03512167 0.005529761 0.00552541 0.03512167 -0.008393406 0.001236855 0.03512167 -0.002159297 0.006262183 0.03512167 -0.007450461 -0.007454991 0.03512167 0.006266653 0.001756131 0.03512167 -0.00178194 -0.006588339 0.03512167 0.007091939 0.00708729 0.03512167 -0.006584048 0.002116501 0.03512167 -0.001353383 0.007993161 0.03512167 -0.005802094 -0.005806446 0.03512167 0.007997751 0.002344489 0.03512167 -9.29954e-4 0.008970975 0.03512167 -0.005112171 0.002488434 0.03512167 -4.71036e-4 -0.005116581 0.03512167 0.008975505 -0.004038512 0.03512167 0.01110917 0.01110464 0.03512167 -0.004034042 -0.004525363 0.03512167 0.01001602 0.01001137 0.03512167 -0.004520952 -0.003660559 0.03512167 0.01224452 0.01224005 0.03512167 -0.003656089 0.002539575 0.03512167 -1.99099e-5 0.01340681 0.03512167 -0.003390729 -0.003395199 0.03512167 0.01341122 2.65307e-4 0.03512167 0.01130867 0.01276528 0.03512167 -0.001191318 0.002510964 0.03512167 4.33027e-4 0.01306092 0.03512167 -0.001094996 -0.003244876 0.03512167 0.0145983 0.01335287 0.03512167 -9.13487e-4 0.0145936 0.03512167 -0.003240406 0.01565605 0.03512167 -0.002162277 0.01546955 0.0351209 -0.003209054 -0.002166748 0.03512167 0.01566058 -0.003213524 0.0351209 0.01547408 0.006664216 0.03512167 0.00709182 0.001831293 0.03512167 0.001791656 0.007530629 0.03512167 0.006266713 0.002165019 0.03512167 0.001362979 0.001460075 0.03512167 0.002100765 0.005882322 0.03512167 0.007997632 0.001083672 0.03512167 0.002317249 0.01357716 0.03512167 -6.55528e-4 0.008473932 0.03512167 0.005529701 0.002384543 0.03512167 9.15362e-4 0.005192399 0.03512167 0.008975446 6.1223e-4 0.03512167 0.002479374 0.009484171 0.03512167 0.004888474 0.00460124 0.03512167 0.01001578 5.60919e-4 0.03512167 0.01140493 0.0157966 0.03512167 -6.6164e-4 0.01370769 0.03512167 -4.06664e-4 -6.66003e-4 0.03512167 0.01580107 0.01055204 0.03512167 0.004348874 0.00411427 0.03512167 0.01110911 8.52943e-4 0.03512167 0.01158648 0.0116676 0.03512167 0.003915965 0.001077175 0.03512167 0.01184445 0.0137912 0.03512167 -4.16402e-5 0.003736376 0.03512167 0.01224422 0.001207649 0.03512167 0.0120933 0.01282018 0.03512167 0.003593862 0.001277089 0.03512167 0.01236456 0.01575201 0.03512167 0.001584649 0.01375734 0.03512167 3.30365e-4 0.001580178 0.03512167 0.01575648 5.5508e-4 0.03512167 0.0136885 0.01305502 0.03512167 0.001188516 0.003471016 0.03512167 0.01341098 0.001286685 0.03512167 0.01264536 0.01364856 0.03512167 6.22373e-4 0.01399856 0.03512167 0.003385782 0.001213312 0.03512167 0.01298052 0.01343011 0.03512167 9.26577e-4 8.83241e-4 0.03512167 0.01346731 0.003320634 0.03512167 0.01459807 0.001067221 0.03512167 0.01325482 0.01547324 0.03511983 0.003290235 0.003289282 0.0351209 0.01547408 0.001329362 0.03012168 -0.01691311 0.002571582 0.03012168 -0.01676774 0.003537833 0.03112167 -0.01659339 0.003813207 0.03012168 -0.01653695 0.004792451 0.03112173 -0.0162841 0.00539571 0.03012168 -0.01609635 0.006349027 0.03112173 -0.01574772 0.007033586 0.03012168 -0.0154587 0.007771015 0.03112173 -0.01510035 0.008594155 0.03012168 -0.01465296 0.009139478 0.03112173 -0.0143215 0.01000773 0.03012168 -0.01373326 0.0104866 0.03112173 -0.01337355 0.01132279 0.03012168 -0.01267844 0.01173615 0.03112173 -0.01229929 0.01252657 0.03012168 -0.01149904 0.01287627 0.03112167 -0.01110857 0.01360744 0.03012168 -0.01020652 0.0138961 0.03112167 -0.009812533 0.01455485 0.03012168 -0.008813738 0.0147857 0.03112167 -0.008423507 0.01535975 0.03012168 -0.007334172 0.01553654 0.03112167 -0.006954848 0.01601421 0.03012168 -0.005782544 0.01614165 0.03112167 -0.005420148 0.01651221 0.03012168 -0.00417304 0.01668089 0.03112173 -0.003460288 0.01666843 0.03221333 -0.003457605 0.01684671 0.03012168 -0.002533197 0.01692456 0.03213447 -0.001925528 0.01702415 0.03012168 -7.87114e-4 0.01699757 0.03212404 -0.001134991 0.01702338 0.03223955 -3.64355e-4 0.01701867 0.03012168 9.44264e-4 0.01684671 0.03012168 0.002617955 0.01668089 0.03112173 0.003544986 0.01667022 0.03219383 0.003542244 0.01651221 0.03012168 0.004257798 0.01614159 0.03112167 0.005504965 0.01601421 0.03012168 0.005867302 0.01553654 0.03112167 0.007039666 0.01535981 0.03012168 0.00741887 0.0147857 0.03112167 0.008508265 0.01455491 0.03012168 0.008898377 0.01389616 0.03112167 0.009897172 0.01360744 0.03012168 0.01029121 0.01287633 0.03112167 0.01119321 0.01252669 0.03012168 0.01158362 0.01173621 0.03112173 0.01238393 0.01132297 0.03012168 0.01276308 0.0104866 0.03112173 0.01345831 0.01000773 0.03012168 0.01381802 0.009139418 0.03112173 0.01440626 0.008594095 0.03012168 0.01473772 0.007770836 0.03112173 0.01518517 0.007033646 0.03012168 0.0155434 0.006348967 0.03112173 0.01583242 0.00539571 0.03012168 0.01618105 0.004792511 0.03112173 0.01636886 0.003537833 0.03220695 0.01667326 0.003537833 0.03112167 0.01667815 0.003813087 0.03012168 0.0166217 0.002571582 0.03012168 0.01685243 0.001329362 0.03012168 0.01699787 -0.003477275 0.03262168 0.01482087 -0.002688825 0.03262114 0.01638036 -0.003462016 0.03261417 0.01627063 -0.01637899 0.03262156 0.002140998 -0.01500052 0.03262168 0.003550529 -0.01400095 0.03262168 0.003627955 -0.003633856 0.03262168 0.01349782 -0.01283925 0.03262168 0.003828763 1.83449e-4 0.03262138 0.01657879 -0.003891587 0.03262168 0.01234698 -0.01222312 0.03262168 0.00127238 3.07555e-4 0.03262168 0.01376748 -0.01170229 0.03262168 0.004142761 -0.0163145 0.03262031 -0.002587735 -0.01192688 0.03262168 0.001175343 6.0124e-4 0.03262168 0.01366031 -0.004260957 0.03262168 0.01122701 0.001814305 0.03261852 0.0165233 8.43614e-4 0.03262168 0.01350259 -0.01158314 0.03262168 9.43491e-4 -0.01060199 0.03262168 0.004566609 -0.01592254 0.03261899 -0.004461169 -0.00473845 0.03262168 0.01014882 -0.01131308 0.03262168 5.49963e-4 -0.009548425 0.03262168 0.005096495 0.003553032 0.03262168 0.01482075 -0.005474567 0.03262168 0.008872926 -0.01121914 0.03262168 1.98088e-4 0.001098394 0.03262168 0.01321554 -0.01554965 0.03262013 -0.005545198 0.003709614 0.03262168 0.01349771 0.001270353 0.03262168 0.01279145 -0.01214379 0.03262168 -0.001169562 0.003967344 0.03262168 0.01234704 0.001275539 0.03262168 0.01232415 -0.01404297 0.0326212 -0.008678019 0.004336655 0.03262168 0.01122725 0.001110792 0.03262168 0.01188671 -0.01177996 0.03262168 -0.001013934 8.43636e-4 0.03262168 0.01158213 0.004814088 0.03262168 0.01014894 6.08912e-4 0.03262168 0.01142859 3.56154e-4 0.03262168 0.01133036 0.005395054 0.03262168 0.009122788 -0.006562829 0.03262168 0.007477879 -0.007403373 0.03262168 0.006650924 -0.008310079 0.03262168 0.005894541 -0.01278072 0.03261852 -0.0104708 -0.0112161 0.03262168 -8.22985e-5 -0.01129645 0.03262168 -4.25768e-4 6.98969e-4 0.03262168 0.002457261 0.006073832 0.03262168 0.008158624 0.001275479 0.03262168 0.002224802 -0.01148837 0.03262168 -7.46296e-4 0.007045865 0.03262168 0.007050096 0.001739919 0.03262168 0.001876831 -0.01068228 0.03261989 -0.01260685 0.002083599 0.03262168 0.001489937 0.008385777 0.03262168 0.005894541 0.00235188 0.03262168 9.98591e-4 0.002495467 0.03262168 5.2109e-4 0.009624183 0.03262168 0.005096495 0.01067775 0.03262168 0.004566609 0.01177793 0.03262168 0.004142761 -0.008580803 0.03261768 -0.01413238 -0.007166922 0.03261971 -0.01488941 0.01291495 0.03262168 0.003828763 0.002539396 0.03262168 8.90337e-5 4.11519e-4 0.03262168 -0.002436578 0.002505123 0.03262168 -3.92666e-4 2.76896e-4 0.03262168 -0.01122754 0.01277685 0.03262168 0.00127238 0.0140767 0.03262168 0.003627955 0.01307302 0.03262168 0.001175343 0.01341676 0.03262168 9.43517e-4 0.01507622 0.03262168 0.003550529 -0.00169605 0.03262042 -0.01644092 0.01642161 0.03262072 0.002258121 0.01621925 0.03261947 0.003457605 0.007473289 0.03262168 -0.006558477 0.001818656 0.03262168 -0.001720905 0.00644803 0.03262168 -0.007617771 0.001381397 0.03262168 -0.002070367 0.002165019 0.03262168 -0.001278281 0.005722701 0.03262168 -0.008547484 9.52436e-4 0.03262168 -0.002287745 0.008627712 0.03262168 -0.005642473 0.002367317 0.03262168 -8.71935e-4 0.01365715 0.03262168 6.05683e-4 0.005092024 0.03262168 -0.009543895 5.73066e-4 0.03262168 -0.01132458 0.009624302 0.03262168 -0.005011677 0.004562199 0.03262168 -0.01059734 9.16836e-4 0.03262168 -0.0115565 0.01067757 0.03262168 -0.004481971 0.01649677 0.03262192 0.001216053 0.00413829 0.03262168 -0.0116977 0.001157164 0.03262168 -0.01189428 0.01177775 0.03262168 -0.004058122 0.001274347 0.03262168 -0.01223963 0.016577 0.03262037 4.2412e-4 0.01377439 0.03262168 2.60349e-4 0.003824353 0.03262168 -0.01283448 0.01291441 0.03262168 -0.003744184 0.01651924 0.03262096 -0.001583158 0.01377552 0.03262168 -1.7584e-4 0.001275539 0.03262168 -0.01267582 0.01285612 0.03262168 -0.001169562 4.07971e-4 0.03262168 -0.01365739 0.003623485 0.03262168 -0.01399642 0.001148581 0.03262168 -0.01303756 0.01407659 0.03262168 -0.003543257 0.01310878 0.03262168 -0.001071393 7.09573e-4 0.03262168 -0.01351404 9.50803e-4 0.03262168 -0.013318 0.01334357 0.03262168 -9.17871e-4 0.01361078 0.03262168 -6.13301e-4 0.003546059 0.03262168 -0.01499617 0.01507622 0.03262168 -0.003465831 0.0152921 0.03487056 0.00353986 0.01644885 0.03254121 0.003542304 0.01660817 0.03237509 0.003542363 0.003537833 0.03236657 0.01661455 0.003537893 0.03251123 0.01649296 0.003537833 0.03259754 0.01633059 0.003537833 0.03262031 0.01621139 0.01380395 0.03487175 0.003664612 0.01264399 0.03487175 0.003892779 0.01151192 0.03487169 0.004233956 0.01041907 0.03487169 0.004684805 0.009375929 0.03487169 0.005240976 0.008392333 0.03487169 0.005897164 0.007478117 0.03487169 0.006646931 0.006642162 0.03487169 0.007482886 0.005892574 0.03487169 0.008396923 0.005236387 0.03487169 0.009380578 0.004680275 0.03487169 0.01042366 0.004229426 0.03487169 0.01151651 0.003888309 0.03487175 0.01264834 0.003660082 0.03487175 0.01380842 0.00353533 0.03487056 0.01529657 -0.003462076 0.03253549 0.01646083 -0.003462135 0.03238528 0.01660531 -0.003461897 0.03221249 0.01667225 -0.003459632 0.03487056 0.01529657 -0.01653206 0.03237479 0.003542363 -0.01641535 0.03250622 0.003542363 -0.01628434 0.03258442 0.003542304 -0.01615732 0.03261762 0.003542304 -0.01520979 0.03487181 0.003544688 -0.003584325 0.03487175 0.01380854 -0.003812491 0.03487175 0.01264858 -0.004153788 0.03487169 0.01151633 -0.004604578 0.03487169 0.0104236 -0.005160748 0.03487169 0.0093804 -0.005816876 0.03487169 0.008396923 -0.006566405 0.03487169 0.007482886 -0.007619678 0.03487175 0.006446778 -0.008800148 0.03487169 0.00555706 -0.009814858 0.03487169 0.004950106 -0.01088428 0.03487169 0.00444591 -0.01199811 0.03487169 0.00404936 -0.01314526 0.03487175 0.00376439 -0.01431548 0.03487175 0.003593623 0.00353533 0.03487056 -0.01521188 0.01658308 0.03241217 -0.003457605 0.01646369 0.03252685 -0.003457486 0.01634669 0.03258991 -0.003457605 0.01621925 0.03261947 -0.003457605 0.003660082 0.03487175 -0.01372373 0.003888309 0.03487175 -0.01256364 0.004229426 0.03487169 -0.01143175 0.004680335 0.03487169 -0.0103389 0.005236387 0.03487169 -0.009295821 0.005892634 0.03487169 -0.008312165 0.006642341 0.03487169 -0.007398009 0.007478237 0.03487169 -0.006562113 0.008392274 0.03487169 -0.005812466 0.00937587 0.03487169 -0.005156278 0.01041913 0.03487169 -0.004600107 0.01151198 0.03487169 -0.004149198 0.01264381 0.03487175 -0.003808081 0.01380389 0.03487175 -0.003579854 0.0152921 0.03487056 -0.003455102 -0.01649528 0.03259479 0.002208232 -0.01649004 0.03255486 0.002785325 -0.0166037 0.03246271 0.002791643 -0.01669961 0.03231441 0.002819597 -0.01667749 0.03250354 0.001964211 -0.01676869 0.03239881 0.001977443 -0.01682686 0.03228223 0.001983344 -0.01658636 0.03259772 0.001115858 -0.01674538 0.03251194 0.001131057 -0.01685112 0.03238719 0.001141607 -0.01690238 0.03228223 0.001145362 -0.01654994 0.03261721 -3.78468e-4 -0.01668441 0.03257268 -1.20908e-4 -0.01678562 0.03250354 3.00388e-4 -0.0168845 0.03238922 3.05245e-4 -0.01693624 0.03228217 3.04655e-4 -0.01677775 0.03250354 -5.33572e-4 -0.01687675 0.03238916 -5.33619e-4 -0.01692837 0.03228211 -5.36708e-4 -0.01656657 0.03258091 -0.00181365 -0.01674509 0.0324909 -0.001360118 -0.01686638 0.03232306 -0.001370251 -0.01666319 0.03248196 -0.002196252 -0.01677644 0.03232002 -0.002206861 -0.01638257 0.03258144 -0.003004848 -0.01649785 0.03251135 -0.003010988 -0.01660841 0.03238648 -0.003036022 -0.01666533 0.03224021 -0.003045916 -0.01622068 0.03257834 -0.003812611 -0.01635897 0.03248184 -0.003840267 -0.01647126 0.03232049 -0.003859639 -0.01607334 0.03254187 -0.004634797 -0.01621437 0.03239804 -0.004668533 -0.0162754 0.03225076 -0.004683375 -0.01574993 0.03258228 -0.005398809 -0.01589471 0.03248274 -0.005445539 -0.01600664 0.0323109 -0.005476415 -0.01517063 0.03260552 -0.006709218 -0.01550585 0.03255784 -0.006196558 -0.01560926 0.03247326 -0.006228029 -0.01570856 0.03232938 -0.00626105 -0.01521891 0.03252893 -0.006974458 -0.01531404 0.03243309 -0.007006883 -0.01538425 0.03229916 -0.007039904 -0.01450157 0.0326038 -0.008052468 -0.014804 0.03256255 -0.007698953 -0.01491576 0.03247278 -0.007742464 -0.01501041 0.03231692 -0.007791578 -0.01420873 0.03258436 -0.008669555 -0.01448315 0.03250128 -0.008462071 -0.01457685 0.03236883 -0.008519411 -0.01401537 0.03253215 -0.009146153 -0.01410102 0.0324279 -0.009208559 -0.01416432 0.03230166 -0.00924623 -0.0131424 0.03259366 -0.01017719 -0.01352524 0.03254115 -0.009826838 -0.01361793 0.03245073 -0.00987935 -0.01368671 0.03230041 -0.009939014 -0.01309686 0.0324757 -0.01052743 -0.0131753 0.03229916 -0.01060742 -0.0124157 0.03258407 -0.01108145 -0.01253849 0.03248178 -0.01117217 -0.01262736 0.03231739 -0.01124519 -0.01184248 0.03259527 -0.01164764 -0.01193112 0.03252524 -0.011743 -0.01199471 0.03243559 -0.01181185 -0.01205688 0.0322982 -0.01186305 -0.01125335 0.03258228 -0.01226085 -0.01137202 0.03248393 -0.01235646 -0.01144963 0.03230905 -0.0124455 -0.01061826 0.0325908 -0.01279151 -0.01074916 0.0324769 -0.01291275 -0.0108174 0.03229916 -0.01300257 -0.009996294 0.03257346 -0.0133332 -0.01010316 0.03245794 -0.01344472 -0.01015889 0.03229498 -0.01352524 -0.009300649 0.03259962 -0.01375013 -0.009371101 0.03252434 -0.01387417 -0.009438335 0.03240984 -0.01396578 -0.009477376 0.03227037 -0.01401954 -0.008642852 0.03255701 -0.01428091 -0.008709609 0.03247272 -0.0143693 -0.008753001 0.03232991 -0.01445895 -0.007934451 0.03255933 -0.01468837 -0.007998824 0.03244125 -0.01480948 -0.008030414 0.03230881 -0.01488214 -0.007162511 0.0325796 -0.01503658 -0.007234513 0.03247386 -0.01516574 -0.00728327 0.03230762 -0.01526689 -0.006422042 0.03257775 -0.01536941 -0.006470501 0.03248167 -0.01550006 -0.006505608 0.03232526 -0.01560539 -0.004873633 0.03261953 -0.01578658 -0.0051831 0.03257942 -0.01583194 -0.005675613 0.03250551 -0.01578307 -0.005724251 0.03237354 -0.015881 -0.004918098 0.03246742 -0.01607948 -0.004932284 0.032301 -0.01618283 -0.003422021 0.03259682 -0.01626342 -0.004067897 0.03255796 -0.0161935 -0.004100859 0.03245151 -0.0163232 -0.004122555 0.03228807 -0.01641356 -0.003277182 0.03248971 -0.01647102 -0.003306627 0.0323348 -0.0165801 -0.002426326 0.03257346 -0.016496 -0.002462387 0.03243649 -0.01666706 -0.002483904 0.03222483 -0.01676237 -0.001611709 0.03259587 -0.01654165 -0.00161904 0.0325185 -0.01668304 -0.001640796 0.03240174 -0.0167911 -0.001645326 0.03222638 -0.01686674 -7.80459e-4 0.03257459 -0.01665621 -7.97451e-4 0.03247547 -0.01679277 -8.01455e-4 0.0323714 -0.01687109 -8.01637e-4 0.03222244 -0.01693016 0.002275407 0.03259891 0.01654982 0.002799749 0.0325694 0.01654058 0.002825796 0.03248488 0.01665502 0.002831459 0.03236842 0.01674854 0.002853751 0.03220033 0.01680338 0.002078115 0.03251153 0.01673769 0.002113282 0.0323655 0.01685422 0.002088367 0.03220915 0.01691353 0.001322627 0.03256869 0.01672506 0.001385271 0.0324499 0.0168699 0.00136274 0.03232413 0.01695042 0.001327753 0.03220081 0.0169903 3.36728e-4 0.03260594 0.01667356 5.74544e-4 0.03256136 0.01677608 6.00056e-4 0.0324524 0.01691401 6.31416e-4 0.03228795 0.01700681 6.13243e-4 0.0321604 0.01703304 -8.04032e-4 0.0326066 0.01665478 -4.85055e-4 0.03255999 0.01678234 -1.23694e-4 0.03249335 0.01687866 -3.36712e-4 0.03244119 0.01692771 -1.08791e-4 0.03228569 0.01701796 -5.87694e-4 0.03230983 0.01699882 -0.001658856 0.0325573 0.01670825 -0.001245498 0.03250664 0.01681572 -0.001265764 0.03239101 0.0169171 -0.001304805 0.0322178 0.01698422 -0.002251029 0.03259783 0.01654535 -0.002043128 0.0324676 0.01677757 -0.002019941 0.03232997 0.0168752 -0.00202322 0.03218001 0.01691514 -0.002747118 0.03254175 0.01658403 -0.002748489 0.0324108 0.01672458 -0.002774715 0.03221249 0.01680284 0.01654249 0.03260165 -0.002156436 0.01652359 0.03257673 -0.002680003 0.01665371 0.03254169 -0.002277314 0.01666343 0.03248012 -0.00270158 0.01672011 0.03241521 -0.002786517 0.0167877 0.03227561 -0.002733826 0.0168116 0.03215581 -0.002720475 0.01679861 0.03245097 -0.001955747 0.01688015 0.03231811 -0.001968204 0.01667821 0.03260058 -6.28707e-4 0.0167613 0.03254801 -0.001146733 0.01688802 0.0324347 -0.001158893 0.01696825 0.03228938 -0.001166403 0.01684463 0.03251671 -3.6256e-4 0.01695042 0.03239911 -3.59367e-4 0.01674395 0.03257948 4.21025e-4 0.0168994 0.03246557 4.37652e-4 0.01697736 0.03235369 4.30037e-4 0.01702797 0.0322138 4.3231e-4 0.01665747 0.03259938 0.001189649 0.01682502 0.032503 0.001213371 0.01692163 0.0323885 0.001208245 0.01699 0.03223109 0.001211285 0.01657277 0.03260582 0.001947224 0.01676076 0.03249883 0.001971423 0.01686471 0.03236293 0.001993536 0.01692098 0.03221154 0.001988232 0.01646041 0.03260231 0.002721846 0.01652359 0.03257673 0.002680003 0.01660507 0.03252863 0.002777695 0.01666146 0.03248298 0.00277549 0.01672011 0.03241521 0.002786517 0.0167877 0.03227561 0.002733826 0.01681131 0.03215819 0.002806007 + + + + + + + + + + -0.01394283 -0.9260045 0.3772551 -0.01215833 -0.7300962 0.6832362 -0.01911735 -0.7472212 0.6643004 -0.009701251 -0.522474 0.8526 -0.03338068 -0.4036703 0.9142954 -0.009875953 -0.2359375 0.971718 -0.03091961 -0.9768531 0.2116649 -0.009190797 -0.9258766 0.3777143 -0.05182003 -0.7762934 0.6282383 -0.03787386 -0.7306685 0.6816811 -0.05958807 -0.4124065 0.9090492 -0.05634593 -0.4019362 0.9139324 -0.02039843 -0.983542 0.1795243 -0.01548635 -0.9773554 0.2110372 -0.05973714 -0.8762457 0.4781476 -0.04988533 -0.7762809 0.6284102 -0.08370459 -0.693534 0.7155447 -0.08583766 -0.4110713 0.907553 -0.1001585 -0.367697 0.9245362 -0.02266508 -0.9885631 0.1490949 -0.01987564 -0.9835699 0.179431 -0.07033604 -0.8763573 0.4764986 -0.07967829 -0.8623663 0.4999756 -0.0977354 -0.6934803 0.7138158 -0.1128843 -0.6544131 0.7476634 -0.1331403 -0.464667 0.8754189 -0.1234472 -0.3668283 0.9220618 -0.1479477 -0.2254779 0.9629493 -0.02782148 -0.9862732 0.1627609 -0.06869626 -0.9467718 0.3144904 -0.08599805 -0.86226 0.4991114 -0.1233949 -0.799611 0.5877041 -0.132706 -0.6555755 0.7433774 -0.1708911 -0.5112142 0.8422924 -0.1656844 -0.458272 0.8732328 -0.1803485 -0.2285694 0.9566768 -0.1860757 -0.2032653 0.9612799 0.05699366 -0.005381822 0.9983601 0.1610792 0.005890905 0.9869239 0.3200652 -0.004109978 0.9473867 0.3258035 -0.005532979 0.9454213 0.4938212 0.006428301 0.8695397 0.5761891 -0.006739318 0.8172888 0.6503263 0.00397098 0.7596448 0.749252 -0.004564762 0.6622693 0.767095 5.97225e-4 0.6415334 0.8826068 0.003669857 0.4700978 0.9006382 -0.005666792 0.4345328 0.9786016 0.004075229 0.2057239 0.9781827 0.004597723 0.2076959 0.9993754 -0.006023705 0.03482222 0.9971218 0.006648302 -0.0755245 0.9877409 -0.004338383 -0.1560422 0.9527817 0.005384922 -0.3036083 0.9372333 -0.003430247 -0.3486863 0.8351139 0.006102681 -0.5500433 0.8541365 -5.97505e-4 -0.5200487 0.7562969 -0.005143761 -0.6542084 0.6654775 0.006439685 -0.7463902 0.624778 -0.002493619 -0.7807986 0.4793876 -0.001388788 -0.8776022 0.453844 0.004592359 -0.8910693 0.2659506 -0.003962695 -0.9639786 0.2332228 0.002782464 -0.9724195 0.02232635 0.001837015 -0.9997491 0.04417961 -0.001980185 -0.9990217 0.03829473 -0.003006696 0.999262 0.1333081 0.00484991 0.9910628 0.2942742 -0.006246566 0.9557007 0.4269672 0.005566954 0.90425 0.6306955 0.001261591 0.7760294 0.5901238 -0.004872858 0.8072981 0.8218622 -5.28343e-5 0.5696865 0.8259369 -0.001160383 0.5637612 0.9581579 0.001225173 0.2862377 0.952793 0.004253685 0.303591 0.9971296 -0.005631685 0.07550501 0.9977484 0.006177663 -0.06678378 0.9819613 -0.003658056 -0.1890468 0.9365588 0.003851592 -0.3504893 0.9047428 -0.004734754 -0.4259322 0.7815161 0.00589466 -0.6238573 0.7105423 -0.005289256 -0.7036347 0.5810947 0.004482865 -0.8138236 0.4934548 -0.004217982 -0.8697613 0.2999841 0.00449258 -0.9539337 0.2659758 -2.42098e-4 -0.9639798 0.03590357 -0.003167212 -0.9993503 0.1906127 0.00243479 0.9816623 0.2191189 -7.2895e-4 0.9756979 0.4121889 7.11312e-4 0.9110982 0.4330788 -0.001708149 0.9013544 0.6305263 0.00299555 0.7761622 0.654672 -0.001087963 0.7559124 0.8064942 -0.002213716 0.591238 0.8314375 0.002467334 0.5556129 0.9283083 -0.001292169 0.3718095 0.9275668 -0.001033484 0.373656 0.99509 0.001160681 0.09896796 0.994063 0.002684354 0.1087736 0.9923363 -0.004305183 -0.1234914 0.9729231 0.006110429 -0.2310487 0.918439 -0.005544304 -0.3955239 0.8572847 0.00554341 -0.5148128 0.771979 -0.004405975 -0.6356328 0.6612637 0.004736304 -0.7501386 0.6111938 -0.002073168 -0.7914783 0.3835225 -3.07911e-5 -0.9235316 0.3954813 -0.002188742 -0.9184715 0.1726319 0.004477202 -0.9849763 0.05267703 -0.005639314 -0.9985957 0.1906124 0.002435505 0.9816624 0.219132 -7.29213e-4 0.975695 0.4196766 7.69224e-4 0.9076735 0.4330908 -9.70797e-4 0.9013499 0.6434061 9.69979e-4 0.7655245 0.6610915 -0.001767992 0.7503033 0.7977929 0.002202093 0.6029277 0.8351268 -0.003775775 0.5500446 0.9249326 0.004899799 0.3800997 0.9602001 -0.006280243 0.2792426 0.9983104 0.006757676 0.05771327 0.9983105 -0.006757497 -0.057711 0.9601981 0.006280541 -0.2792496 0.9149826 -0.007548749 -0.4034228 0.8351206 0.006307303 -0.5500308 0.7105461 -0.004535555 -0.7036361 0.64656 0.00481981 -0.7628479 0.4934349 -0.006170928 -0.869761 0.3159343 0.006731569 -0.9487572 0.2659627 -2.41924e-4 -0.9639833 0.02756208 -0.003268837 -0.9996148 0.1906079 0.002434909 0.9816633 0.2191138 -7.28777e-4 0.9756991 0.4121892 7.11913e-4 0.911098 0.4330776 -0.001708149 0.901355 0.630535 0.00299561 0.7761551 0.6611076 -0.00219357 0.750288 0.8447437 0.00137788 0.5351693 0.8397557 -7.96586e-5 0.5429645 0.9628442 2.44488e-5 0.2700579 0.9622749 2.94983e-4 0.2720792 0.9977167 -9.06365e-4 0.06753402 0.9988086 0.001103878 0.04878818 0.98315 -2.20075e-5 -0.1828013 0.9819685 -7.70048e-4 -0.1890432 0.9201242 7.29421e-4 -0.3916264 0.9162629 -3.31017e-4 -0.4005775 0.7987334 -3.30352e-4 -0.6016851 0.7904261 0.001374781 -0.6125559 0.6195188 -0.001663088 -0.7849801 0.5946194 0.00197184 -0.8040049 0.3835278 -0.002261221 -0.9235267 0.379876 -0.00170356 -0.9250358 0.1726338 0.004477083 -0.9849759 0.05268174 -0.005639076 -0.9985955 -0.01563984 0.7192375 -0.6945883 -0.02909475 0.6992921 -0.7142438 -0.08300071 0.7157484 -0.6934084 -0.09370219 0.6979845 -0.7099561 -0.1505565 0.7154594 -0.6822395 -0.1623389 0.6983042 -0.6971494 -0.216732 0.7151277 -0.6645448 -0.2293767 0.698636 -0.6777125 -0.2809004 0.7148169 -0.6404153 -0.2941706 0.6989759 -0.6518409 -0.3424351 0.7144751 -0.610134 -0.356089 0.6993364 -0.6197816 -0.4007146 0.714155 -0.5739428 -0.4145734 0.6996796 -0.581874 -0.455709 0.7139415 -0.5316174 -0.4799655 0.6890613 -0.5429804 -0.5008322 0.7298725 -0.4652454 -0.5451328 0.6860324 -0.4818609 -0.5726178 0.7110959 -0.4079846 -0.5701205 0.7152088 -0.4042758 -0.610141 0.7144701 -0.3424332 -0.6197921 0.6993238 -0.3560955 -0.640425 0.7148028 -0.2809141 -0.6518288 0.6989932 -0.2941561 -0.6645521 0.7151147 -0.2167524 -0.6776978 0.6986544 -0.2293639 -0.6822488 0.7154514 -0.1505521 -0.697144 0.6983097 -0.162339 -0.6934044 0.7157521 -0.08300125 -0.7099596 0.6979815 -0.09369724 -0.6946799 0.7191497 -0.01561087 -0.7142766 0.6992639 -0.02896523 -0.4918528 0.8673661 0.07587397 -0.4957426 0.8643134 0.08486223 0.03973501 0.9992103 -7.402e-5 -0.5032373 0.8636226 0.03014004 -0.4933509 0.8696705 0.0166853 -0.5072236 0.8615803 -0.02009123 -0.4911478 0.8642988 -0.1084513 -0.4916638 0.8635329 -0.1121514 -0.4912098 0.8683617 -0.06827068 -0.4935382 0.8671939 -0.06629502 -0.4766528 0.8643829 -0.1601384 -0.4809307 0.8679997 -0.1236216 -0.4588263 0.8642996 -0.2060697 -0.4671415 0.8684068 -0.1662788 -0.4375355 0.864605 -0.2470244 -0.4483518 0.8684715 -0.2115134 -0.42157 0.8635904 -0.2765691 -0.4252123 0.868525 -0.2546741 -0.396595 0.8627433 -0.3136666 -0.397923 0.8685846 -0.2953271 -0.3639341 0.8628038 -0.3508868 -0.3668831 0.8685568 -0.3331756 -0.3277982 0.8628686 -0.3847159 -0.3322578 0.8685256 -0.3677884 -0.2885371 0.8629343 -0.4148382 -0.2943865 0.8684891 -0.3988276 -0.2536392 0.8684512 -0.4259808 -0.2465255 0.8630006 -0.4409707 -0.2021715 0.8630732 -0.4628515 -0.2104067 0.8684143 -0.4489829 -0.1651149 0.8683728 -0.4676173 -0.1559064 0.8631473 -0.4802812 -0.124269 0.8675824 -0.4815164 -0.1087973 0.8627678 -0.4937559 -0.06635552 0.8686779 -0.4909131 -0.08752852 0.8598598 -0.5029714 -0.06177473 0.8745768 -0.480936 -0.03400921 0.8628382 -0.5043349 0.05789971 -0.005090951 -0.9983095 0.03441077 0.005737423 -0.9993913 0.09588825 -0.004144132 -0.9953835 0.1476225 -0.003765225 -0.9890367 0.1162588 0.003562986 -0.9932126 0.1867545 -0.005361974 -0.982392 0.1779267 3.94317e-4 -0.9840437 0.1827179 0.005184471 -0.9831517 0.2393525 -0.01109504 -0.9708694 0.2681814 0.01909112 -0.9631792 0.3257552 -0.01899755 -0.9452633 0.3626965 0.02095419 -0.9316717 0.4142311 -0.02061086 -0.9099385 0.494551 -0.01836574 -0.8689545 0.4586638 0.01987081 -0.8883878 0.5753743 -0.01860433 -0.8176786 0.5452533 0.01952922 -0.8380438 0.651818 -0.01806139 -0.7581605 0.6255831 0.01901584 -0.7799257 0.6997473 0.01841878 -0.7141531 0.7221736 -0.01744753 -0.6914918 0.7670004 0.01776355 -0.6414006 0.785762 -0.01679313 -0.6183011 0.8267143 0.01706665 -0.5623631 0.8419805 -0.01606464 -0.5392688 0.8902825 -0.01527094 -0.4551528 0.8783108 0.01629066 -0.4778127 0.930211 -0.0144115 -0.3667426 0.9212846 0.01546001 -0.3885816 0.963832 -0.02646005 -0.2651941 0.9552214 0.01456832 -0.2955332 0.9827392 -0.008935987 -0.184781 0.9845387 -7.21748e-4 -0.1751658 0.9781837 0.01744598 -0.207008 0.9899035 0.004019141 -0.141687 0.9911512 -3.33956e-4 -0.1327378 0.9964702 -0.003362238 -0.08388048 0.9994008 -1.12133e-4 -0.0346145 0.9986319 0.008208394 -0.05164337 0.9998847 -0.003493964 0.01478087 0.9979414 9.29029e-5 0.06413394 0.9988203 0.008153259 0.04787224 0.9935504 -0.003603458 0.1133348 0.9867481 3.06072e-4 0.1622599 0.9891165 0.008090674 0.1469119 0.9775242 -0.003712296 0.2107908 0.9659436 5.2613e-4 0.2587525 0.9696161 0.008000969 0.2445012 0.9519811 -0.003829956 0.3061333 0.935707 7.50914e-4 0.3527773 0.9405116 0.007933199 0.3396691 0.917134 -0.003924846 0.3985598 0.9020888 0.007827699 0.4314796 0.8963757 9.84734e-4 0.4432942 0.8731285 -0.004089355 0.4874732 0.8547369 0.006915032 0.5190157 0.8493694 0.001441836 0.5277971 0.8210763 -0.004119992 0.5708038 0.7989051 0.00766766 0.6014083 0.7918705 0.001444935 0.6106875 0.7608094 -0.004235506 0.6489617 0.7351567 0.007532894 0.6778555 0.7278414 0.0017066 0.6857433 0.6930747 -0.004303395 0.720853 0.6641322 0.007443964 0.7475782 0.6565855 0.001926958 0.7542491 0.6186425 -0.0044142 0.7856602 0.5790902 0.002209544 0.8152604 0.5865204 0.00729078 0.8099017 0.5375325 -0.00456506 0.8432309 0.4964536 0.002201497 0.8680606 0.50309 0.006505608 0.8642095 0.453312 -0.004947423 0.8913382 0.4072985 0.002399921 0.913292 0.4146772 0.007001042 0.9099417 0.3567875 -0.005859911 0.9341672 0.3233541 0.00399363 0.9462696 0.3221568 0.003286957 0.9466806 0.2683397 -0.005019724 0.9633113 0.2188201 0.001622498 0.9757639 0.226422 0.006129622 0.97401 0.1677893 -0.006824076 0.9857993 0.1235428 -7.29363e-5 0.9923393 0.1284474 0.002718806 0.9917127 0.07490724 -0.008050978 0.997158 0.0303719 -9.15007e-4 0.9995383 0.03590881 0.001302599 0.9993543 0.02042013 0.002649664 -0.9997881 0.0353446 -0.001720488 -0.9993737 0.1058865 0.001682996 -0.9943768 0.1174531 -0.001372098 -0.9930776 0.1729628 0.001485109 -0.9849272 0.1618139 -0.002698183 -0.9868177 0.1927905 0 -0.98124 0.183309 -0.008043408 -0.9830225 0.2237752 0.00853312 -0.9746034 0.2612372 -0.008871793 -0.965234 0.2801659 0.008045971 -0.959918 0.3286558 -0.01310068 -0.944359 0.3602426 0.01928228 -0.9326594 0.4145181 -0.02038937 -0.9098127 0.4484815 0.01973092 -0.8935743 0.5027487 -0.02003991 -0.8642003 0.5335433 0.01936542 -0.845551 0.5859936 -0.01965761 -0.8100773 0.6135306 0.01896953 -0.7894431 0.6634457 -0.01922267 -0.7479775 0.687671 0.0185455 -0.7257856 0.7343498 -0.01878565 -0.6785113 0.7552581 0.01807874 -0.6551782 0.7980009 -0.01829117 -0.6023788 0.8156328 0.01758742 -0.5783025 0.8537967 -0.01778084 -0.5203029 0.868218 0.01705813 -0.4958896 0.9011763 -0.01723897 -0.4331099 0.9125177 0.01650148 -0.4087044 0.9396727 -0.01665711 -0.3416694 0.9480832 0.01591706 -0.3176238 0.9812392 0 -0.1927945 0.9872216 -0.002913177 -0.1593269 0.9689239 -0.01606112 -0.2468369 0.9728007 0.004358232 -0.2316024 0.9841253 0.005578041 -0.1773875 0.9888538 -0.004323661 -0.1488279 0.9972685 0.003408968 -0.07378298 0.9987761 -0.004233479 -0.04927939 0.9999145 0.003204286 0.01267647 0.99691 0.002472221 0.07851463 0.9991416 -0.002415776 0.04135674 0.9942622 -0.003418445 0.1069172 0.9872216 -0.002913177 0.159327 0.9812393 0 0.1927939 0.9843668 0.004954695 0.1760607 0.9799349 -0.01602494 0.1986731 0.9727355 0.0123462 0.2315889 0.9554767 -0.01609963 0.2946271 0.9480919 0.01534682 0.3176261 0.9215781 -0.01547145 0.3878848 0.9125425 0.01467305 0.408719 0.8786013 -0.01478898 0.477327 0.8682596 0.01397991 0.4959133 0.8156904 0.01322394 0.5783376 0.826976 -0.01406896 0.5620611 0.7553231 0.01242625 0.6552348 0.7671902 -0.01329654 0.6412819 0.6877421 0.01157152 0.7258629 0.6998388 -0.01247292 0.714192 0.6136096 0.01064139 0.7895379 0.6255685 -0.01158303 0.7800834 0.5336178 0.009657025 0.8456707 0.5451223 -0.01064538 0.838289 0.4485635 0.008588969 0.8937098 0.459284 -0.009630322 0.8882374 0.3603082 0.00441426 0.932823 0.367868 -0.008754372 0.9298368 0.2801699 0.00309664 0.9599455 0.2686492 -0.01234477 0.963159 0.157929 -0.003035366 0.9874459 0.1927956 0 0.981239 0.2237747 0.008532285 0.9746036 0.1709664 0.003318905 0.9852713 0.183308 -0.008042573 0.9830226 0.1174482 -0.003921568 0.9930714 0.07645159 0.003487467 0.9970673 0.01121252 0.002273201 0.9999346 0.03534793 -0.002466619 0.9993721 -0.07101249 0.004468202 0.9974654 -0.03534471 -0.003377914 0.9993696 -0.1174483 -0.003921449 0.9930713 -0.1579284 -0.003035485 0.987446 -0.1927967 0 0.9812389 -0.1709663 0.003319144 0.9852713 -0.1833081 -0.00804156 0.9830227 -0.2237721 0.008532643 0.9746043 -0.280169 0.003093779 0.9599457 -0.2686513 -0.01234555 0.9631585 -0.3603107 0.004409432 0.9328219 -0.3678661 -0.0087471 0.9298377 -0.4485691 0.008584737 0.8937069 -0.4592787 -0.009629666 0.8882402 -0.5336178 0.009651243 0.8456707 -0.5451177 -0.01064777 0.838292 -0.6136087 0.01064223 0.7895386 -0.6255711 -0.01158791 0.7800812 -0.6877412 0.01156139 0.7258639 -0.6998309 -0.01247316 0.7141997 -0.7553216 0.01242375 0.6552366 -0.7671889 -0.01329219 0.6412835 -0.8156907 0.01321482 0.5783374 -0.8269708 -0.0140661 0.562069 -0.8682621 0.01398003 0.495909 -0.8786044 -0.01478946 0.4773213 -0.9125407 0.01468175 0.4087225 -0.9215804 -0.0154705 0.3878792 -0.9480926 0.01534646 0.3176237 -0.9554772 -0.01610404 0.2946253 -0.9812393 0 0.1927939 -0.9873919 -0.003005683 0.1582667 -0.9727346 0.01234745 0.2315925 -0.9844756 0.005460441 0.1754373 -0.9799649 -0.01616102 0.1985141 -0.9959921 -0.006232738 0.08922445 -0.9943145 2.24774e-5 0.1064841 -0.999562 8.47165e-4 0.02958267 -0.9991758 -0.002413511 0.04052084 -0.9992868 0.001789391 -0.03771924 -0.9986795 -0.003089606 -0.05128103 -0.9912441 0.003026902 -0.1320073 -0.9886689 -0.003365814 -0.1500756 -0.9741078 0.00318098 -0.2260618 -0.9689095 -0.003997147 -0.2473835 -0.9479326 0.003961086 -0.3184466 -0.9396006 -0.004139959 -0.342248 -0.9122247 0.004097402 -0.4096698 -0.9010284 -0.004276692 -0.4337391 -0.8715518 0.003311336 -0.4902924 -0.8535757 -0.004045128 -0.5209531 -0.8370594 0.002993643 -0.5471039 -0.7977055 -0.003777325 -0.6030353 -0.7842817 0.003589808 -0.6203945 -0.733968 -0.003612995 -0.6791746 -0.7198355 0.003419816 -0.6941363 -0.6629872 -0.00343728 -0.7486228 -0.6484878 0.003240525 -0.7612183 -0.5854588 -0.003251254 -0.8106957 -0.5709293 0.00304985 -0.8209936 -0.5021513 -0.003058075 -0.8647744 -0.4878941 0.002848863 -0.8728982 -0.4001917 0.0026322 -0.9164277 -0.4138674 -0.002851903 -0.9103327 -0.308669 0.002400517 -0.9511665 -0.3214918 -0.002633273 -0.9469088 -0.2145305 0.002035558 -0.9767152 -0.2259377 -0.002398014 -0.9741388 -0.1281294 -0.002061486 -0.9917554 -0.1281175 -0.002057671 -0.9917569 -0.06328934 0.003322541 -0.9979897 -0.0357849 -0.003266274 -0.9993543 9.37832e-6 1 6.41754e-6 1.61528e-5 1 6.45987e-6 0 1 0 1.44666e-6 1 -5.04009e-6 -2.32251e-6 1 -3.85451e-6 0 1 1.38246e-5 0 1 3.59974e-6 0 1 -1.3164e-6 -1.03159e-6 1 -2.28489e-6 0 1 -5.86879e-6 -1.39259e-7 1 -6.12619e-6 1.19083e-5 1 -7.66051e-6 2.61304e-6 1 -1.17854e-5 0 1 1.89324e-5 -2.52678e-6 1 6.46929e-6 0 1 -1.21882e-6 -4.27687e-6 1 0 0 1 -1.70585e-5 5.7159e-6 1 -1.21492e-5 0 1 2.44e-6 0 1 2.86584e-6 9.24004e-6 1 -1.34455e-5 -1.70866e-5 1 -1.51837e-5 -3.73853e-6 1 0 0 1 2.13356e-6 -0.001342475 0.999998 0.001499295 -5.41104e-6 1 -2.85455e-6 0 1 1.40693e-5 0.00217545 0.9999967 -0.001425385 -9.45579e-7 1 -6.25315e-6 0 1 -1.90804e-6 0 1 6.61907e-6 0 1 2.65467e-6 0 1 6.00186e-6 0 1 -5.30758e-6 0 1 -2.10804e-6 0 1 6.11715e-7 0 1 1.20063e-6 0 1 8.7612e-7 0 1 5.87969e-7 0 1 -1.42562e-6 0 1 -2.20241e-6 0 1 -7.80045e-6 -3.89944e-7 1 0 -2.01518e-6 1 -6.9193e-7 -3.05135e-7 1 0 1.60607e-6 1 -1.39983e-6 0 1 5.90388e-6 0 1 2.4811e-6 0 1 6.71799e-7 0 1 8.46185e-6 0 1 -1.51866e-5 0 1 -7.41479e-7 0 1 3.67484e-7 0 1 -2.11698e-7 0 1 6.47132e-7 0 1 3.55246e-7 0 1 -8.30618e-7 0 1 2.06963e-6 0 1 -7.96442e-6 0 1 -1.26363e-6 0 1 2.51029e-6 0 1 1.81219e-6 0 1 -4.09953e-6 0 1 -1.03858e-5 0 1 7.9552e-6 0 1 9.73615e-6 0 1 -5.62078e-6 0 1 1.21226e-6 0 1 -2.30505e-6 0 1 3.09388e-5 0 1 2.62266e-6 0 1 2.0607e-6 0 1 -4.29207e-6 0 1 8.33332e-7 0 1 -6.4521e-7 0 1 1.74391e-5 0 1 -2.12764e-5 0 1 -6.3356e-7 9.47667e-4 0.9999992 -9.42327e-4 -9.26094e-4 0.9999992 9.56528e-4 0 1 5.08275e-6 0 1 -3.39217e-6 0 1 5.7805e-6 0 1 8.58868e-6 0 1 -3.37772e-6 2.27523e-6 1 1.9097e-6 1.09927e-6 1 -4.16152e-6 1.30147e-6 1 0 -1.04976e-6 1 5.34817e-6 0 1 -3.39199e-6 0 1 4.86528e-7 0 1 1.29167e-6 0 1 -4.78001e-6 0 1 3.24358e-6 0 1 2.55634e-7 0 1 2.09613e-6 0 1 -3.41165e-5 3.36295e-6 1 4.36807e-6 3.35214e-6 1 -1.64426e-5 -1.89663e-6 1 3.01122e-6 2.1769e-6 1 4.30956e-6 0 1 1.59666e-6 0 1 -2.89944e-6 0 1 -1.91822e-6 3.46984e-6 1 5.22169e-6 -9.50483e-7 1 2.88731e-6 0 1 5.7392e-6 0 1 4.47614e-6 0 1 1.27134e-6 0 1 -3.94454e-6 0 1 -1.75013e-5 3.22233e-6 1 -3.25033e-6 1.7666e-6 1 -1.15939e-6 4.11677e-7 1 -7.95186e-6 -1.598e-6 1 6.49457e-6 0 1 1.9774e-6 0 1 5.28842e-6 0 1 -1.21167e-5 1.51321e-6 1 1.77122e-5 0 1 6.53025e-7 0 1 2.79952e-5 1.33308e-6 1 -1.28384e-5 9.10128e-7 1 6.0272e-6 0 1 -1.69793e-6 1.7169e-6 1 0 0 1 -5.05794e-6 0 1 1.62868e-5 -8.79126e-7 1 -1.51846e-6 0.001353323 0.9999983 0.001315653 6.15417e-4 0.9999995 9.2887e-4 -0.02668637 -9.21634e-4 0.9996435 -0.03441327 0.001630663 0.9994063 -0.06156808 -0.006124794 0.9980841 -0.1010963 -0.004077911 0.9948683 -0.1162649 0.00188905 0.9932165 -0.1411609 -0.003328979 0.9899812 -0.180328 0.002782821 0.9836027 -0.186225 -0.001013457 0.9825066 -0.1827255 0.005180299 0.9831504 -0.2393425 -0.01110166 0.9708718 -0.2681875 0.01909297 0.9631776 -0.3257569 -0.01899927 0.9452627 -0.3626923 0.02095246 0.9316734 -0.4142415 -0.02061229 0.9099337 -0.4945622 -0.01835578 0.8689485 -0.4586685 0.0198791 0.8883851 -0.5753766 -0.01859712 0.8176772 -0.5452553 0.01953285 0.8380424 -0.651826 -0.01806318 0.7581536 -0.6255807 0.01901936 0.7799277 -0.6997288 0.01841479 0.7141712 -0.7221711 -0.01746219 0.6914941 -0.7669953 0.01776754 0.6414068 -0.7857622 -0.01680004 0.6183006 -0.826714 0.01706159 0.5623638 -0.8419807 -0.01606774 0.5392683 -0.8783075 0.01630043 0.4778182 -0.8902826 -0.01526564 0.4551528 -0.9212814 0.01546406 0.3885893 -0.9302113 -0.0144149 0.3667414 -0.9552211 0.01457566 0.2955338 -0.9638314 -0.02645236 0.265197 -0.9817718 -0.01163429 0.1897073 -0.9845362 -8.88596e-4 0.1751791 -0.9795652 0.02278357 0.1998325 -0.9900563 -0.004168748 0.1406102 -0.9957553 0.002770781 0.09199935 -0.9948468 0.007951974 0.1010778 -0.9993775 -0.007260859 0.0345233 -0.9999826 -0.001512467 0.005721271 -0.9999883 0.003670334 -0.003168225 -0.9987946 -0.007435977 -0.04851925 -0.9960709 -0.002331733 -0.08852839 -0.9947554 0.004550814 -0.1021818 -0.9910694 -0.00494343 -0.1332553 -0.9821668 -0.01027423 -0.1877307 -0.9845504 -9.65043e-4 -0.175099 -0.9795652 0.02278852 -0.1998324 -0.9638305 -0.02645546 -0.2651998 -0.9552207 0.01456993 -0.2955355 -0.9302085 -0.01441663 -0.3667485 -0.9212814 0.01545178 -0.3885897 -0.8902828 -0.01526606 -0.4551524 -0.8783079 0.01629763 -0.4778175 -0.8419837 -0.01606142 -0.539264 -0.8267158 0.01706552 -0.5623608 -0.7857689 -0.01679605 -0.6182922 -0.7669981 0.0177741 -0.6414031 -0.7221745 -0.01744902 -0.6914908 -0.6997407 0.01842242 -0.7141594 -0.6518277 -0.0180599 -0.7581522 -0.6255838 0.01902282 -0.7799252 -0.5753738 -0.01859909 -0.8176792 -0.545256 0.01953375 -0.8380421 -0.4945508 -0.0183627 -0.8689548 -0.4142345 -0.02061223 -0.9099367 -0.4586687 0.01986914 -0.8883853 -0.3257587 -0.01899737 -0.9452621 -0.3626959 0.02095389 -0.931672 -0.1868629 -0.004442751 -0.982376 -0.2393489 -0.01109766 -0.9708703 -0.268185 0.01909339 -0.9631783 -0.1424748 -0.00402075 -0.9897903 -0.1785443 0.001014232 -0.9839314 -0.1827174 0.00518316 -0.9831519 -0.100376 -0.003700137 -0.9949428 -0.1162627 0.002146184 -0.9932162 -0.05947762 -0.00368005 -0.998223 -0.03441321 0.005143582 -0.9993945 -0.009111642 -0.00199896 -0.9999565 0.009762644 -0.9999383 -0.005307495 0.003534018 -0.9999881 -0.003378868 0 -1 0 -1.27014e-4 -1 -3.07775e-4 4.74588e-5 -1 3.18345e-5 2.71987e-5 -1 -2.7039e-5 0 -1 4.27073e-6 0 -1 1.43933e-5 0 -1 -2.12573e-6 3.12433e-5 -1 -1.58112e-5 5.61539e-5 -1 -1.69585e-4 9.34007e-5 -1 -1.29954e-4 3.5523e-5 -1 0 4.20646e-5 -1 0 0.001446962 -0.9999976 0.001639962 0 -1 -2.3271e-6 -6.39348e-6 -1 -1.18744e-4 0.001542747 -0.9999988 4.31471e-4 0.001499652 -0.9999981 -0.001243889 -4.47259e-5 -1 -1.24275e-4 0 -1 2.71238e-6 -0.001764476 -0.9999984 -3.70203e-4 3.42916e-4 -1 2.20281e-4 -5.69546e-4 -0.9999995 -8.79413e-4 0 -1 -1.74584e-5 4.65973e-5 -0.9999998 6.99884e-4 0 -1 1.84036e-5 0 -1 -3.84183e-6 3.81176e-4 -0.9999998 4.65333e-4 8.8775e-4 -0.9999992 -9.67257e-4 2.58015e-4 -0.9999998 5.6998e-4 0 -1 3.19126e-5 0 -1 3.0896e-6 6.10174e-4 -0.9999991 -0.001253902 1.33189e-4 -0.9999998 6.87912e-4 0 -1 -4.90006e-6 0.001320421 -0.999999 -5.57692e-4 0 -1 3.93439e-6 -4.61866e-5 -1 4.01505e-4 0 -1 -4.97013e-7 5.62109e-4 -0.9999999 -7.67104e-5 0 -1 1.08484e-5 -3.18896e-5 -1 7.6151e-5 0 -1 -3.13974e-6 0 -1 -2.49971e-5 0 -1 8.09124e-6 0 -1 1.48173e-5 0 -1 -7.48493e-6 0 -1 8.30356e-7 0 -1 4.18207e-7 0 -1 3.33871e-6 0 -1 -5.92292e-6 0 -1 -6.40778e-7 0 -1 -6.41034e-7 0 -1 1.70942e-7 0 -1 -1.06438e-5 0 -1 8.33533e-7 -0.001413226 -0.9999989 4.82208e-4 0 -1 2.61555e-5 0 -1 -3.17618e-6 0 -1 -4.35383e-7 0 -1 -8.93893e-6 0 -1 1.60756e-6 0 -1 -6.41511e-6 0 -1 -1.81421e-5 0 -1 1.16196e-5 2.31037e-5 -1 3.30669e-4 4.41725e-4 -0.9999999 -1.99458e-4 8.30635e-5 -1 1.0044e-4 0 -1 -8.07771e-6 0 -1 8.37374e-6 1.81265e-4 -1 1.10587e-5 0 -1 2.65407e-6 1.99619e-4 -1 -1.54457e-4 0 -1 -4.55572e-7 6.45571e-5 -0.9999989 0.001533508 8.58775e-4 -0.9999992 -0.001070916 0 -1 4.94423e-7 0 -1 -9.36463e-7 3.97251e-4 -1 -1.67383e-4 0 -1 -3.65658e-7 0 -1 -6.76402e-7 0 -1 4.99257e-6 3.40397e-4 -1 -2.47847e-5 0 -1 -9.55662e-6 1.21817e-4 -1 5.45947e-4 0 -1 -2.28115e-6 0 -1 -2.4272e-6 4.73048e-4 -0.9999999 1.53797e-4 0 -1 -6.76357e-6 3.54352e-4 -1 2.98824e-4 4.20482e-4 -0.9999999 2.95342e-4 -0.00203824 -0.999997 -0.001377463 0 -1 -2.65796e-6 0 -1 3.03415e-6 0 -1 2.61206e-6 0 -1 -3.33202e-6 0 -1 4.3983e-6 0 -1 -6.7385e-6 0 -1 5.71903e-6 -2.4393e-4 -1 -1.70813e-4 -4.43321e-4 -1 2.81916e-4 0 -1 -3.20162e-5 0 -1 2.80821e-7 0 -1 3.20042e-6 0 -1 -2.4433e-6 2.69196e-4 -1 3.32256e-4 1.72896e-4 -1 3.70245e-4 0 -1 2.47666e-5 0 -1 -1.02887e-6 0 -1 -1.93542e-6 6.48024e-5 -1 1.90168e-5 3.03827e-4 -0.9999994 -0.00109446 0 -1 1.72525e-6 0 -1 9.93179e-7 0 -1 -1.037e-5 0 -1 2.31616e-6 0 -1 -1.80723e-6 -5.85362e-4 -0.9999981 0.001883506 0 -1 4.56385e-6 0 -1 -4.71625e-6 0 -1 2.4155e-6 1.98078e-4 -0.999999 0.00146979 -0.001110374 -0.9999989 9.97828e-4 -2.59689e-4 -1 -7.93107e-6 -4.58521e-4 -1 -2.97967e-4 0 -1 -1.89909e-6 -2.03281e-4 -0.9999991 0.001378357 0 -1 4.86121e-6 0 -1 -1.78855e-6 0 -1 -1.36249e-6 -2.17352e-4 -1 9.14519e-5 1.03744e-5 -1 -2.04568e-5 0.005324959 -0.9999839 0.001966178 0 -1 4.11662e-6 -2.95222e-4 -1 -1.52397e-4 0 -1 1.35679e-6 0 -1 -1.505e-6 -1.84013e-4 -1 -2.83047e-4 1.30121e-4 -1 -1.57317e-4 7.83237e-4 -0.9999997 1.69643e-4 -0.001282513 -0.9999989 8.68866e-4 -0.001934111 -0.9999976 0.00110495 0 -1 -4.17633e-6 0 -1 -2.08741e-6 0 -1 4.17786e-6 0 -1 2.08679e-6 0 -1 -4.17868e-6 0 -1 -2.08594e-6 0 -1 -2.08523e-6 0 -1 1.04525e-6 0 -1 -1.08063e-6 0 -1 -8.36425e-6 0 -1 1.08125e-6 0 -1 -2.08366e-6 0 -1 1.08175e-6 -1.34845e-6 -1 0 -1.38771e-6 -1 0 1.4422e-6 -1 0 1.35944e-6 -1 1.07005e-5 4.72446e-6 -1 5.26927e-6 6.26215e-6 -1 -5.77818e-6 -1.46986e-6 -1 -1.16127e-5 -1.47456e-6 -1 1.16066e-5 8.19614e-6 -1 -5.68469e-6 4.23118e-6 -1 0 6.5674e-6 -1 2.30952e-5 6.45131e-6 -1 -5.80508e-6 6.74091e-7 -1 4.12662e-6 -7.06738e-6 -1 1.11122e-5 -7.48626e-6 -1 8.70437e-6 0 -1 -2.0931e-6 0 -1 4.33092e-6 3.65962e-7 -1 0 0 -1 -7.93659e-6 0 -1 4.18742e-6 0 -1 4.38651e-6 0 -1 -2.09435e-6 0 -1 4.3715e-6 0 -1 -8.27833e-6 0 -1 -4.18965e-6 0 -1 4.37261e-6 2.53674e-7 -1 0 2.13463e-6 -1 -2.09523e-6 4.88061e-7 -1 -4.37417e-6 -4.62241e-7 -1 0 2.60991e-6 -1 0 2.60975e-6 -1 -8.382e-6 -7.0518e-7 -1 -4.37411e-6 6.6808e-7 -1 0 3.13643e-6 -1 0 0 -1 -8.64009e-6 3.10623e-6 -1 4.37551e-6 2.08793e-6 -1 0 0 -1 -4.3747e-6 0 -1 5.18162e-7 0 -1 8.28803e-6 0 -1 4.37579e-6 5.21163e-6 -1 -8.88364e-6 5.0867e-6 -1 0 8.47073e-6 -1 4.38734e-6 1.71705e-5 -1 -4.17574e-6 -6.56832e-6 -1 -2.30972e-5 -4.23169e-6 -1 0 1.52039e-5 -1 -8.57615e-6 1.46984e-6 -1 0 1.47451e-6 -1 0 3.63223e-6 -1 1.98555e-6 -1.35944e-6 -1 1.07006e-5 -1.44224e-6 -1 0 -1.71107e-6 -1 4.02894e-6 1.36639e-6 -1 0 1.43507e-6 -1 0 -6.46169e-6 -1 -2.85572e-6 -5.51204e-6 -1 -1.06144e-6 -7.20022e-6 -1 -8.31914e-6 -1.47092e-6 -1 0 -1.47347e-6 -1 0 6.56812e-6 -1 -1.15485e-5 4.23154e-6 -1 0 -2.36845e-7 -1 0 -7.50972e-6 -1 3.12371e-6 -5.2117e-6 -1 0 -5.08675e-6 -1 -8.36571e-6 0 -1 -2.62477e-7 0 -1 -5.13106e-6 0 -1 -8.66221e-6 0 -1 4.18702e-6 0 -1 8.2879e-6 0 -1 -2.0986e-6 0 -1 -8.63236e-6 0 -1 -4.32084e-6 -2.33261e-6 -1 -8.63725e-6 -8.73801e-7 -1 8.38183e-6 3.60756e-6 -1 -2.16087e-6 1.86203e-6 -1 8.64405e-6 -1.80548e-6 -1 0 2.59338e-5 1 5.82422e-6 -9.05566e-7 1 0 8.7319e-6 1 1.0148e-5 -8.18651e-7 1 1.17572e-5 0 1 4.43245e-6 0 1 -8.99135e-6 0 1 4.42028e-6 0 1 4.43669e-6 0 1 4.4355e-6 2.06858e-6 1 0 2.13153e-6 1 -2.21811e-6 0.005289852 0.002642333 0.9999826 0.08104932 -0.003032863 0.9967055 -0.2896391 0.1697071 0.9419707 -9.60129e-5 3.83165e-5 1 8.39463e-4 -3.40603e-4 0.9999997 -0.02875018 -0.0483188 0.9984181 -2.21604e-4 0 1 1 -4.10307e-7 0 1 -1.45684e-6 2.3191e-6 1 -1.6243e-4 4.05854e-4 1 2.424e-4 -3.39365e-4 1 -9.45045e-6 8.23291e-6 1 0 4.51635e-7 0.9999994 7.42597e-4 -8.94764e-4 0.9999247 0.005556523 0.01094681 0.0772289 -0.002664625 0.9970098 0.08353567 -0.006094038 0.9964863 0.1703199 0.004605829 0.9853782 0.1929851 -0.004654765 0.9811907 0.2661918 0.004651546 0.9639089 0.2885893 -0.004687309 0.9574415 0.3594841 0.004678726 0.9331395 0.3813668 -0.00472474 0.9244118 0.4493122 0.004718244 0.8933625 0.4704551 -0.0047549 0.8824111 0.5416707 0.005789518 0.8405708 0.5549768 -0.002594828 0.8318619 0.6530512 0.01022022 0.7572449 0.6341261 -0.002756953 0.7732248 0.7070899 -0.009154081 0.7070646 0.7518573 0.008069336 0.6592767 0.7732288 -0.004886925 0.6341084 0.8176833 0.004885613 0.5756478 0.8318618 -0.004922389 0.554961 0.8702145 0.004920661 0.4926486 0.8824188 -0.004953682 0.4704386 0.9143546 0.004949033 0.4048843 0.9244123 -0.004987776 0.3813623 0.9496712 0.004978179 0.313209 0.9574409 -0.005016148 0.2885857 0.9758176 0.005011856 0.2185296 0.9811868 -0.005052983 0.1929951 0.9930533 0.005629956 0.1175306 0.996457 -0.009829103 0.08352828 -2.22289e-5 1 5.82411e-6 -7.48372e-6 1 7.61166e-6 0 1 -1.05993e-6 0 1 4.43346e-6 0 1 -2.64994e-6 0 1 -1.32502e-7 0 1 -1.59021e-6 -2.06835e-6 1 -5.30267e-6 -2.13127e-6 1 0 0 1 4.24374e-6 0 1 4.43651e-6 0 1 2.12273e-6 0 1 4.42039e-6 0 1 -4.49549e-6 0 1 4.6215e-6 8.1862e-7 1 1.17569e-5 9.05562e-7 1 0 -1 1.73728e-4 0 -1 1.63815e-4 -2.95787e-4 -1 1.79367e-4 -3.22578e-4 -0.999998 -7.40898e-4 0.001897037 -1 0 -3.66909e-4 -0.9999283 0.005631625 0.01056963 -0.9999994 6.63554e-4 -9.38899e-4 -0.005332469 0.002573966 0.9999825 -2.94347e-5 -1.11402e-5 1 1.62354e-5 9.1278e-6 1 5.65406e-5 3.08201e-5 1 -1.71623e-5 -2.10967e-5 1 2.98558e-6 0 1 -8.45646e-4 -6.89004e-4 0.9999994 -0.007117271 0.001946866 0.9999729 -0.9930539 0.005634665 0.1175252 -0.9964578 -0.009826719 0.08351784 -0.9758204 0.005014061 0.2185167 -0.9811885 -0.005048215 0.1929862 -0.9496669 0.004978537 0.3132221 -0.9574413 -0.005022943 0.2885847 -0.9244053 -0.004988312 0.3813791 -0.9143468 0.004947125 0.4049021 -0.8824161 -0.004957318 0.4704439 -0.8661487 0.008094966 0.4997211 -0.8318285 -0.009150385 0.5549573 -0.7884155 0.01016652 0.6150592 -0.7732415 -0.002645373 0.6341062 -0.7013253 -0.002741396 0.7128362 -0.7012902 -0.002707421 0.7128707 -0.6405807 0.008088409 0.7678483 -0.6018469 -0.01132988 0.7985311 -0.5416616 0.008083641 0.8405579 -0.5133464 -0.004937827 0.8581674 -0.44931 0.004934072 0.8933624 -0.4264262 -0.004971683 0.9045088 -0.359481 0.004961431 0.9331393 -0.3353749 -0.005005419 0.9420715 -0.2661859 0.004999101 0.9639088 -0.2410826 -0.005029857 0.9704915 -0.1703161 0.005021095 0.9853767 -0.1444348 -0.00507164 0.9895014 -0.07722854 0.004438161 0.9970036 -0.05461543 -0.002474904 0.9985044 -9.05612e-7 1 -1.10532e-5 -8.18537e-7 1 -2.93922e-6 0 1 4.62238e-6 0 1 4.41984e-6 0 1 4.43666e-6 0 1 4.43676e-6 0 1 4.24395e-6 2.13121e-6 1 -4.43594e-6 2.06822e-6 1 0 0 1 2.21779e-6 0 1 3.88099e-6 0 1 -2.6326e-6 0 1 4.24015e-6 0 1 -2.21671e-6 0 1 4.23984e-6 0 1 1.10818e-6 8.73106e-6 1 -1.35315e-5 2.59339e-5 1 -4.36813e-6 1 5.94725e-5 0 0.9999651 0.00406295 -0.007294297 1 -1.66878e-4 -1.80183e-4 0.9999998 3.88549e-4 5.49982e-4 1 -4.1241e-5 -1.14404e-4 1 -4.42889e-5 -1.19909e-4 0.9999997 -2.85439e-4 -7.93252e-4 0.9999994 7.33046e-4 9.00078e-4 1 0 1.21945e-4 0.005288839 0.002500414 -0.999983 0.00719881 0.00407058 -0.9999658 2.67797e-5 -9.17342e-6 -1 -6.13649e-4 2.6779e-4 -0.9999998 5.29869e-4 -3.787e-4 -0.9999998 8.66057e-5 -7.59174e-5 -1 -8.9854e-4 7.35308e-4 -0.9999994 -3.95565e-6 0 -1 0.9970111 -0.002656996 -0.07721263 0.9964864 -0.006093561 -0.0835337 0.9853747 0.0046072 -0.1703396 0.9811885 -0.00465238 -0.1929958 0.9639081 0.004649162 -0.2661944 0.9574432 -0.004685938 -0.2885838 0.9331353 0.004679083 -0.3594951 0.9244126 -0.00472027 -0.3813648 0.8933612 0.004714787 -0.4493147 0.8824188 -0.004750847 -0.4704409 0.8449637 0.004749536 -0.5348027 0.8318618 -0.00478816 -0.5549622 0.7884116 0.004787206 -0.6151296 0.7732204 -0.004823982 -0.6341191 0.7185679 0.005883216 -0.6954319 0.7071051 -0.00270617 -0.7071034 0.6215513 0.00584191 -0.7833518 0.6341301 -0.002653717 -0.7732218 0.5347993 0.004752635 -0.8449658 0.5549761 -0.004790067 -0.8318526 0.449308 0.004713773 -0.8933645 0.4704523 -0.004758954 -0.8824127 0.3595039 0.004676938 -0.9331319 0.3813648 -0.004720509 -0.9244127 0.266217 0.004645287 -0.9639019 0.2885897 -0.004683434 -0.9574415 0.1703526 0.004612624 -0.9853724 0.1930096 -0.004650175 -0.9811859 0.07723015 -0.002665102 -0.9970098 0.08352762 -0.006089389 -0.9964869 -1.00621e-4 1 4.99658e-5 2.40658e-5 1 -7.12929e-5 -7.28415e-6 1 -2.22887e-5 -5.22326e-5 1 -5.13699e-6 -6.06397e-6 1 -4.98236e-5 -2.65616e-5 1 -9.10399e-6 -2.1214e-5 1 -4.5067e-6 -4.91298e-6 1 -2.2261e-5 -7.55734e-6 1 -1.62992e-5 -1.70928e-5 1 -8.13689e-6 -1.38056e-5 1 -6.02546e-6 -4.75035e-6 1 -1.49579e-5 -6.05685e-6 1 -9.93187e-6 -1.27761e-5 1 -8.68317e-6 -1.21124e-5 1 -8.12001e-6 -5.91804e-6 1 -8.6291e-6 -9.78346e-6 1 -4.65559e-6 -5.47109e-6 1 -6.95835e-6 -6.23042e-6 1 -9.60106e-6 -8.42024e-6 1 -6.39649e-6 -9.57305e-6 1 -6.69005e-6 -5.67714e-6 1 -1.02856e-5 -1.13081e-5 1 7.37951e-7 -3.16269e-6 1 -1.4513e-5 -6.36721e-6 1 -3.88915e-6 -6.47246e-6 1 -9.02733e-6 0.007607519 0.8676795 -0.4970659 0.01112782 0.8663711 -0.4992769 0.08043307 0.8671407 -0.4915257 0.05136048 0.865689 -0.4979405 0.05353307 0.8663647 -0.4965345 0.08953976 0.8646843 -0.4942711 0.07650047 0.8675203 0.4914839 0.08200639 0.8656747 0.4938446 0.009835124 0.8686521 0.4953251 0.04089063 0.8621732 0.5049608 0.005831301 0.8671925 0.4979389 -0.04644197 0.8670617 0.4960315 -0.07649886 0.8675206 0.4914835 -0.03767943 0.8642203 0.5017006 -0.08918517 0.8632194 0.4968885 0.4914538 0.867468 -0.07728141 0.4963254 0.8668916 -0.04647749 0.4962598 0.8635932 -0.08906757 0.5017964 0.8641363 -0.03832501 0.4953203 0.8686549 0.009830713 0.4978808 0.8672254 0.005903482 0.4917054 0.8673223 0.07731658 0.5052047 0.8619942 0.04164332 0.4934573 0.8659337 0.08160197 -0.7732495 0.5518546 0.3123167 -0.7786694 0.54524 0.3104628 -0.722255 0.6911193 0.02649611 -0.6748005 0.7357845 0.05714488 -0.7191503 0.6888619 0.09106171 -0.6769778 0.7238584 0.1331545 -0.706558 0.6891673 0.160699 -0.6608557 0.7235977 0.1991893 -0.6872211 0.6894932 0.2287496 -0.6383311 0.7233151 0.2633417 -0.6613453 0.6898214 0.2945656 -0.6095922 0.7230331 0.3249934 -0.6291958 0.6901394 0.3575196 -0.5749262 0.7227303 0.3835635 -0.5910426 0.6904917 0.4170011 -0.5346657 0.7224121 0.4384673 -0.5473003 0.6908439 0.4724375 -0.4828316 0.725242 0.4908133 -0.4934826 0.6985346 0.5181934 -0.4139927 0.7258815 0.5492778 -0.4411777 0.6975338 0.5646318 -0.3547159 0.7228671 0.5929924 -0.3877143 0.6903284 0.6108391 -0.2945125 0.7231735 0.624726 -0.3264434 0.6899828 0.6460329 -0.2619788 0.689645 0.6750977 -0.2315372 0.7234674 0.6503733 -0.1949741 0.6893124 0.6977345 -0.1663691 0.7237136 0.6697463 -0.1260312 0.689032 0.7136884 -0.09963011 0.7239915 0.6825762 -0.04816561 0.6822068 0.7295712 -0.03885358 0.7012194 0.7118861 -0.3133992 0.5515238 0.7730476 -0.3139756 0.5535978 0.7713292 0.3123193 0.5518549 -0.7732484 0.3104677 0.5452432 -0.7786655 0.7732455 0.551857 -0.3123227 0.7750086 0.5497204 -0.3117198 0.6886453 0.7227505 -0.05830556 0.7229838 0.6892157 -0.04771077 0.6810348 0.7198943 -0.1339545 0.7093094 0.693679 -0.1252586 0.6641649 0.7202842 -0.2001894 0.6941318 0.6932235 -0.1939642 0.6722693 0.6928115 -0.2608951 0.6408857 0.7206693 -0.2643889 0.6439815 0.6923873 -0.3254039 0.611427 0.7210388 -0.3259758 0.6094976 0.6919854 -0.3868707 0.5760812 0.721403 -0.3843283 0.5691463 0.6915906 -0.4447189 0.5351857 0.7217562 -0.4389128 0.5233103 0.691228 -0.4983476 0.4891631 0.7221071 -0.4891636 0.4724361 0.690856 -0.5472862 0.4384804 0.7224136 -0.5346528 0.4170117 0.6904821 -0.5910463 0.3835574 0.7227461 -0.5749103 0.324993 0.723034 -0.6095911 0.3575233 0.6901447 -0.629188 0.2945738 0.6897981 -0.6613659 0.2633455 0.7233232 -0.6383202 0.2287608 0.6894872 -0.6872234 0.199194 0.7235831 -0.6608701 0.1606999 0.6891895 -0.7065363 0.1331675 0.7238624 -0.676971 0.09106171 0.6888709 -0.7191416 0.05715 0.7357821 -0.6748027 0.02650052 0.6911197 -0.7222543 0.3123212 0.5518572 0.773246 0.3116997 0.5496408 0.7750732 0.05830883 0.7227462 0.6886494 0.04772078 0.6892462 0.722954 0.1339486 0.7198834 0.6810476 0.1252585 0.6936768 0.7093116 0.2001847 0.7202733 0.6641781 0.1939733 0.6932284 0.6941246 0.2608884 0.6928005 0.6722833 0.2643926 0.7206876 0.6408635 0.325393 0.6923909 0.6439833 0.3259716 0.7210628 0.6114009 0.3843138 0.7214243 0.5760642 0.3868579 0.6919918 0.6094984 0.4389105 0.7217628 0.5351784 0.444724 0.691573 0.5691638 0.4891737 0.7221062 0.4891542 0.4983572 0.6912181 0.5233142 0.5346599 0.7224159 0.4384679 0.5472908 0.6908438 0.4724487 0.5749303 0.7227328 0.3835527 0.5910581 0.6904734 0.4170095 0.6095917 0.7230336 0.3249931 0.6291972 0.6901285 0.3575383 0.6613668 0.689794 0.2945815 0.638337 0.7233124 0.2633349 0.6872244 0.6894843 0.2287664 0.6608588 0.7235952 0.1991879 0.7065532 0.6891683 0.1607167 0.6769593 0.723875 0.1331582 0.7191359 0.688875 0.09107571 0.6747897 0.7357938 0.05715233 0.7222703 0.6911031 0.02649748 0.7732461 0.5518562 0.3123222 0.778666 0.5452433 0.310466 -0.0672416 0.003796696 -0.9977295 -0.2495744 -0.004729628 -0.9683442 -0.3113517 0.002750813 -0.9502909 -0.559252 3.26841e-4 -0.8289977 -0.5657546 -0.00104779 -0.8245731 -0.8024867 -0.002333343 -0.5966656 -0.8244876 0.004134595 -0.565865 -0.9661816 -0.002387285 -0.2578517 -0.9655965 -0.002774 -0.2600302 -0.9999325 0.003854513 -0.01096373 -0.9963213 -0.004598975 0.08557355 -0.9737048 0.004390358 0.2277716 -0.9356857 -0.005924344 0.3527849 -0.8579321 0.006086409 0.513727 -0.7710961 -0.006370663 0.636687 -0.6762198 0.006338834 0.7366726 -0.5280022 -0.006062567 0.8492214 -0.3932886 0.004785001 0.9194027 -0.3097773 -0.002991974 0.9508045 -0.1153351 0.004442989 0.9933167 -0.03848361 -0.004221618 0.9992504 -0.05281013 0.005772352 -0.998588 -0.2495751 -0.00589174 -0.9683375 -0.3428226 0.004255533 -0.9393906 -0.5454787 -6.27545e-4 -0.8381245 -0.558932 -0.00284177 -0.8292086 -0.7478521 0.002486109 -0.6638608 -0.7559263 8.64315e-4 -0.6546562 -0.8826175 -0.003618001 -0.470078 -0.9266793 0.007271885 -0.3757827 -0.9768609 -0.006121397 -0.2137881 -0.9999215 0.005874454 -0.01106607 -0.9994159 5.90073e-5 0.03417432 -0.9688146 -0.00341624 0.2477632 -0.9358302 0.007138907 0.3523789 -0.8855723 -0.004071474 0.4644837 -0.7546664 9.30366e-4 0.656108 -0.7516978 0.001645445 0.6595057 -0.5473836 5.74728e-4 0.8368816 -0.5280082 -0.002096712 0.8492368 -0.3622743 0.001868963 0.9320697 -0.3097638 -0.002991557 0.9508088 -0.1153226 0.004443109 0.9933182 -0.03847813 -0.0042212 0.9992506 -0.06723552 0.00379616 -0.99773 -0.2495701 -0.004728317 -0.9683452 -0.3113273 0.002749919 -0.9502988 -0.559228 3.264e-4 -0.8290138 -0.5725637 -0.002500772 -0.8198564 -0.8122308 3.80768e-4 -0.5833361 -0.8148027 0.001080632 -0.5797373 -0.9469299 0.002560675 -0.3214303 -0.9370968 -8.77362e-4 -0.3490687 -0.9958798 -0.004237413 -0.09058547 -0.9999759 0.006410419 -0.002671003 -0.9747968 -0.005862116 0.2230172 -0.9358256 0.007139563 0.3523914 -0.8855825 -0.004070401 0.4644645 -0.7546599 9.27e-4 0.6561156 -0.7516764 0.001646339 0.6595301 -0.5473334 5.72604e-4 0.8369146 -0.5280192 -0.002090692 0.8492299 -0.3622416 0.001866579 0.9320825 -0.3097675 -0.002991497 0.9508076 -0.1153246 0.004443168 0.993318 -0.03847688 -0.0042212 0.9992507 -0.04455041 0.004875123 -0.9989953 -0.1951698 -0.004023075 -0.9807612 -0.3113239 0.004399478 -0.9502938 -0.4533545 -0.004033565 -0.8913213 -0.5592419 0.005627036 -0.8289856 -0.6702179 -0.006721079 -0.742134 -0.8148022 0.006043016 -0.5797076 -0.870352 -0.005093276 -0.4924036 -0.9469212 0.005185604 -0.3214241 -0.9768664 -0.005024194 -0.2137917 -0.999985 0.004796326 -0.002670884 -0.9981062 -0.003447771 0.06141895 -0.9436003 0.003447413 0.3310692 -0.929957 -0.001574158 0.3676651 -0.8149136 5.32306e-4 0.5795823 -0.8171407 -1.40787e-5 0.5764383 -0.6306537 0.001262187 0.7760633 -0.6098467 -0.001914918 0.7925172 -0.4293032 0.001870334 0.9031586 -0.4103086 -5.53214e-4 0.9119467 -0.1459794 0.003221452 0.9892824 -0.1868289 -0.001430809 0.9823915 -0.1689143 0.002847313 -0.9856267 -0.1373499 -0.002158105 -0.9905202 -0.3739579 0.005603075 -0.9274288 -0.3251646 -0.002927005 -0.945653 -0.4985273 -0.006194472 -0.8668519 -0.5996182 0.00457257 -0.8002732 -0.6399059 -0.002788126 -0.7684483 -0.7476151 0.004701316 -0.6641157 -0.789065 -0.005494654 -0.6142851 -0.8777095 0.004256129 -0.4791743 -0.897872 -0.002925097 -0.4402468 -0.9576336 0.002925276 -0.2879745 -0.9673054 -0.002925276 -0.2535979 -0.9948616 0.002613961 -0.1012109 -0.9980112 -0.002682387 -0.06298053 -0.9974698 0.003157258 0.07102298 -0.9936357 -0.003094613 0.112599 -0.9610748 0.002253115 0.2762793 -0.954146 -0.001779615 0.2993364 -0.8951894 0.00215584 0.4456809 -0.8805137 -0.002845704 0.4740123 -0.7875684 0.003231942 0.6162188 -0.7653422 -0.003442883 0.6436145 -0.6243116 0.003443479 0.7811679 -0.587852 -0.005227506 0.8089517 -0.4519172 0.005587041 0.8920425 -0.3605918 -0.006891787 0.9326984 -0.265347 0.006382942 0.9641319 -0.1340149 -0.006007075 0.9909611 -0.03062599 0.005002737 0.9995185 0.2528802 -0.9665532 -0.0427379 0.2024807 -0.9784836 -0.03964132 0.3802415 -0.9224348 -0.06731128 0.5096077 -0.85396 -0.1051297 0.621981 -0.7751007 -0.1111689 0.7395755 -0.6567098 -0.1475138 0.8185432 -0.5562849 -0.1432977 0.9309516 -0.3119494 -0.1897808 0.9705736 -0.17058 -0.1699686 0.513925 -0.8554529 -0.06388813 0.6237052 -0.7759993 -0.09389919 0.744134 -0.6606619 -0.09894686 0.8226273 -0.5550897 -0.1231253 0.9731128 -0.2072021 -0.1005927 0.842537 -0.4021232 0.3583692 0.8749613 -0.4461839 -0.1880502 0.981436 -0.139612 -0.1314988 0.2132354 -0.9767883 -0.02037978 0.4713393 -0.8809679 -0.04165166 0.4992584 -0.8650478 -0.04933154 0.7481117 -0.6601228 -0.06757766 0.7583131 -0.6485681 -0.06573241 0.9519518 -0.2927923 -0.08978021 0.8309932 -0.3914051 0.3952876 0.8874318 -0.4382506 -0.142833 0.9866669 -0.1399331 -0.08310961 0.158331 -0.987345 -0.009018719 0.3056399 -0.9521343 -0.004968523 0.4732742 -0.8806949 -0.01969641 0.5163366 -0.8562285 -0.01640987 0.7554469 -0.6545215 -0.0300281 0.7610087 -0.6479549 -0.03194373 0.9585444 -0.2822674 -0.03896057 0.8031374 -0.3904196 0.4500476 0.8964223 -0.4324401 -0.09707033 0.9895355 -0.1401606 -0.03427267 0.579313 -0.8150867 0.005478978 0.7560299 -0.6544981 0.007147073 0.7565509 -0.6538975 0.007003068 0.9595823 -0.2812885 0.008872687 0.7742853 -0.3877038 0.5001682 0.900137 -0.4324471 -0.052374 0.9899955 -0.140338 0.01463526 0.3479143 -0.9373202 0.01966053 0.4966374 -0.8673335 0.03292393 0.512766 -0.8579497 0.03152173 0.7554336 -0.6540098 0.03988999 0.8075937 -0.5870313 0.05645108 0.9611909 -0.2738301 0.03360426 0.9826763 -0.1742381 0.06315422 0.2203118 -0.975179 0.02210694 0.5763902 -0.8145713 0.06517916 0.8051128 -0.5869797 0.08513784 0.8133446 -0.5748577 0.08949482 0.9754464 -0.1933073 0.1055316 0.9786537 -0.1725517 0.1116367 0.2823958 -0.958326 0.04317331 0.5150535 -0.8534936 0.07917428 0.5415994 -0.8368483 0.07971972 0.7303239 -0.671754 0.1239913 0.8100115 -0.5743963 0.1181116 0.9628304 -0.202357 0.1789118 0.796101 -0.3435578 0.498188 0.9237998 -0.366959 0.1092476 0.9811293 -0.1065652 0.1613358 0.2382245 -0.9698456 0.05146521 0.2449429 -0.9681469 0.05190974 0.5126956 -0.8520008 0.1060103 0.5516906 -0.8251186 0.121724 0.7259454 -0.6721873 0.1454909 0.7971909 -0.5766096 0.1789078 0.9479424 -0.2634228 0.1789239 0.9627828 -0.1731598 0.2075215 0.3548188 -0.929035 0.1048693 0.5488939 -0.8249163 0.1350141 0.6781499 -0.7098904 0.1901801 0.7933667 -0.576074 0.1967442 0.9386495 -0.2032371 0.2786253 0.69226 -0.35026 0.6309471 0.8998697 -0.391991 0.1912525 0.9593495 -0.1166453 0.2569874 0.2429499 -0.9665152 0.08260613 0.3575095 -0.9283015 0.1021935 0.5186148 -0.8368574 0.1752378 0.6754218 -0.709651 0.2005016 0.7863487 -0.559227 0.2625281 0.923271 -0.2759991 0.267199 0.9386931 -0.1665354 0.3018631 0.2504499 -0.9635952 0.09359073 0.3319869 -0.9342558 0.130196 0.5159019 -0.8367729 0.1834566 0.5766709 -0.7868189 0.2199245 0.7576021 -0.5879256 0.2835182 0.7796683 -0.5585825 0.2830251 0.9201222 -0.1849878 0.345188 0.9205377 -0.179334 0.3470588 0.08251535 -0.9958125 0.03935515 0.4083718 -0.8941072 0.183861 0.5700184 -0.7859616 0.2394648 0.633275 -0.7225506 0.2772787 0.7464889 -0.5870631 0.3132271 0.7918692 -0.5010185 0.3491755 0.9030361 -0.1934865 0.3835219 0.9054295 -0.1596509 0.3933309 0.122919 -0.9904459 0.06251364 0.3093284 -0.9381873 0.1553087 0.3987523 -0.8978577 0.1866768 0.5369062 -0.7991352 0.2703972 0.6245645 -0.7213485 0.2992918 0.7380176 -0.5648423 0.3691657 0.7795241 -0.501113 0.3758032 0.8828473 -0.1774836 0.4348335 0.883107 -0.1713759 0.436752 0.3548789 -0.9138984 0.1971067 0.4542769 -0.8522428 0.2594508 0.5297467 -0.7981733 0.286859 0.6707795 -0.6381333 0.377943 0.7260102 -0.5648469 0.3922463 0.8489354 -0.1929914 0.491999 0.8455441 -0.2701961 0.460488 0.2213999 -0.9657378 0.135398 0.4666016 -0.8385559 0.2812597 0.5940153 -0.7122071 0.3740416 0.65792 -0.638377 0.3995199 0.7303552 -0.5039582 0.4610938 0.8247627 -0.2759742 0.4935635 0.8349689 -0.1624614 0.5257694 0.2216672 -0.9633871 0.1508274 0.3479508 -0.9061288 0.2405431 0.3350275 -0.913937 0.2290759 0.5312119 -0.7610231 0.372368 0.580422 -0.7128113 0.3937136 0.7093158 -0.5031545 0.4936667 0.7049183 -0.5157607 0.4869098 0.8103151 -0.175973 0.5589481 0.8104227 -0.16061 0.5634002 0.1600455 -0.9804871 0.114152 0.4246457 -0.839854 0.3381146 0.5205506 -0.7599133 0.389306 0.6765009 -0.5174802 0.5239855 0.6719902 -0.5320103 0.5151643 0.7817898 -0.1747751 0.5985471 0.7817018 -0.1606947 0.602594 0.2135905 -0.9598445 0.1818724 0.4101473 -0.8468484 0.3385661 0.4252753 -0.8301898 0.3604525 0.622215 -0.572959 0.5334479 0.6487731 -0.5339451 0.542214 0.7492693 -0.1748461 0.6387678 0.749219 -0.1738508 0.6390985 0.1782918 -0.9706492 0.1614075 0.1089701 -0.988331 0.1064306 0.3418586 -0.8803849 0.3287177 0.412936 -0.8294017 0.3762667 0.5005763 -0.7219948 0.4776474 0.6038541 -0.5724723 0.5546493 0.626454 -0.5046314 0.594056 0.7192459 -0.1846264 0.6697751 0.718531 -0.1594055 0.6769809 0.1816142 -0.9638592 0.1949149 0.3322176 -0.880623 0.3378383 0.3741104 -0.8379389 0.3973664 0.4860923 -0.7224663 0.4916877 0.5699077 -0.5593038 0.6019839 0.602819 -0.5032753 0.619131 0.6834888 -0.1720405 0.7093977 0.6832624 -0.1677675 0.7106382 0.1953018 -0.9561296 0.2183427 0.3598567 -0.8363887 0.4134697 0.3531582 -0.8413565 0.4091436 0.5485326 -0.5596193 0.6212394 0.5538112 -0.5349935 0.6380245 0.6489658 -0.178227 0.7396476 0.6480697 -0.1626471 0.7440105 0.1513837 -0.9670214 0.2048238 0.3423234 -0.8404872 0.4199954 0.3678904 -0.799232 0.4752736 0.5273371 -0.5357006 0.6595003 0.5311067 -0.5144377 0.6732604 0.6116945 -0.1725783 0.7720407 0.6107783 -0.1589011 0.7756935 0.09492391 -0.9866718 0.1321684 0.1683013 -0.9607778 0.2204107 0.2647835 -0.8835785 0.3862369 0.3568912 -0.798403 0.4849551 0.4055523 -0.7044829 0.5824356 0.5053561 -0.5150669 0.6923304 0.5198525 -0.4298174 0.7382482 0.5747377 -0.1681224 0.8008817 0.5731892 -0.142215 0.8069877 0.1851114 -0.934356 0.3044878 0.2577213 -0.883835 0.3904042 0.3227059 -0.7948289 0.5139145 0.3895382 -0.7041153 0.5937016 0.4352324 -0.5695679 0.6972556 0.4939234 -0.4294223 0.7560663 0.5216526 -0.1557816 0.8388152 0.5294229 -0.221518 0.8189269 0.145394 -0.9520928 0.2690355 0.1795895 -0.9346456 0.3068964 0.3051919 -0.7937722 0.5261024 0.3189423 -0.7577643 0.5692709 0.4139155 -0.5706285 0.7092652 0.4231758 -0.5113888 0.747933 0.4876033 -0.2245861 0.843685 0.4861122 -0.2027099 0.8500609 0.1442694 -0.9536104 0.2642225 0.2570092 -0.8130488 0.5223963 0.3019436 -0.7578424 0.5783643 0.3695822 -0.5598116 0.7416334 0.3924429 -0.5126453 0.7636644 0.4477542 -0.2063069 0.8700309 0.4433805 -0.159811 0.8819718 0.1164706 -0.9573473 0.2644253 0.2313398 -0.8227307 0.5192265 0.2406607 -0.8124501 0.5310436 0.3413576 -0.5597213 0.7551074 0.3323567 -0.5770568 0.7460191 0.3966933 -0.1663894 0.9027453 0.4028841 -0.2061749 0.8917266 0.07877349 -0.975056 0.2075106 0.09120512 -0.968104 0.2333589 0.1763974 -0.8652039 0.4693678 0.2122063 -0.8231418 0.5266936 0.302945 -0.5782078 0.7575619 0.2756276 -0.6363285 0.7204968 0.3305972 -0.3525045 0.8754691 0.3656771 -0.2073118 0.90736 0.1770111 -0.8116012 0.5567502 0.2535646 -0.6350106 0.7297031 0.2605682 -0.5253779 0.8099892 0.3049473 -0.3523923 0.8847751 0.3023316 -0.1853405 0.9350104 0.08079493 -0.9532308 0.2912442 0.0934987 -0.9343309 0.3439243 0.160704 -0.8232118 0.5445149 0.1638938 -0.7826114 0.6005484 0.23341 -0.5273989 0.8169273 0.2309418 -0.493977 0.8382439 0.2664248 -0.186983 0.945545 0.2655936 -0.1803032 0.947075 0.02677512 -0.9913311 0.1286309 0.1069001 -0.8512305 0.5137889 0.144949 -0.7826181 0.6053914 0.169196 -0.5885291 0.7905734 0.2009094 -0.4941868 0.845822 0.2210108 -0.1810145 0.9583257 0.2073456 -0.2547451 0.9445173 0.04122906 -0.9610548 0.2732654 0.09903681 -0.8544546 0.5099991 0.09529781 -0.7867289 0.6098985 0.1526508 -0.5880188 0.794312 0.1427949 -0.4184882 0.8969265 0.1764302 -0.2557052 0.9505195 0.04160076 -0.9621588 0.2692951 0.05092871 -0.877095 0.4776092 0.08806008 -0.7865326 0.6112381 0.08033895 -0.6851704 0.7239387 0.1130042 -0.4175634 0.9015935 0.1206954 -0.3959184 0.9103194 0.008350491 -0.9702227 0.2420705 0.008737564 -0.9698384 0.2435922 4.8683e-4 -0.9440158 0.3298999 0.04341661 -0.8772315 0.4781004 0.0227279 -0.8103945 0.5854436 0.03558164 -0.8108711 0.5841422 0.009740829 -0.7477759 0.6638798 0.06125628 -0.6841998 0.7267175 0.02415508 -0.601853 0.7982416 0.05420297 -0.6018662 0.7967554 0.01575672 -0.5214434 0.8531404 0.07290446 -0.3967149 0.9150422 0.06798887 -0.3677715 0.9274275 0.03082865 -0.3684284 0.9291449 0.01619905 -0.2367764 0.9714292 -0.03146439 -0.9832199 -0.1796906 -0.03363585 -0.9816676 -0.1876099 -0.05880272 -0.94115 -0.3328348 -0.09939473 -0.87862 -0.4670627 -0.1011033 -0.8111187 -0.5760769 -0.1487252 -0.6363108 -0.7569606 -0.1472511 -0.6238322 -0.7675614 -0.1761761 -0.3396886 -0.9238905 -0.1736373 -0.3261451 -0.929236 -0.05782538 -0.8806375 -0.4702488 -0.09279167 -0.8108649 -0.5778303 -0.1077373 -0.6258733 -0.7724477 -0.1097736 -0.6359688 -0.7638675 -0.1384238 -0.3236834 -0.935985 -0.1359404 -0.3324919 -0.9332575 -0.02373266 -0.9556028 -0.2937008 -0.05872708 -0.8801954 -0.4709641 -0.04883158 -0.7825538 -0.620665 -0.09008693 -0.6343641 -0.7677673 -0.07935374 -0.5272043 -0.8460252 -0.1012016 -0.3388214 -0.9353921 -0.09325838 -0.2824372 -0.954742 -0.00682789 -0.9887197 -0.1496219 -0.02113515 -0.9574381 -0.2878643 -0.0159161 -0.9297813 -0.3677682 -0.03749972 -0.7805807 -0.6239292 -0.03423064 -0.787337 -0.6155719 -0.04915034 -0.5321316 -0.8452339 -0.04225438 -0.497211 -0.8666002 -0.05919301 -0.2920508 -0.9545693 -0.04758584 -0.1944326 -0.9797611 0.00213319 -0.986493 -0.1637897 -0.001200437 -0.9179353 -0.3967284 -0.002301573 -0.8263319 -0.5631787 -0.01430374 -0.7859397 -0.6181378 -0.002626478 -0.679386 -0.7337765 -0.00652188 -0.5091151 -0.8606739 -0.01161295 -0.4932114 -0.869832 0.005304336 -0.9349339 -0.3547825 -0.01415234 -0.1992144 -0.9798538 -0.006721138 -0.1573017 -0.9875277 0.01012003 -0.4908271 -0.8711982 0.03465729 -0.7561886 -0.6534354 0.007075965 -0.9948373 -0.1012367 0.02751463 -0.9148295 -0.4029021 0.02851992 -0.209638 -0.9773631 0.03571462 -0.8438017 -0.5354654 0.02499902 -0.7613972 -0.6478035 0.0443561 -0.6628974 -0.7473952 0.03837358 -0.5313467 -0.8462849 0.06678587 -0.3734957 -0.9252247 0.04385071 -0.1857883 -0.9816109 0.02050584 -0.9810384 -0.192726 0.0320962 -0.93636 -0.3495713 0.06799256 -0.775705 -0.6274224 0.06813687 -0.6643444 -0.7443144 0.09130656 -0.5660071 -0.8193284 0.08168476 -0.3759865 -0.9230179 0.1058533 -0.2581081 -0.9602996 0.06480818 -0.8874858 -0.4562556 0.07939916 -0.7996268 -0.5952252 0.1094439 -0.727827 -0.6769711 0.1068862 -0.5633602 -0.8192685 0.1466723 -0.3798866 -0.913331 0.1318793 -0.2578344 -0.9571465 0.04493784 -0.9658073 -0.2553372 0.07408982 -0.9214963 -0.381255 0.074207 -0.9204543 -0.383741 0.1228619 -0.7267558 -0.6758188 0.1436865 -0.686273 -0.7130102 0.1656281 -0.3809403 -0.9096439 0.1746003 -0.3552178 -0.9183328 -0.1620286 -0.9864245 0.0267114 -0.2261496 -0.9731504 0.04283356 -0.3185508 -0.9462218 0.05647832 -0.4724721 -0.8770292 0.08712065 -0.586823 -0.8007825 0.1199435 -0.5817806 -0.8066899 0.1038412 -0.6862705 -0.7143014 0.1371364 -0.650637 -0.7470551 0.1363098 -0.9099797 -0.3698229 0.1875315 -0.9034703 -0.3879752 0.1822548 -0.9692005 -0.1736372 0.1746445 -0.4236959 -0.9039272 0.05828696 -0.6672689 -0.7391044 0.09207063 -0.6840244 -0.7231514 0.09572237 -0.8435177 -0.5272517 0.1023892 -0.9108077 -0.3912692 0.131673 -0.9703247 -0.2048266 0.1285148 -0.9746674 -0.179281 0.1337233 -0.2571071 -0.9661287 0.02216887 -0.3789426 -0.9248311 0.03301501 -0.4343019 -0.8995738 0.04635846 -0.628024 -0.7755501 0.06409341 -0.6623392 -0.7468711 0.0590797 -0.8457499 -0.526904 0.08413881 -0.8710501 -0.4849079 0.07833385 -0.9721987 -0.2120943 0.09922575 -0.9835003 -0.1576388 0.08875417 -0.4683356 -0.8834319 0.01448476 -0.6639192 -0.7466949 0.04072093 -0.7435013 -0.6681357 0.02829408 -0.8734868 -0.4846114 0.04661267 -0.9084602 -0.4163696 0.03655982 -0.9848117 -0.1638285 0.05749887 -0.1511659 -0.9885002 0.004044115 -0.2378199 -0.9712984 -0.004611432 -0.4643334 -0.8855885 0.01129448 -0.5903925 -0.8070387 -0.01119405 -0.7434948 -0.6686924 0.008130252 -0.8206183 -0.5714555 -0.004924058 -0.9094011 -0.4158604 0.007059454 -0.9402858 -0.3403404 -0.005578279 -0.1408431 -0.989955 -0.01235175 -0.2377626 -0.971322 -0.001655459 -0.494673 -0.868444 -0.03322124 -0.5898945 -0.8072892 -0.01756989 -0.7645862 -0.6431362 -0.04223489 -0.8210883 -0.5698303 -0.03327655 -0.9158637 -0.398644 -0.04771542 -0.9394561 -0.3405304 -0.03822898 -0.117805 -0.9929905 -0.009597718 -0.1400217 -0.990122 -0.0072335 -0.4893447 -0.8708074 -0.04729104 -0.4929854 -0.8687915 -0.0465483 -0.7640646 -0.6415161 -0.06828343 -0.7859734 -0.6134501 -0.07697296 -0.9138142 -0.3983271 -0.07924246 -0.9344152 -0.344188 -0.09166783 -0.3777934 -0.9258753 -0.005214095 -0.2044599 -0.9774667 -0.05248945 -0.4868328 -0.8709053 -0.06721514 -0.4575791 -0.8874282 -0.05561167 -0.6286454 -0.772125 -0.09288805 -0.7432331 -0.6607646 -0.1048562 -0.7821851 -0.6146297 -0.1020639 -0.9108907 -0.3879981 -0.1404843 -0.9300481 -0.3409714 -0.1369282 -0.9488976 -0.2800242 -0.1455324 -0.1516323 -0.9880796 -0.0265789 -0.4152232 -0.906756 -0.07337123 -0.2969495 -0.9519371 -0.07507973 -0.439008 -0.8953515 -0.07495206 -0.6277034 -0.7698254 -0.1155737 -0.7140158 -0.6847457 -0.145962 -0.7362893 -0.6611266 -0.1441869 -0.91085 -0.3824346 -0.1552289 -0.9327211 -0.3191412 -0.1678701 -0.9419953 -0.291458 -0.1664243 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/meshes/propdrive_3536_motor_can.dae b/Gazebo/models/mini_talon_vtail/meshes/propdrive_3536_motor_can.dae new file mode 100644 index 00000000..f7d615b8 --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/meshes/propdrive_3536_motor_can.dae @@ -0,0 +1,1081 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-07-04T16:31:15 + 2023-07-04T16:31:15 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.8980392 0.9176471 0.9294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.5294118 0.5490197 0.5490197 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.6862745 0.6078432 0.5294118 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.1019608 0.1019608 0.1019608 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -0.005292117 0.009621739 -0.002152025 -0.005225241 0.009371757 -0.00286889 -0.004585802 0.009621739 -0.003399372 -0.004442989 0.009371757 -0.003961443 -0.003698706 0.009621679 -0.004339456 -0.003560781 0.009371757 -0.00476998 -0.002634644 0.009621739 -0.005064666 -0.002672851 0.009371697 -0.005315721 -0.00140798 0.009371817 -0.005802929 -0.001015365 0.009621798 -0.005639076 2.27537e-4 0.009371757 -0.005969285 7.06654e-4 0.009621739 -0.005682766 0.00170505 0.009371757 -0.005736589 0.00196433 0.009621739 -0.005384504 0.00293374 0.009370267 -0.005222916 0.003124415 0.009621739 -0.004825592 0.004034817 0.009373843 -0.004452168 0.004463076 0.009621798 -0.003677546 0.00511825 0.009371817 -0.003189861 0.005283474 0.009621679 -0.002330243 0.005745768 0.009371757 -0.00183618 0.005688548 0.009621739 -0.001105189 0.006045401 0.009371817 -3.66514e-4 0.005792737 0.009621739 3.67613e-4 0.005970656 0.009371697 9.6902e-4 0.005424022 0.009621798 0.002150714 0.00567609 0.009371757 0.002136707 -0.005381762 0.006621718 -0.002561569 -0.004774451 0.006621718 -0.003549098 -0.003979504 0.006621718 -0.00443387 -0.002621412 0.006621718 -0.005360066 -9.10946e-4 0.006621718 -0.005903899 7.35678e-4 0.006621718 -0.005931675 0.002188265 0.006621718 -0.005574762 0.003259599 0.006621718 -0.005024909 0.004201292 0.006621718 -0.004298388 0.005226492 0.006621718 -0.003013253 0.00585395 0.006621718 -0.001490473 0.006043732 0.006621718 -1.55144e-4 0.005919754 0.006621718 0.001331627 0.002628326 1.21737e-4 9.82575e-4 -0.002631783 1.2187e-4 -7.16571e-4 0.002146601 3.74032e-4 0.001401901 0.002260804 1.21802e-4 0.001677453 0.001732051 3.71695e-4 0.00188589 0.001226305 3.71669e-4 0.002251982 0.00157696 1.21898e-4 0.002342104 5.22778e-4 3.71623e-4 0.002503991 5.69885e-4 1.21893e-4 0.002757906 -2.23834e-4 3.71574e-4 0.002537608 -4.76855e-4 1.2188e-4 0.002758264 -0.001009821 3.71288e-4 0.002325713 -0.00150752 1.21895e-4 0.002337753 -0.001775562 3.71982e-4 0.001786589 -0.002273857 1.21892e-4 0.001563251 -0.002275168 3.69715e-4 0.001019835 -0.002692401 1.2181e-4 4.85257e-4 -0.00246644 3.72615e-4 2.1149e-4 -0.002363502 3.70308e-4 -7.23461e-4 0.005788505 0.002111673 0.001808464 0.005476057 0.002111434 0.00261265 0.005242943 0.002113997 0.003072321 0.004622817 0.002112209 0.003940284 0.004113554 0.002111256 0.004471302 0.003306448 0.002109944 0.005091547 0.002516984 0.002111554 0.005523443 0.001816689 0.002112686 0.005786299 9.55181e-4 0.002108514 0.005989789 1.70486e-4 0.002112329 0.006056904 -5.50245e-4 0.002111732 0.006026208 -0.001444637 0.002112269 0.005877435 -0.002430677 0.002109408 0.005526959 -0.003327012 0.002112686 0.005033671 -0.003961026 0.002114057 0.004538357 -0.004463374 0.002100229 0.004020273 -0.004881262 0.002119481 0.003543257 -0.005013227 0.002088069 0.003300905 -0.005384147 0.002113163 0.002648472 -0.005686998 0.002108812 0.001891613 -0.005935728 0.002111852 7.90629e-4 -0.005965113 0.002111017 -4.07607e-4 -0.005819261 0.002099394 -0.001290142 -0.005642235 0.002110898 -0.001939415 2.87885e-4 0.006614208 -0.01546794 -0.00749731 0.006611287 -0.00644809 -0.007183313 0.006610393 -0.006941974 -0.006893098 0.006610572 -0.007450461 -0.006393074 0.006612062 -0.008507251 -0.006629228 0.006610691 -0.007972478 -0.006007432 0.006612837 -0.009572386 -0.01466691 0.00713247 -0.004904866 -0.01404732 0.007131695 0.006548345 -0.01447194 0.007132232 0.005523204 -0.01482582 0.007132232 0.004490017 -0.01517862 0.007134795 0.003063261 -0.01539689 0.007131516 0.001621544 -0.01547658 0.007132232 1.47744e-4 -0.01544106 0.007132232 -9.46154e-4 -0.01533544 0.007132232 -0.002048611 -0.015069 0.007132232 -0.003492057 -0.006585478 0.006606459 -0.002204298 -0.009866237 0.006610751 -3.98915e-4 -0.009580016 0.006606996 -3.64395e-4 -0.009049475 0.006609678 -3.69154e-4 -0.008648335 0.006610393 -4.40479e-4 -0.008249402 0.006610929 -5.65248e-4 -0.008115828 0.006601393 -6.28771e-4 -0.007980585 0.006603598 -6.93195e-4 -0.007849395 0.006603837 -7.65019e-4 -0.00772202 0.006603717 -8.43696e-4 -0.007599771 0.006605744 -9.27257e-4 -0.007481634 0.006603419 -0.001019656 -0.007367789 0.006605744 -0.001114666 -0.007257819 0.006604969 -0.001217126 -0.007153451 0.006605923 -0.001324117 -0.007050275 0.006610035 -0.001433014 -0.006962537 0.006606161 -0.001553833 -0.006873488 0.006608545 -0.001675367 -0.006784796 0.006614089 -0.001796126 -0.006716549 0.006609618 -0.001931548 -0.006626844 0.006619274 -0.002055466 -0.006491124 0.006595909 -0.002483546 -0.01315289 0.00660789 0.007215797 -0.01351964 0.006613969 0.007580339 -0.01278251 0.006608009 0.006808698 -0.0124318 0.006608068 0.006384968 -0.01210004 0.006609618 0.005946099 -0.0117889 0.006611287 0.005492568 -0.01150077 0.006611287 0.005024731 -0.01123124 0.006612479 0.004544436 -0.01098537 0.006613373 0.004052102 -0.01077055 0.006612658 0.003548324 -0.01038163 0.006610155 0.002483963 -0.01574921 0.007128417 0.00757879 -0.01509201 0.007133841 0.008821725 -0.01637935 0.007151663 0.006109833 -0.01672595 0.007128834 0.005024433 -0.01707786 0.007132232 0.00366348 -0.01734834 0.007134437 0.001999855 -0.01743173 0.007128834 8.54439e-4 -0.01744663 0.007132232 -5.51603e-4 -0.01730692 0.007132232 -0.00224179 -0.01700425 0.007132232 -0.003910481 -0.01655066 0.007134258 -0.005517244 -0.009876251 0.002620458 -4.07853e-4 -0.00965631 0.002622544 -3.78866e-4 -0.009356915 0.002622246 -3.64256e-4 -0.009057998 0.002622783 -3.79998e-4 -0.008761644 0.002622246 -4.24874e-4 -0.00854367 0.002622187 -4.7883e-4 -0.008400321 0.002622127 -5.22937e-4 -0.008258879 0.002619981 -5.73649e-4 -0.00812149 0.002618312 -6.31883e-4 -0.007987082 0.002621233 -6.97709e-4 -0.007855832 0.002622008 -7.69671e-4 -0.007668614 0.002625465 -8.8998e-4 -0.006589651 0.002621889 -0.002210319 -0.007428944 0.002622306 -0.001070499 -0.007208943 0.002624809 -0.001275837 -0.007060408 0.002623319 -0.001440823 -0.006918609 0.00262463 -0.001623988 -0.00675559 0.002622723 -0.00187689 -5.4698e-4 0.002444624 -0.006660401 -1.64137e-4 0.002122044 -0.006672143 -7.92715e-4 0.002446711 -0.006420075 -5.54508e-4 0.002121984 -0.006180465 -0.001150548 0.002449512 -0.006290137 -0.001007497 0.002121865 -0.005986034 -0.001574277 0.002445399 -0.006364583 -0.001410007 0.002121746 -0.0059821 -0.00183165 0.002121925 -0.006133317 -0.001846909 0.002446532 -0.006584525 -0.001999557 0.002446532 -0.006861567 -0.002144277 0.002121746 -0.006437242 -0.002325057 0.002121865 -0.006816685 -0.00202775 0.002447128 -0.007172465 -0.002339005 0.002121806 -0.007298529 -0.001948714 0.002445459 -0.007451236 -4.39894e-4 0.006621718 -0.006917297 -5.93451e-4 0.006621718 -0.006599962 -9.05332e-4 0.006621718 -0.006351172 -0.001360833 0.006621718 -0.006297528 -0.001690924 0.006621718 -0.006439507 -0.00192362 0.006621718 -0.006685972 -0.002037286 0.006621718 -0.007089018 -0.00187391 0.006621718 -0.007602334 -0.004741013 0.002448976 0.00496149 -0.004386246 0.002121865 0.004855871 -0.00505954 0.002443969 0.005386352 -0.004548311 0.002121806 0.005297362 -0.004797458 0.002121746 0.005584895 -0.005266606 0.002122104 0.005821585 -0.005568027 0.002451121 0.005518913 -0.005776703 0.002121746 0.005804717 -0.00605303 0.00244677 0.005313873 -0.006178975 0.002121925 0.005625128 -0.006297826 0.002447247 0.004904568 -0.006584763 0.002122402 0.005098223 -0.006300747 0.002447962 0.00455302 -0.006612002 0.002121925 0.004429042 -0.0048514 0.006621718 0.005173385 -0.005207598 0.006621718 0.005462348 -0.005604684 0.006621718 0.005506038 -0.005926966 0.006621718 0.005400836 -0.006219506 0.006621718 0.005101263 -0.006322264 0.006621718 0.004633784 0.007436871 0.002447009 0.003085315 0.00795263 0.002121746 0.002765178 0.007749438 0.002122163 0.003218531 0.007070899 0.002446472 0.003289699 0.007132887 0.002122342 0.003624498 0.006727993 0.002448916 0.003314256 0.006469964 0.002121984 0.003586769 0.006357789 0.002445697 0.003154575 0.006045937 0.002121746 0.003309786 0.006093978 0.002447426 0.002807557 0.005798459 0.002121806 0.002927601 0.006060719 0.002445816 0.002361178 0.005720555 0.002121984 0.002437174 0.005868852 0.002121806 0.001958906 0.007484555 0.006621718 0.00303632 0.006942033 0.006621718 0.003332078 0.006401598 0.006621718 0.003190755 0.006129264 0.006621718 0.002872407 0.006042778 0.006621718 0.002462565 0.004884898 1.21644e-4 0.001801669 0.005704522 6.2292e-4 0.002058625 0.006003856 6.23173e-4 7.60985e-4 0.005190253 1.21687e-4 3.29991e-5 0.006025671 6.21882e-4 -4.62322e-4 0.004858493 1.21654e-4 -0.001818299 0.005807936 6.21909e-4 -0.001635313 0.005362749 6.21936e-4 -0.00274223 0.003685891 1.21609e-4 -0.003628134 0.004707634 6.21971e-4 -0.003739356 0.003768026 6.21913e-4 -0.004675984 0.002038121 1.21575e-4 -0.004719376 0.00260812 6.21975e-4 -0.005389273 0.001035153 6.20732e-4 -0.005904138 3.51917e-4 1.217e-4 -0.005098164 -5.80755e-4 6.21899e-4 -0.005934834 -0.001524567 1.21658e-4 -0.00488305 -0.001749455 6.21859e-4 -0.005694806 -0.00284785 6.21822e-4 -0.005228579 -0.003310501 1.21657e-4 -0.003893136 -0.003832399 6.21792e-4 -0.00455451 -0.004856944 6.21739e-4 -0.003464818 -0.004717767 1.21452e-4 -0.001998841 -0.005628764 6.2292e-4 -0.001973927 0.00601226 0.002112627 7.87457e-4 0.005927085 0.002097964 -0.001154065 0.00572884 0.002113103 -0.001901745 0.005450665 0.002097606 -0.002567589 0.005140304 0.002110958 -0.003140866 0.00473082 0.002111077 -0.003715872 0.004130065 0.00211203 -0.004373311 -1.03615e-4 0.002090036 -0.005962908 -7.30569e-4 0.002113223 -0.005925178 -0.002492427 0.002114593 -0.005415678 -0.003202974 0.002099215 -0.005018174 -0.003617644 0.00211054 -0.004741191 -0.004340291 0.002111673 -0.004082143 -0.005288839 0.002110123 -0.002756297 0.004520595 0.002622544 0.008649647 0.004845082 0.002122104 0.00818783 0.004604816 0.002621293 0.00885415 -0.001484334 0.002121746 0.008593559 -7.18494e-4 0.002121925 0.00740993 -9.03583e-5 0.002623677 0.00754255 2.8922e-5 0.002624452 0.007452249 1.52664e-4 0.002623736 0.00736761 1.18485e-4 0.002121746 0.006804466 3.44925e-4 0.002624571 0.007252633 6.14726e-4 0.002624511 0.007122397 8.96661e-4 0.002624392 0.007019639 0.001187324 0.002624392 0.00694549 0.001079082 0.002121925 0.00643903 0.001484036 0.002625167 0.006901264 0.002107799 0.002121746 0.006399095 0.001703858 0.002621173 0.00688517 0.001853883 0.002622961 0.006885707 0.002002656 0.002619922 0.00689131 0.002152383 0.002622961 0.006907641 0.002300143 0.002621173 0.006928861 0.003112256 0.002121925 0.006627619 0.002446889 0.002621948 0.006958484 0.002592086 0.002621173 0.006995022 0.002734959 0.002620697 0.007038176 0.002876281 0.002622127 0.007090628 0.003083705 0.002622544 0.007179975 0.003346979 0.002622723 0.007323086 0.004263818 0.002121925 0.007389068 0.003594517 0.002622723 0.007491409 0.003824234 0.002622723 0.007683694 0.004033684 0.002622663 0.007897853 0.004220724 0.002622663 0.008131742 0.004383981 0.002620339 0.008382737 0.005244731 0.002621054 -0.008137047 0.005384504 0.002620398 -0.008318722 0.00468862 0.002122044 -0.008193194 0.004354953 0.002121746 -0.00749439 0.004958629 0.002622723 -0.007644116 0.005102336 0.002617239 -0.007917106 0.007691621 0.002120792 0.007244169 0.01013273 0.002857148 0.006935298 0.009420037 0.002121627 0.004834294 0.01556956 0.005121707 0.008105576 0.01352095 0.004191458 0.007332086 0.01618474 0.005117952 0.006814002 0.01434534 0.007621705 0.006042957 0.01403725 0.006621718 0.006732285 0.01501238 0.006621718 0.004135429 0.01320773 0.007621645 0.0082286 0.01333045 0.007131516 0.008031189 0.012138 0.007621705 0.009736478 0.01056259 0.007621705 0.01145327 0.008110582 0.007621705 0.01330184 0.005342841 0.007621705 0.01463145 0.002367854 0.007621705 0.01539015 -6.98477e-4 0.007621705 0.01554852 -0.003736138 0.007621705 0.01510018 -0.006626367 0.007621705 0.01406258 -0.009226143 0.007621645 0.01249444 -0.01081001 0.006621718 0.01113563 -0.01101517 0.007621705 0.01091504 -0.009718 0.006611883 0.01210492 -0.01231247 0.007621705 0.009432733 -0.01261734 0.006621718 0.009033083 -0.0138179 0.007621645 0.007033288 -0.01350533 0.007131576 0.007585644 -0.01491069 0.007621705 0.004226624 -0.01544022 0.007621705 0.001225173 -0.01537281 0.007621705 -0.001822233 -0.01490497 0.007621705 -0.004092514 -0.01426929 0.007621705 -0.005959033 0.01619988 0.02962172 0.006795227 0.0171715 0.005124688 0.003740131 0.01690578 0.02962172 0.004721641 0.01736545 0.02962172 0.002559185 0.01744878 0.007133901 0.001766085 0.01755911 0.02962172 -4.13414e-4 0.01753187 0.00712502 1.41206e-5 0.01744371 0.007134437 -0.001734673 0.01720154 0.02962172 -0.003445386 0.01718115 0.007132232 -0.003447234 0.01674896 0.007132232 -0.005135357 0.01662635 0.02962172 -0.005548834 0.01625674 0.007128655 -0.006499886 0.01581054 0.02962172 -0.007571995 0.01581037 0.007152199 -0.007545888 0.01526331 0.007129013 -0.008562445 0.01449984 0.02962172 -0.009837269 0.01448315 0.007132232 -0.009827017 0.01342958 0.007131934 -0.01121491 0.01315283 0.02962172 -0.01155227 0.0122556 0.007134199 -0.01248168 0.01161581 0.02962172 -0.01309943 0.01140642 0.007129013 -0.01324719 0.01047313 0.007128655 -0.01399183 0.009886801 0.02962172 -0.01442962 0.009547054 0.007152199 -0.01465213 0.007630348 0.02962172 -0.01575493 0.008550584 0.007129013 -0.01523476 0.007510185 0.007128655 -0.01576924 0.006430625 0.00715053 -0.01625096 0.004350721 0.02962172 -0.01694583 0.005319952 0.007128775 -0.01662939 0.0039379 0.007134735 -0.01701372 0.002754032 0.007128715 -0.01723355 9.32084e-4 0.02962172 -0.01745986 0.001342535 0.007131934 -0.0174036 -2.05456e-5 0.005783259 -0.01744145 -0.002194762 0.02962172 -0.01733106 -0.001496016 0.005129516 -0.01738154 -0.005131244 0.02962172 -0.01669865 -0.00532943 0.005143225 -0.01661276 -0.005915105 0.005903363 -0.01640284 -0.007151365 0.007131934 -0.01590657 -0.008342862 0.02962172 -0.01535063 -0.008662045 0.007132232 -0.01513558 -0.01022458 0.007128536 -0.01412642 -0.01120495 0.02962172 -0.01340305 -0.01144218 0.007151603 -0.01316928 -0.01226913 0.007128715 -0.0123825 -0.01362872 0.02962172 -0.01093029 -0.01321923 0.007132232 -0.01137298 -0.01426231 0.007132232 -0.01003557 -0.01551938 0.02962172 -0.008028626 -0.01517093 0.007132232 -0.008603632 -0.01597458 0.007128357 -0.007002532 -0.01683819 0.02962172 -0.004703819 -0.01595199 0.007621705 -0.005761325 -0.01585996 0.02962172 -0.00605154 -0.01671069 0.007621705 -0.003017544 -0.01675224 0.02962172 -0.002780675 -0.01696002 0.007621705 -4.41269e-4 -0.01697635 0.02962172 9.06682e-4 -0.01689291 0.007621705 0.00175172 -0.01644903 0.02962172 0.00425601 -0.01644289 0.007621705 0.00425446 -0.01581317 0.007621705 0.00619924 -0.01575833 0.02962172 0.006338596 -0.01494705 0.007621705 0.008099079 -0.01484537 0.02962172 0.008285403 -0.01351773 0.007621705 0.01032924 -0.01351267 0.02962172 0.01032543 -0.01183301 0.02962172 0.0122348 -0.0118286 0.007621705 0.01223021 -0.009639739 0.007621705 0.01405024 -0.009440898 0.02962172 0.01418554 -0.007394015 0.007621705 0.0153371 -0.007259011 0.02962172 0.01540201 -0.005080819 0.007621705 0.01628047 -0.005265474 0.02962172 0.01620817 -0.002365648 0.02962172 0.01689767 -0.002555608 0.007621705 0.0168482 -4.77317e-4 0.007621705 0.01704806 4.77073e-4 0.02962172 0.01704722 0.002168834 0.007621705 0.01692527 0.002902507 0.02962172 0.01681298 0.004248261 0.007621705 0.01651597 0.005065023 0.02962172 0.01628911 0.006268918 0.007621705 0.01587736 0.007546782 0.02962172 0.01532286 0.008556306 0.007621705 0.01476633 0.01032763 0.02962172 0.0136016 0.01065969 0.007621705 0.01333713 0.01252239 0.02962172 0.01160567 0.01281028 0.007621705 0.01129394 0.0141012 0.02962172 0.009612143 0.01433217 0.007621705 0.00925666 0.01517856 0.02962172 0.007787585 0.01541876 0.007621705 0.007314741 0.01617789 0.02962172 0.005449116 0.01618564 0.007621705 0.005372643 -9.61562e-4 0.002622783 0.008660674 -7.79804e-4 0.002620816 0.008324086 -7.86431e-4 0.006607949 0.008307039 -6.59477e-4 0.00262463 0.008142054 -6.90366e-4 0.006596386 0.008178293 -6.02761e-4 0.006596446 0.00805813 -4.71852e-4 0.002624094 0.007905662 -5.13011e-4 0.006614387 0.007931411 -4.10307e-4 0.006596505 0.007831513 -2.62179e-4 0.002623975 0.00769025 -3.07815e-4 0.006613433 0.007715284 -1.96486e-4 0.006596624 0.007625102 -8.25561e-5 0.006597101 0.007530272 3.65554e-5 0.006614327 0.007430255 1.61045e-4 0.00659275 0.007359504 2.87923e-4 0.00659275 0.007282495 5.54651e-4 0.006596803 0.007146179 0.002224683 0.009621679 0.001302301 0.001522243 0.009621679 0.002069234 6.8041e-4 0.009621679 0.002475142 -3.7758e-4 0.009621679 0.002528488 -0.001361012 0.009621679 0.002133846 -0.001986563 0.009621679 0.001524388 -0.002356231 0.009621679 8.03851e-4 -0.002472817 0.009621679 -1.43508e-4 -0.00217545 0.009621679 -0.001160442 -0.009240746 0.006605446 0.01177465 -0.00849539 0.006607115 0.01131993 -0.007733225 0.006608247 0.01093208 -0.009916782 0.006605029 2.08039e-4 -0.009993076 0.006604015 7.83884e-4 -0.00694257 0.006609022 0.0105912 -0.01009672 0.006604075 0.001356184 -0.005911648 0.006610035 0.01024925 -0.0102275 0.006605088 0.001922845 -0.004326045 0.006612122 0.009912014 -0.003259539 0.006608605 0.009809076 -0.005419671 0.006621718 0.002557158 -0.006071329 0.006621718 0.004105508 -0.005586445 0.006621718 0.003902792 -0.004664719 0.006621718 0.003799378 -0.005847334 0.006621718 0.001283466 -0.005078554 0.006621718 0.004010081 -0.004775524 0.006621718 0.004381477 -0.00597161 0.006621718 -2.07085e-4 -0.003587186 0.006621718 0.004836916 -0.004702806 0.006621718 0.004767358 -0.001808643 0.006611287 0.009814143 -0.001163721 0.006610691 0.009248077 -0.002370297 0.006607651 0.009800076 -0.002253115 0.006621718 0.005611002 -0.005783617 0.006621718 -0.001434504 -0.001019656 0.006611168 0.008770763 -0.006435215 0.006612837 -0.002631962 -0.006344616 0.006614983 -0.003357887 -9.62552e-4 0.006621718 0.005963206 -0.006946861 0.006610214 -0.005174219 2.38148e-4 0.006621718 0.006053686 4.15872e-4 0.006613492 0.007200002 0.002008259 0.006621718 0.00574088 0.001405417 0.006608843 0.006901383 0.001667082 0.006620109 0.006861031 0.001922547 0.006609916 0.006878435 0.002156317 0.006608188 0.006902456 0.002304494 0.006612539 0.006914615 0.002450823 0.006606042 0.006955146 0.002594769 0.006603956 0.006991326 0.002738654 0.006605207 0.007035315 0.002878785 0.006604373 0.007085502 0.003017723 0.006605565 0.007143616 0.003838419 0.006621718 0.00472331 0.003151476 0.00660324 0.007209479 0.003284096 0.006605267 0.007279574 0.003410279 0.006605327 0.007353305 0.005161881 0.006604611 0.008580148 0.00435537 0.006609201 0.008310854 0.00353378 0.006604194 0.007436811 0.003656089 0.006611526 0.007525682 -0.005530238 0.006612479 -0.01443743 -0.005484521 0.00660634 -0.01389837 0.003966748 0.006611049 0.007804512 0.005689799 0.00660932 0.008362293 -0.005730569 0.006605923 -0.01063311 -0.00142765 0.006621718 -0.007879853 -0.005627274 0.006605446 -0.01117092 -0.004145562 0.006621718 -0.01489871 -0.005465686 0.006601333 -0.01335561 -0.00554955 0.006604254 -0.0117135 0.006496131 0.006609976 0.008078277 -0.005469083 0.006601393 -0.0128076 -4.4118e-4 0.006621718 -0.007269978 -0.005496799 0.006602942 -0.01225948 0.00521022 0.006621718 0.003141164 0.006202816 0.006621718 0.002032756 0.007566332 0.006612896 0.007801175 0.006611347 0.006621718 0.001735568 0.009108841 0.006610929 0.007583558 0.007057011 0.006621718 0.001737058 0.01021629 0.006610214 0.007548689 0.00737673 0.006621718 0.001900553 9.30628e-4 0.006608188 -0.01357793 -0.001420915 0.006621718 -0.01541274 0.001448988 0.006609082 -0.01252752 4.29734e-4 0.006604731 -0.01490986 -9.6912e-4 0.006621718 -0.007867395 0.005018174 0.006608605 -0.005010187 0.004919767 0.006608188 -0.005222797 0.004856109 0.006612479 -0.00535655 0.005125761 0.006608426 -0.004820466 0.004817426 0.006606638 -0.005503773 0.00525707 0.006613433 -0.004605889 0.004777431 0.006603956 -0.005646347 0.002141177 0.006608724 -0.0114237 0.00474292 0.006605684 -0.005792677 0.005488336 0.006614148 -0.004328668 0.004717648 0.006603837 -0.005939722 0.0113877 0.006608963 0.007625222 0.004697859 0.006605565 -0.006088674 0.004687368 0.006603717 -0.006237328 0.004682362 0.006605267 -0.006387531 0.002953052 0.00660932 -0.01040393 -5.95572e-4 0.006621718 -0.007601082 0.005858778 0.006611824 -0.004000067 0.004683136 0.006605327 -0.006533682 0.0046947 0.006603419 -0.006682515 0.00470519 0.006613135 -0.006831705 0.003769397 0.006608903 -0.009568333 0.004421293 0.006608188 -0.009009957 0.004876434 0.006615459 -0.007496893 0.004870295 0.006604135 -0.008664309 0.005136311 0.006611526 -0.007996857 0.005374193 0.006609737 -0.008314251 0.0133447 0.00661391 0.008014142 0.01278948 0.006604969 0.007857561 0.009423196 0.006611824 -0.003245413 0.009178698 0.006608486 -0.003765523 0.009698569 0.006609022 -0.002738356 0.01014435 0.006609678 -0.001984953 0.01078921 0.006612777 -0.001082897 0.01183736 0.00661081 7.79772e-5 0.007589101 0.006621718 0.002189993 0.01266199 0.006610095 8.12623e-4 0.007661163 0.006621718 0.002555489 0.01335322 0.006608724 0.001327157 0.01406502 0.006608247 0.001790881 0.01483726 0.006605982 0.002212047 0.01536172 0.006612658 0.002460181 0.006126523 0.002121686 0.007669985 -0.003134727 0.002121686 0.009298622 -0.004678726 0.002140104 0.009524345 0.0103712 0.002121686 0.002015352 0.007975399 0.002121806 0.00238651 0.007861435 0.002121806 0.002002298 0.007576048 0.002121865 0.001645028 0.01060426 0.002141952 -6.30604e-4 0.00620687 0.002122104 0.00157541 0.006739437 0.002121746 0.001389384 0.009640157 0.002121686 -0.001838386 -0.007056593 0.002121686 0.007814347 0.00719881 0.002121806 0.001438021 -0.008550882 0.002121686 0.006103157 -0.004476428 0.002122342 0.004223048 -0.004827082 0.002121746 0.003809571 -0.005176246 0.002121865 0.003625571 0.007992327 0.002121925 -0.002883255 -0.01003682 0.002121865 0.003167808 -0.00579375 0.002122342 0.003597617 0.006620407 0.002121925 -0.00303775 -0.006349325 0.002121865 0.00394392 0.00570327 0.002121746 -0.00350672 0.004939675 0.002121925 -0.00419718 -0.009612143 0.002121686 0.00150156 0.004583954 0.002134144 -0.004754424 0.004183292 0.002121925 -0.006095051 -0.007606983 0.002121806 -3.28194e-4 -0.008395552 0.002121746 -1.64716e-6 -0.006927132 0.002121746 -8.46947e-4 -0.009402632 0.002119243 1.50205e-4 -0.006357014 0.002121806 -0.001540839 0.002071797 0.002111017 -0.005622148 0.001251876 0.002113044 -0.005847752 -0.005900859 0.002121806 -0.002759993 -0.005870461 0.002121746 -0.003676593 0.003599166 0.002121686 -0.009044408 -0.006047248 0.002121746 -0.004540741 -1.04725e-4 0.002121806 -0.007223665 -0.006461739 0.002121746 -0.00534147 -2.07928e-4 0.002121746 -0.007582008 5.17293e-4 0.002121686 -0.01048296 0.002378165 0.002119779 -0.01022368 -4.23485e-4 0.002121865 -0.007893085 -0.006391882 0.002121686 -0.007333397 -0.007140636 0.002119421 -0.006098747 -8.84863e-4 0.002122342 -0.008186221 -0.002812623 0.002121567 -0.01013463 -0.001582801 0.002122104 -0.00818032 -0.005785822 0.002121865 -0.008721292 -0.002109527 0.002122104 -0.007815599 -0.001914978 3.7173e-4 -0.001532733 -0.001387596 0.009621679 -0.002044439 -0.001299858 3.7436e-4 -0.002084136 -6.46487e-4 3.73052e-4 -0.002367615 -3.81142e-4 0.009621679 -0.00243473 5.68863e-5 3.75483e-4 -0.002469897 4.09367e-4 0.009621679 -0.002437949 7.69886e-4 3.72144e-4 -0.002352058 0.001106917 0.009621679 -0.002227425 0.001336634 3.72975e-4 -0.002105474 0.001791298 0.009621679 -0.001758515 0.00207442 3.75152e-4 -0.001442849 0.002246618 0.009621679 -0.001141607 0.002488315 3.70711e-4 -5.22947e-4 0.002487659 0.009621679 -4.99143e-4 0.002535879 0.009621679 3.09996e-4 0.002509891 3.67467e-4 5.42353e-4 -0.00122106 0.002620995 0.009884893 -0.001210629 0.002623796 0.009644985 -0.00118035 0.002619028 0.009381294 -0.00111407 0.002619028 0.009090602 0.009191215 0.002620995 -0.00378859 0.008984506 0.002625584 -0.003680586 0.008707761 0.002626001 -0.003565669 0.008422076 0.002625942 -0.003478705 0.008128881 0.002626001 -0.00342065 0.007831275 0.002626001 -0.00339204 0.007605135 0.006611704 -0.003374159 0.007532238 0.002626061 -0.003393173 0.007447719 0.006596565 -0.003394782 0.00729984 0.006596624 -0.003410577 0.007312774 0.002625584 -0.003413319 0.007144987 0.006613254 -0.003426194 0.00716561 0.002626895 -0.003436088 0.007002294 0.006606101 -0.003461122 0.007018327 0.00262469 -0.003465294 0.006874263 0.002626836 -0.003503143 0.006855666 0.006613433 -0.003494679 0.006730854 0.002625405 -0.00354731 0.006721913 0.006596624 -0.003545999 0.006591081 0.002626836 -0.003598809 0.006582796 0.006597101 -0.003597259 0.006452798 0.002625465 -0.003657042 0.006436586 0.006614327 -0.003650188 0.006318807 0.002626836 -0.00372219 0.006313979 0.006590902 -0.003723025 0.006187021 0.002625465 -0.003793835 0.006182253 0.006594181 -0.003794133 0.006060183 0.002626836 -0.003871977 0.006056547 0.006593227 -0.003871917 0.005936086 0.002624869 -0.003956377 0.005752921 0.002622187 -0.004098594 0.005534589 0.002622246 -0.004302799 0.005337893 0.002622306 -0.00452733 0.005164444 0.002622425 -0.004770398 0.005015969 0.002622544 -0.005029559 0.00492382 0.002621948 -0.005228459 0.00486952 0.002622485 -0.005367517 0.004822015 0.002622067 -0.005509376 0.004762172 0.002622663 -0.00573486 0.004711508 0.002622842 -0.006029248 0.004690408 0.002623021 -0.006326913 0.004698812 0.0026232 -0.006624281 0.004759609 0.002622365 -0.007056593 -0.007856607 0.002621173 -0.005969166 -0.007658958 0.002625405 -0.005843698 -0.007419824 0.002622187 -0.005661725 -0.00720334 0.002625823 -0.00545752 -0.007006764 0.002625703 -0.005233108 -0.006877541 0.002625584 -0.005056321 -0.006794929 0.002620935 -0.00492978 -0.006705105 0.006609857 -0.0048002 -0.006722331 0.002625584 -0.004801273 -0.006642758 0.006598055 -0.004656851 -0.006654918 0.002626955 -0.004668593 -0.006583392 0.006596565 -0.004521191 -0.006593227 0.002625524 -0.004532098 -0.006524801 0.00660485 -0.004381 -0.006537437 0.002620875 -0.004392027 -0.006472408 0.006614208 -0.004238426 -0.006466746 0.002620875 -0.00416994 -0.006443679 0.006597101 -0.004098474 -0.006412506 0.006595075 -0.003951907 -0.006402254 0.002622544 -0.003879487 -0.006376981 0.006613671 -0.003801941 -0.006366491 0.006601452 -0.003656268 -0.006366431 0.002622604 -0.003583848 -0.006359338 0.00659424 -0.003510475 -0.006358861 0.002622187 -0.003367245 -0.006359398 0.006597936 -0.003211319 -0.006368875 0.0026232 -0.003129541 -0.00637108 0.006599068 -0.003062307 -0.006392896 0.006588876 -0.002918303 -0.006393074 0.002622663 -0.002920866 -0.006417691 0.006595194 -0.002770185 -0.006415367 0.002622306 -0.002763986 0.016828 0.007621705 0.002865314 0.01684755 0.02962172 0.002667963 0.01705116 0.02962172 1.3329e-4 0.01705092 0.007621705 -7.89658e-5 0.01682293 0.02962172 -0.002810597 0.01678097 0.007621705 -0.003047406 0.0161761 0.02962172 -0.005316793 0.0161283 0.007621705 -0.005458712 0.01523625 0.02962172 -0.007631421 0.01531344 0.007621705 -0.007448732 0.01378226 0.007621705 -0.01000595 0.01387953 0.02962172 -0.009835422 0.01257139 0.02962172 -0.0114628 0.01183015 0.007621705 -0.01222145 0.01071667 0.02962172 -0.0132023 0.01023352 0.007621705 -0.01356691 0.008955717 0.02962172 -0.01443642 0.008439242 0.007621705 -0.01475208 0.007118284 0.02962172 -0.01542782 0.005733489 0.007621705 -0.01600247 0.004340946 0.02962172 -0.01643067 0.003318965 0.007621705 -0.01664286 9.91524e-4 0.02962172 -0.01695668 0.001188218 0.007621705 -0.01693218 -0.001354515 0.007621705 -0.01691406 -0.002395629 0.02962172 -0.01680862 -0.004294514 0.007621705 -0.01642298 -0.005294263 0.02962172 -0.01611399 -0.007069885 0.007621705 -0.01541525 -0.007642745 0.02962172 -0.0151388 -0.008905708 0.007621705 -0.0144205 -0.009491741 0.02962172 -0.01404124 -0.0106644 0.007621705 -0.01318335 -0.01146531 0.02962172 -0.0125097 -0.01251608 0.007621705 -0.01144051 -0.01346892 0.02962172 -0.01030296 -0.01382124 0.007621705 -0.009810864 -0.0146979 0.02962172 -0.008447945 -0.0149613 0.007621705 -0.007987737 -0.01744639 0.02962172 -0.001171708 -0.01734399 0.02962172 0.002289354 -0.01656329 0.02962172 0.005662202 -0.01536273 0.02962172 0.008373141 -0.01470446 0.005120873 0.009471535 -0.01507371 0.005783677 0.008834242 -0.01363593 0.02962172 0.01101028 -0.01394259 0.00512284 0.01057618 -0.01280212 0.00512278 0.01194632 -0.01170104 0.005120933 0.01302081 -0.01155835 0.02962172 0.01315808 -0.01049917 0.007131695 0.01400089 -0.009448528 0.02962172 0.01476526 -0.009430706 0.007132232 0.01475346 -0.008281171 0.007128953 0.01542472 -0.006753325 0.02962172 0.0162003 -0.007131755 0.007134795 0.01600211 -0.005511641 0.007132232 0.01663374 -0.004265189 0.02962172 0.01701068 -0.004116237 0.007128655 0.01703053 -0.002969563 0.007134437 0.01727831 -0.001690387 0.02962172 0.01748406 -0.001249969 0.007132232 0.01748979 4.81521e-4 0.007134675 0.01753306 9.26396e-4 0.02962172 0.01752519 0.002229332 0.007125318 0.01739805 0.003525972 0.02962172 0.01721888 0.003955841 0.007134675 0.01709437 0.005622327 0.007132232 0.016622 0.006859481 0.02962172 0.01618754 0.00697422 0.007128655 0.01609671 0.008038401 0.007134437 0.01560235 0.009551942 0.02962172 0.01474738 0.009537339 0.007132232 0.01473355 0.01095163 0.007132232 0.01371568 0.01130062 0.02962172 0.01344347 0.01225012 0.007134735 0.01257157 0.01288539 0.02962172 0.01194602 0.01345688 0.007125258 0.01126563 0.01474881 0.02962172 0.009566843 0.01450037 0.007133841 0.009888589 0.01520848 0.005783259 0.00873363 0.005052506 0.007133364 0.01472598 0.008352756 0.007124602 0.01316249 0.003485739 0.00713253 0.01516932 0.009096086 0.007134437 0.01263868 0.001999139 0.007132232 0.01543295 0.01113331 0.007134377 0.01088815 3.483e-4 0.007133483 0.01555603 0.01472854 0.007100522 0.008532941 0.0126968 0.007131695 0.009013354 0.01427954 0.007102847 0.00835359 -0.002313315 0.007133483 0.01538151 0.01382553 0.007101237 0.008191347 -0.003890216 0.007131576 0.01505213 -0.007280945 0.007133305 0.01372736 -0.00876671 0.007131695 0.01281762 -0.01084083 0.007108032 0.01307469 -0.01119017 0.007111608 0.01341247 -0.0104832 0.007110357 0.01275461 -0.01011645 0.007106304 0.01244521 -0.0112214 0.005898952 0.01341873 -0.009560942 0.004929482 0.01200413 -0.008776187 0.004519939 0.01149022 -0.007843255 0.004081308 0.0109902 -0.006739914 0.00361675 0.01052528 -0.004714131 0.002925574 0.009980618 -0.002884089 0.00262314 0.009806573 -0.002330958 0.002621352 0.009806394 -0.001774609 0.002620577 0.009833276 0.005136311 0.00262463 0.008601725 0.005672991 0.002625584 0.008377909 0.0062204 0.002625584 0.008179962 0.00677663 0.002624154 0.008008122 0.007340967 0.00262171 0.007859766 0.008602261 0.00298345 0.007642328 0.009545981 0.00330621 0.007566869 0.01041769 0.003632187 0.007564783 0.01271569 0.004597306 0.007862448 0.01337236 0.007107436 0.008048951 0.01464766 0.005506217 0.00848329 0.01518118 0.007110297 0.008737683 0.01676356 0.007108032 0.002947449 0.01630753 0.007110357 0.002797722 0.01550012 0.007130563 0.001344919 0.0158562 0.007106304 0.002634823 0.01555347 0.007133841 2.73818e-4 0.01550197 0.007133901 -0.001251935 0.01530486 0.007133901 -0.002733469 0.01403516 0.007133483 -0.006654381 0.01238578 0.00713253 -0.009351253 0.0114144 0.007132232 -0.0105071 0.01061266 0.007132232 -0.01130437 0.009757995 0.007132232 -0.01205044 0.008536517 0.007132232 -0.01293802 0.007234573 0.007132232 -0.01370263 0.006195008 0.007130682 -0.01419478 0.003882765 0.007134377 -0.01498949 2.01296e-4 0.007101237 -0.01597261 0.001477479 0.007131695 -0.01540607 1.14817e-4 0.007102847 -0.01644688 4.56149e-5 0.007100522 -0.01692545 0.004901289 0.00262463 -0.008652687 0.004439055 0.002625584 -0.009005546 0.003993988 0.002625584 -0.009380638 0.00356698 0.002624154 -0.009776473 0.003161609 0.002624332 -0.01019203 0.002670466 0.00282067 -0.01075047 2.98436e-4 0.007093727 -0.01550036 4.30703e-5 0.005506098 -0.01683038 1.31971e-6 0.005680441 -0.01720499 0.01725178 0.005898892 0.003105044 0.01519882 0.004930615 0.002375364 0.01347601 0.004090607 0.001404464 0.01265239 0.003686964 7.88974e-4 0.01186823 0.003305494 1.00688e-4 0.01110923 0.002969503 -7.15504e-4 0.01025408 0.002625048 -0.001841783 0.009954929 0.00262314 -0.002309143 0.009678244 0.002621352 -0.002788126 0.009423315 0.002620577 -0.003283381 -0.01428073 0.007102847 0.008220374 -0.01466053 0.007100522 0.008519589 -0.01391321 0.007101237 0.007908284 -0.01413202 0.007134795 -0.006272971 -0.01347762 0.007131516 -0.00757718 -0.01269215 0.007132232 -0.008826434 -0.0120247 0.007132232 -0.009707987 -0.01130914 0.007132232 -0.01053851 -0.005626142 0.007106304 -0.01495295 -0.005565881 0.007113873 -0.0144701 -0.006594955 0.007131695 -0.01398348 -0.01008921 0.007133245 -0.01171636 -0.005710721 0.007110357 -0.01542526 -0.008015036 0.007133305 -0.01322108 -0.005809068 0.007108032 -0.01589506 -0.009923934 0.002624511 1.78142e-4 -0.00999844 0.002625465 7.5484e-4 -0.01010072 0.002625465 0.001327812 -0.01023 0.002624094 0.001895487 -0.01038724 0.002624332 0.00245434 -0.0106253 0.002820551 0.003159046 -0.01296001 0.004525482 0.00698769 -0.01355975 0.007106959 0.00758481 -0.01487499 0.005678832 0.008693099 -0.005734682 0.005565285 -0.01567423 -0.005492508 0.004773378 -0.01390558 -0.005473196 0.004328668 -0.01285415 -0.005568146 0.003820598 -0.01159679 -0.005826771 0.003305792 -0.01023268 -0.005856037 0.006610691 -0.01009887 -0.006453812 0.002749681 -0.00839591 -0.006701946 0.002625048 -0.007862985 -0.006957173 0.00262314 -0.007370233 -0.007233619 0.002621352 -0.006891071 -0.00753498 0.002620577 -0.006422758 0.01498043 0.007621705 0.004178106 0.01539289 0.007621645 0.00220704 0.01553899 0.007621705 3.66268e-4 0.01543158 0.007621705 -0.001961112 0.01473605 0.007621705 -0.004952132 0.01346558 0.007621705 -0.007747352 0.01166987 0.007621705 -0.01023775 0.009418964 0.007621705 -0.01232606 0.006801009 0.007621705 -0.01393049 0.003917992 0.007621705 -0.01498836 -0.01298105 0.007621705 -0.008411824 9.19992e-4 0.007621705 -0.01545244 -0.01107805 0.007621705 -0.01079308 -0.001467943 0.007621705 -0.01538866 -0.003413975 0.007621705 -0.01508361 -0.008746564 0.007621705 -0.01275616 -0.006106197 0.007621645 -0.0142095 -0.005738496 0.002230405 -0.009062588 -7.41164e-4 0.005123138 -0.01743167 -0.005333244 0.005117177 -0.01659721 -0.004572689 0.005123019 -0.01682794 4.65086e-4 0.003232479 -0.01304817 -0.002274274 0.005117774 -0.01729136 -4.32462e-4 0.004309773 -0.01555567 -0.004939556 0.004114687 -0.01427161 -0.003813564 0.005117416 -0.01701533 -0.005058825 0.003123819 -0.0117436 -0.003047883 0.005123972 -0.0171718 -0.01098448 0.002860844 0.005349755 -0.01284354 0.004083156 0.007881879 -0.006688237 0.002764642 0.009998679 -0.009654641 0.00400567 0.01135927 0.01223957 0.002866566 0.001067757 0.0146839 0.004006266 0.002776384 1.10031e-4 0.005300939 -0.01638096 1.94851e-4 0.005094826 -0.01592916 3.17147e-4 0.004848897 -0.01539587 4.71415e-4 0.004597067 -0.01484668 6.49995e-4 0.004352211 -0.01431077 9.29319e-4 0.004035592 -0.0136047 0.001469135 0.003540456 -0.01250451 0.002099931 0.003115653 -0.01150256 0.008950114 0.002121806 -0.003122508 0.01690816 0.005738675 0.003012299 0.01599252 0.005311846 0.002709507 0.01438081 0.004530906 0.001963376 0.01059091 0.002749443 -0.001361191 -0.01096981 0.005738914 0.01316815 -0.01025581 0.005315601 0.01253122 -0.005797028 0.003267288 0.01022791 -0.003438055 0.002627968 0.009828865 -0.001676619 0.002122044 0.009343683 0.01422452 0.005300819 0.008316397 0.0131973 0.004814445 0.007983446 0.0121622 0.004352271 0.00774908 0.01141178 0.004036068 0.007638037 -0.005573451 0.005136966 -0.0147174 -0.006154596 0.002968668 -0.009165108 -0.01422065 0.005300581 0.008191049 -0.01344376 0.004830539 0.007493734 -0.01264327 0.004315972 0.006621658 -0.01222741 0.004036247 0.006094992 -0.01154345 0.003540396 0.005075752 -0.01099193 0.00311613 0.004030168 0.00297898 1.2166e-4 0.004290878 0.001103639 1.21658e-4 0.005098581 0.004210412 1.21705e-4 0.003057599 -4.8617e-4 1.21745e-4 0.005156636 -0.001719474 1.21699e-4 0.004884004 0.002798974 1.21837e-4 1.44837e-4 -0.003018498 1.217e-4 0.004187524 -0.003998517 1.21727e-4 0.003228127 0.002661347 1.2178e-4 -8.04208e-4 -0.004782736 1.21657e-4 0.001903057 0.002297759 1.2178e-4 -0.001536309 -0.005114495 1.21687e-4 5.16968e-5 0.001514613 1.22003e-4 -0.002304792 3.24571e-4 1.21896e-4 -0.002709865 -0.002165734 1.2179e-4 -0.00161612 -0.001553773 1.21841e-4 -0.00221616 -6.83272e-4 1.21783e-4 -0.002618312 -0.005971074 6.18875e-4 -3.45466e-4 -0.005870223 6.21894e-4 0.001138985 -0.005537152 6.21923e-4 0.002284586 -0.0049842 6.21956e-4 0.003341913 -0.00423336 6.21991e-4 0.004269123 -0.002943754 6.20574e-4 0.005283057 -9.59443e-4 6.20732e-4 0.005988836 6.56543e-4 6.21896e-4 0.006019592 0.001825213 6.21859e-4 0.005779564 0.002923548 6.21822e-4 0.005313336 0.003908157 6.2179e-4 0.004639267 0.00493133 6.2119e-4 0.003551483 0.006268441 0.00244826 0.001947939 0.006626069 0.002447485 0.001744687 0.006925106 0.002446055 0.00171405 0.00721842 0.002447247 0.001799523 0.00750339 0.002446591 0.002034664 0.007638633 0.002446174 0.002346217 0.007644772 0.002446472 0.00267136 -0.006185591 0.002445757 0.004266798 -0.005989611 0.002446651 0.004062294 -0.00563836 0.002447247 0.003902494 -0.005145132 0.002448558 0.003984868 -0.004854559 0.002446949 0.004243075 -0.00472033 0.002445757 0.004549622 -0.001768052 0.002448141 -0.007694959 -0.001413047 0.002446889 -0.007883906 -0.001050412 0.002447783 -0.007880508 -7.41006e-4 0.002446472 -0.007742345 -4.66742e-4 0.00244385 -0.007383167 -4.31744e-4 0.002446234 -0.00697869 -0.01387226 0.005094766 0.007892072 -0.01457703 0.005506098 0.008474349 -0.00566399 0.00557208 -0.01649457 -0.005483865 0.0053339 -0.01655727 -0.01506572 0.007116913 0.008791863 -0.01506984 0.007091343 0.008826136 -0.005923569 0.007136583 -0.01640683 -0.005917489 0.007095396 -0.01638913 -0.005936861 0.007117211 -0.01637333 -0.01354199 0.007120668 0.007563531 -0.00729537 0.006610691 -0.005568087 -0.007828354 0.006609618 -0.005969345 -0.009105145 0.007153272 -0.01248186 -0.005534291 0.007133543 -0.01442718 -0.005543887 0.007104635 -0.0144481 0.01499247 0.005680143 0.008634209 0.01372778 0.005064606 0.00814253 0.01521641 0.007119655 0.008737683 0.01334381 0.007115781 0.008000254 0.008166432 0.006599307 0.007697582 0.004608452 0.006608009 0.008841812 -0.01122552 0.007124781 0.01342689 -0.001238167 0.006611347 0.009857356 9.76675e-4 0.006588459 0.006993949 7.21846e-4 0.006612718 0.007064938 0.01181077 0.007131159 0.01014995 0.01016026 0.00715053 0.01179033 0.007526576 0.007134139 0.01363122 0.006344676 0.00715059 0.01420933 -0.00101149 0.007152676 0.01551365 -0.004944264 0.007134377 0.01473778 -0.006125867 0.007155239 0.01427096 -0.009695112 0.007121682 0.01214253 -0.004972934 0.006599545 0.01002675 -0.009721279 0.007117927 0.01209032 -0.009729981 0.007096648 0.01213365 -2.44455e-5 0.00713247 -0.01745378 1.23508e-5 0.007116913 -0.01741242 -1.13626e-5 0.007097899 -0.01742607 0.01724743 0.007096529 0.003101527 0.01723736 0.007115602 0.003076612 0.0172621 0.007130444 0.003111839 2.9431e-4 0.007127046 -0.01546257 3.25884e-4 0.007117927 -0.01549774 0.004801273 0.006599068 -0.007237434 0.005626082 0.006597101 -0.004209518 0.00797528 0.006602108 -0.003397524 0.008489251 0.006610512 -0.003480017 0.002904891 0.007131159 -0.01520705 0.005154848 0.007144272 -0.01459866 0.01324063 0.007132232 -0.008106589 0.01462072 0.007135212 -0.005256056 0.01501923 0.007152676 -0.003960132 0.01536101 0.007129848 0.002442598 0.01118546 0.006599247 -6.15501e-4 0.01535451 0.007104158 0.002466619 0.01539546 0.007105588 0.00245136 -0.00477612 0.002112984 -0.003565073 -0.001711964 0.002111852 -0.005717098 3.64171e-4 0.002113759 -0.005971133 0.002821743 0.002107083 -0.005286514 0.003416895 0.002107203 -0.004927992 0.005997657 0.002113938 -8.19472e-4 0.006042778 0.00210011 -1.17073e-4 -0.005207836 0.009621679 0.002414822 -0.004498243 0.009621739 0.003609299 -0.005636155 0.009621739 0.001093327 -0.003436028 0.009621739 0.004637181 -0.005693852 0.009621739 -6.2576e-4 -0.002288639 0.009621739 0.005316019 -0.001058161 0.009621679 0.005695819 2.29885e-4 0.009621739 0.005803227 0.001926183 0.009621798 0.005503356 0.00331968 0.009621679 0.004774391 0.004397332 0.009621739 0.003823161 0.004984915 0.009371757 0.003463268 0.004097819 0.009371757 0.004472494 0.003010749 0.009371757 0.005270957 0.001483678 0.009371817 0.005887687 -1.51787e-4 0.009371757 0.006054043 -0.001776337 0.009371817 0.005784034 -0.003127038 0.009371757 0.005150437 -0.004301309 0.009371817 0.004217207 -0.005102574 0.009371697 0.003145992 -0.005623102 0.009369909 0.002074539 -0.005922436 0.009374856 7.94654e-4 -0.005960881 0.009369492 -2.51545e-4 -0.005785167 0.009373843 -0.00146389 + + + + + + + + + + -0.7192916 0.6323877 -0.2875855 -0.5624821 0.7630025 -0.3184983 -0.6211978 0.6451994 -0.444782 -0.4825506 0.7481889 -0.4553661 -0.5029802 0.6676756 -0.5488353 -0.3765209 0.7436615 -0.5524488 -0.3823724 0.6831485 -0.6221733 -0.2201734 0.7525977 -0.6205809 -0.2552584 0.7042314 -0.6624963 -0.07857614 0.6298998 -0.7726914 -0.01624512 0.7667836 -0.6417002 0.1194601 0.6406009 -0.7585248 0.1528089 0.7492261 -0.6444454 0.2927826 0.7382209 -0.6077074 0.2876827 0.6681129 -0.6861953 0.4326945 0.6533837 -0.6211805 0.4071934 0.7802028 -0.4748446 0.6159681 0.5848585 -0.5277537 0.5403562 0.7744512 -0.3289992 0.6924559 0.6461467 -0.3209351 0.6275838 0.7503869 -0.2075046 0.7619149 0.6287592 -0.1553952 0.6335949 0.7723659 -0.04481738 0.7625229 0.6455486 0.04273027 0.6318687 0.7639889 0.1306257 0.6981167 0.6939937 0.1760851 -0.9288886 0.01150041 -0.3701809 -0.8517591 -0.01006156 -0.523837 -0.8130376 0.01069819 -0.5821129 -0.7438316 -0.01056438 -0.6682837 -0.6755821 0.01277285 -0.7371742 -0.5633729 -0.01517695 -0.8260635 -0.5236071 0.003961503 -0.8519507 -0.3594421 0.008340477 -0.9331301 -0.3029309 -0.01976358 -0.9528077 -0.1011831 0.01823765 -0.9947007 -0.01686626 -0.01678746 -0.9997169 0.1555534 0.01523554 -0.9877101 0.2385973 -0.01522272 -0.9709994 0.3857007 0.01347923 -0.9225255 0.4565827 -0.009955644 -0.8896254 0.5734168 0.008970201 -0.8192148 0.6108341 -0.00728935 -0.7917251 0.7587839 0.009510397 -0.6512731 0.7817031 -0.00929296 -0.6235815 0.9072338 0.008684396 -0.4205371 0.9245206 -0.01152044 -0.3809581 0.9797504 0.01342779 -0.1997724 0.9899877 -0.01143163 -0.1406903 0.9983758 -0.01113194 0.05587393 0.9965246 0.005763709 0.08309996 0.9695235 0.01428663 0.2445815 -0.6125335 -0.7488107 -0.2531508 -0.6535231 -0.6733973 -0.3456063 -0.520349 -0.726265 -0.4491952 -0.5241357 -0.6592363 -0.5391562 -0.3913815 -0.7445814 -0.5407581 -0.2359353 -0.7143926 -0.65877 -0.2880361 -0.6560687 -0.6975738 -0.03137743 -0.7155513 -0.6978552 -2.19725e-4 -0.6620444 -0.7494647 0.1738246 -0.7451137 -0.6438872 0.2952009 -0.6239258 -0.7235836 0.3704961 -0.7647323 -0.5271788 0.558245 -0.6190519 -0.5523924 0.5407665 -0.7648589 -0.3500896 0.7320034 -0.6192209 -0.284142 0.6438522 -0.7492792 -0.1550322 0.7629266 -0.64534 0.03846526 0.6785015 -0.7306008 0.07653892 -0.511292 0.7150732 0.4767085 -0.4289155 -0.8361243 0.341947 -0.8646617 -0.1237856 0.4868648 -0.2755361 0.9595298 -0.05815821 0.9926294 -0.0136913 0.1204141 0.4189872 -0.8814128 -0.2180852 0.3901733 -0.8978749 -0.2039253 -0.2934406 0.9246096 -0.2428783 -0.3174512 0.9289387 -0.1905192 -0.3397578 0.9242848 -0.1739612 -0.9187019 0.2323586 -0.3193688 -0.3636015 -0.9106521 0.1962314 -0.316165 -0.9409908 0.1207314 -0.4876495 -0.7209883 -0.4923149 -0.5801002 -0.6717625 -0.4606724 -0.2435095 -0.7148086 -0.6555547 -0.2832685 -0.6952517 -0.6605938 -0.00701332 -0.6819339 -0.7313803 0.1250416 -0.730282 -0.6716047 0.2455757 -0.6854565 -0.6854502 0.4300645 -0.7259098 -0.5367491 0.5021944 -0.6938427 -0.5161232 0.6129465 -0.7143243 -0.3376942 0.6496647 -0.694236 -0.3097938 0.7001612 -0.7110245 -0.06495022 0.7264336 -0.6869172 -0.02095365 0.67012 -0.7163966 0.1942039 -0.9001454 -0.003712296 -0.4355741 -0.623574 -0.00391829 -0.7817546 -0.6991506 0.002566039 -0.7149699 -0.3412433 0.006308495 -0.9399539 -0.1170132 -0.007649481 -0.993101 0.1729595 0.006979227 -0.9849043 0.3951031 -0.005439877 -0.9186207 0.6279509 0.003581404 -0.7782449 0.7271829 -0.003314971 -0.6864358 0.8758532 0.004370808 -0.4825578 0.9624609 -0.006086468 -0.2713525 0.9959034 0.004076361 -0.09033155 0.9529229 -0.003890335 0.3031879 0.9620679 -0.007365703 0.2727106 -0.6954325 -0.6716825 -0.255375 -0.5362175 -0.7373965 -0.4107522 -0.5295157 -0.7134599 -0.4588989 -0.3324431 -0.675767 -0.657891 -0.1769856 -0.7492198 -0.6382364 0.0252195 -0.6641756 -0.7471512 0.2762571 -0.7185835 -0.6382161 0.280779 -0.7242572 -0.6297736 0.5909414 -0.6656967 -0.455671 0.5873827 -0.728687 -0.3521321 0.7403258 -0.6715922 -0.02969294 0.7247135 -0.68901 -0.007457911 -0.9390748 -0.007398962 -0.3436337 -0.8001489 0.009281158 -0.5997298 -0.630046 -0.008206188 -0.7765146 -0.2521542 0.008663535 -0.9676483 -0.1093431 -0.004035532 -0.9939959 0.3103072 -2.08522e-4 -0.9506363 0.3893574 0.007432162 -0.9210569 0.7154598 -0.007051706 -0.6986183 0.8581969 0.008079648 -0.5132572 0.9766349 -0.008205354 -0.2147484 0.9999508 0.005317568 -0.00837785 -0.6186254 -0.7220792 -0.3096842 -0.6508511 -0.7011692 -0.2911264 -0.3447642 -0.7054921 -0.619208 -0.4147585 -0.6570422 -0.6295008 -0.05442196 -0.7224102 -0.6893199 0.04309421 -0.65956 -0.7504158 0.2742111 -0.7341905 -0.621106 0.4011042 -0.6801726 -0.6135803 0.5457526 -0.7259558 -0.4185 0.6048995 -0.6933147 -0.3916777 0.6830288 -0.7287945 -0.04827404 0.7144814 -0.6903414 -0.1137776 0.6980865 -0.6824184 0.2167499 -0.8936446 0.004934132 -0.4487485 -0.4786476 -0.004847466 -0.8779938 -0.4875388 -0.006192207 -0.8730794 -0.07132834 0.007916986 -0.9974215 0.252952 -0.008841991 -0.9674385 0.3959924 0.003801643 -0.918246 0.7599104 -0.002341747 -0.6500236 0.7961047 0.002671122 -0.6051531 0.9784335 -0.005060195 -0.2065003 0.9972158 0.0060938 -0.07432144 0.4922603 -0.8630325 0.11338 0.4694282 -0.8792459 0.08101785 0.5180722 -0.855277 0.01014 0.474257 -0.8762764 -0.08497011 0.4776135 -0.8740843 -0.08866804 0.4863683 -0.8515704 -0.1956364 0.3990636 -0.8797214 -0.2585314 0.400973 -0.8773871 -0.2634626 0.3743213 -0.8478733 -0.3754924 0.2640178 -0.8782769 -0.3986534 0.2613183 -0.8666598 -0.4249866 0.1634449 -0.8520251 -0.497332 0.1030632 -0.8824248 -0.4590257 0.009288787 -0.8536731 -0.5207265 -0.05360257 -0.8822571 -0.4677066 -0.1028569 -0.8593162 -0.5009952 -0.2007554 -0.8578872 -0.4729977 -0.2270256 -0.8835774 -0.4095734 -0.288835 -0.8593906 -0.4219267 -0.3749074 -0.8574237 -0.3525181 -0.3631325 -0.8917996 -0.269867 -0.4727436 -0.8467231 -0.2440769 0.9743698 -0.009475111 0.2247531 0.976645 -0.01911371 0.2140075 0.9997171 -0.01573663 0.01784193 0.9994082 -0.006222784 0.03383201 0.9979386 0.003417789 -0.06408601 0.978317 -0.03064078 -0.2048342 0.9830144 -0.01983904 -0.1824534 0.9666081 0.005527973 -0.2561996 0.927715 -0.01110035 -0.3731243 0.9227043 -0.01981514 -0.3849989 0.8794354 0.003949046 -0.4760017 0.8355616 -0.0221309 -0.548951 0.8145356 -0.00349909 -0.5801032 0.7382155 -8.22542e-4 -0.6745646 0.7056838 -0.02765113 -0.7079873 0.6138744 0.01117402 -0.7893247 0.5237862 -0.01639682 -0.851692 0.5158487 -0.02337306 -0.8563609 0.4085293 0.004406034 -0.9127346 0.3108708 -0.03655529 -0.9497489 0.2652949 -0.002123951 -0.964165 0.1376403 0.01739889 -0.9903295 -0.0148971 -0.05152672 -0.9985606 0.01899415 -0.02529448 -0.9994997 -0.06011158 4.38675e-4 -0.9981916 -0.2073528 -0.01448261 -0.9781591 -0.2011572 -0.009580314 -0.9795122 -0.360289 -0.004880666 -0.932828 -0.3906474 -0.02233779 -0.9202694 -0.4883362 0.006896138 -0.8726283 -0.5648213 -0.01826691 -0.8250111 -0.555733 -0.02402281 -0.8310137 -0.6738385 0.00456947 -0.7388646 -0.7282111 -0.03115433 -0.6846445 -0.7646033 -0.001901149 -0.6444984 -0.8445582 0.009768068 -0.5353748 -0.8873882 -0.03883397 -0.4593847 -0.9177889 8.97582e-4 -0.3970677 -0.6727302 -0.6877919 0.2727206 0.6265357 -0.6657033 0.4053297 0.626744 -0.6998951 0.3425478 0.631641 -0.6619161 0.4036048 0.5532299 -0.7068557 0.4407852 0.496381 -0.7210381 0.4834358 0.456656 -0.7124766 0.5327687 0.4161487 -0.6706796 0.6140106 0.4359182 -0.6963874 0.5701053 0.4250593 -0.6883645 0.5877746 0.3660215 -0.7056192 0.6067372 0.3074396 -0.7065551 0.637386 0.2467307 -0.6930456 0.6773565 0.2588893 -0.685742 0.6802458 0.172096 -0.7174461 0.6750215 0.1044932 -0.7170817 0.6891118 0.04023408 -0.6933041 0.7195212 0.02811795 -0.6853894 0.7276337 -0.04114425 -0.7066383 0.7063778 0.005562782 -0.6951135 0.7188785 -0.1094866 -0.7031316 0.70258 -0.06227332 -0.7081094 0.7033514 -0.1607769 -0.6883864 0.7073012 -0.1785041 -0.6970514 0.6944463 -0.1430035 -0.6714364 0.7271335 -0.2356841 -0.7177037 0.6552515 -0.2059249 -0.7100775 0.6733387 -0.2736184 -0.7197065 0.6380875 -0.3377812 -0.7060572 0.6224043 -0.4099885 -0.6689266 0.6200376 -0.4136916 -0.6772331 0.6084526 -0.4505631 -0.7121743 0.5383313 -0.495939 -0.7204693 0.4847356 -0.5540677 -0.7047976 0.443023 -0.5778906 -0.699342 0.4206701 -0.6342582 -0.6575968 0.4065502 -0.6265763 -0.7076128 0.3266289 0.5732645 -0.6887632 0.4438166 0.6476387 -0.6744244 0.3545644 0.6400837 -0.7050223 0.3053464 0.5979796 -0.708525 0.3747169 0.3071221 -0.9259008 0.2199636 0.3531535 -0.9198288 0.1708735 0.3373958 -0.9183135 0.2070378 0.3541004 -0.9178696 0.1792441 -0.9351827 0.0460335 -0.3511615 -0.9304671 -0.08994114 -0.3551642 -0.8861409 -0.04494678 -0.4612311 -0.8809555 -0.02361112 -0.4726099 -0.8796663 -0.01474702 -0.4753627 -0.8402751 0.007919013 -0.5421027 -0.8132554 -0.07601708 -0.5769203 -0.7886388 0.00796622 -0.6148052 -0.7345129 -0.07860648 -0.6740266 -0.7347379 -0.07778519 -0.6738766 -0.6783657 0.05513352 -0.732653 -0.5968993 -0.1296955 -0.7917641 -0.6228556 -0.02747178 -0.7818544 -0.5332113 0.06907314 -0.8431577 -0.4302743 -0.1124454 -0.8956674 -0.4388943 -0.07895869 -0.8950628 -0.3714534 0.04118502 -0.9275378 -0.2451539 -0.1262235 -0.9612323 -0.272151 -0.02451604 -0.9619423 -0.1744689 0.04542338 -0.9836145 -0.05116784 -0.1249805 -0.990839 -0.07433676 -0.03115028 -0.9967466 0.03186976 0.05295318 -0.9980884 0.1445088 -0.1430335 -0.9791111 0.1008807 0.006655156 -0.9948763 0.2043135 0.03165799 -0.9783935 0.2858399 0.004055738 -0.9582688 0.3347344 -0.1364108 -0.9323868 0.3670192 -0.02163344 -0.9299619 0.4244327 0.05156809 -0.9039899 0.513692 -0.1039808 -0.8516505 0.5208864 -0.07252156 -0.8505399 0.6050757 0.04304742 -0.7950034 0.6615357 -0.02957874 -0.7493301 0.6636374 -0.01721847 -0.7478563 0.6773744 -0.07905846 -0.731378 0.752472 0.009106636 -0.6585613 0.7580081 0.02929615 -0.6515868 0.8461871 -0.04581385 -0.5309131 0.8381344 -0.07439255 -0.5403671 0.8854767 0.04340189 -0.4626526 0.8493885 -0.01814037 -0.5274562 0.9225281 -0.05357676 -0.3821931 0.9245707 -0.1248076 -0.3599892 0.9460133 -0.01017004 -0.3239682 0.9700208 0.03927141 -0.2398277 0.9769712 -0.1257887 -0.1723503 0.9881907 -0.03353995 -0.1495137 0.9975492 0.04457324 -0.05393344 0.9922793 -0.1220666 0.0219444 0.9961905 -0.08098065 0.03235495 0.9949313 0.03194278 0.09534972 0.9762435 -0.08043169 0.2011953 0.9833546 -0.008779525 0.1814845 0.9617189 0.01338744 0.273711 0.9439743 -0.07457494 0.3214831 0.9521471 -3.52547e-4 0.3056399 0.9466456 -0.002644002 0.3222661 0.9933589 -0.008956372 0.114709 0.9902556 -0.001126587 0.1392577 0.9781444 0.002279222 0.2079145 0.9905144 -0.001173317 0.1374041 0.9988777 -3.07545e-4 0.04736423 0.9978837 0.001407086 0.06501084 0.9987291 -0.002164721 -0.05035382 0.988452 -8.82955e-4 -0.1515324 0.9931175 0.001786351 -0.1171084 0.9687538 -8.56919e-4 -0.2480229 0.9645838 4.10513e-4 -0.2637764 0.9406706 -0.001108825 -0.3393196 0.9197289 -4.65272e-4 -0.3925539 0.9274412 5.73799e-4 -0.3739685 0.8806032 -5.59296e-4 -0.4738542 0.8510599 -8.7182e-4 -0.5250679 0.8655518 9.94305e-4 -0.5008185 0.7965117 -8.67648e-4 -0.6046225 0.7864353 4.11239e-4 -0.6176726 0.7334561 -0.001171588 -0.6797358 0.7094216 8.22433e-4 -0.7047839 0.6695818 -0.001353681 -0.7427371 0.6236721 -6.70485e-4 -0.7816858 0.580518 -7.14107e-4 -0.8142473 0.6097522 4.69393e-4 -0.7925919 0.504749 6.87093e-4 -0.863266 0.5064532 8.81277e-4 -0.8622671 0.4569305 -0.001875996 -0.8895006 0.4075002 -0.001596808 -0.9132037 0.3413219 0.002526581 -0.9399431 0.3224977 5.79578e-4 -0.9465701 0.2679133 -0.002009928 -0.963441 0.1825852 -3.83834e-4 -0.98319 0.1196073 -2.99292e-4 -0.9928212 0.148678 0.002095341 -0.9888836 -0.005145907 -0.0091784 -0.9999446 0.03667694 -0.001829147 -0.9993255 -0.03418302 0.001184463 -0.9994149 -0.06626456 1.64134e-4 -0.9978021 -0.04114478 0.001660406 -0.9991519 -0.1150757 -0.001237392 -0.9933559 -0.1527481 -0.001106858 -0.9882645 -0.2001738 5.99718e-4 -0.9797602 -0.2397137 -3.41946e-4 -0.9708437 -0.2105491 0.001313209 -0.9775825 -0.3436434 -0.005403697 -0.9390847 -0.2734814 -0.001159369 -0.9618767 -0.3294462 -6.44253e-4 -0.9441742 -0.3773245 0.001278102 -0.9260803 -0.3870124 0.002289175 -0.9220717 -0.4545704 -0.002065181 -0.8907085 -0.5425513 -3.31705e-4 -0.8400226 -0.5625891 0.002067804 -0.8267341 -0.6180151 -0.001652598 -0.7861647 -0.6892836 -2.58731e-4 -0.7244917 -0.7282364 2.29301e-4 -0.685326 -0.7141405 0.002028584 -0.6999995 -0.7885196 -0.002252578 -0.6150055 -0.8443678 6.15523e-4 -0.5357639 -0.8378412 0.001885831 -0.5459108 -0.8937192 -0.002377033 -0.4486207 -0.9323257 0.001160323 -0.3616179 -0.9295397 0.001992881 -0.368717 0.9638285 -5.14078e-4 0.266523 0.9647477 -0.00101155 0.2631747 0.9953486 8.42678e-4 0.09633618 0.9981539 -0.002977132 0.06066387 0.9995285 0.002615153 -0.03059178 0.9878312 -0.002227902 -0.1555145 0.9842159 2.87688e-4 -0.1769722 0.9513675 2.8782e-4 -0.3080584 0.9491575 -3.71802e-4 -0.3148016 0.909906 3.59565e-4 -0.4148144 0.9053887 -5.88752e-4 -0.4245836 0.8419206 6.78824e-4 -0.5396013 0.8371809 -2.87805e-4 -0.546926 0.7508381 -2.87613e-4 -0.6604864 0.7475413 2.87657e-4 -0.6642154 0.6393452 2.87541e-4 -0.7689198 0.6319893 -9.4555e-4 -0.7749765 0.4971907 8.42475e-4 -0.8676409 0.4869542 -4.12861e-4 -0.8734275 0.377614 4.12912e-4 -0.925963 0.3748967 9.98713e-5 -0.9270666 0.2313174 -0.001255989 -0.9728775 0.2193543 2.98008e-4 -0.9756453 0.09571665 0.001409828 -0.9954077 0.05254411 -0.002317786 -0.998616 -0.04634976 0.001972317 -0.9989234 -0.09613633 -0.001875817 -0.9953665 -0.19314 0.001431703 -0.9811702 -0.2354231 -0.00127989 -0.9718922 -0.3013336 0.001356422 -0.9535178 -0.3628196 -0.00241357 -0.9318563 -0.4369258 0.002706468 -0.8994935 -0.5620027 0.00146234 -0.8271341 -0.5262961 -0.002638876 -0.8502974 -0.6887637 0.00125879 -0.7249849 -0.6728071 -0.001259446 -0.7398169 -0.8011505 0.001259446 -0.5984616 -0.7839328 -0.001461744 -0.620844 -0.8726738 9.68515e-4 -0.4883028 -0.8610816 -8.23878e-4 -0.5084664 -0.919556 -0.001592576 -0.392956 -0.9301089 9.48593e-4 -0.3672828 0.9149483 -0.00507909 0.4035394 0.8848637 0.001771032 0.4658467 0.8394435 0.003706693 0.5434343 0.8001912 6.62298e-4 0.5997449 0.7925002 0.001361966 0.6098702 0.893321 6.18652e-4 0.4494187 0.8798934 0.003492951 0.4751582 0.8342302 0.003742873 0.5514037 0.8015506 7.73642e-4 0.5979265 0.808094 9.05632e-4 0.5890529 0.783282 0.001948952 0.6216637 0.8157274 0.004678189 0.5784176 0.6974182 0.002565085 0.7166598 0.7165601 0.00191158 0.6975228 0.7497619 0.004423916 0.661693 0.629624 0.002326488 0.7768965 0.6518787 0.00165385 0.7583215 0.6397941 0.001118779 0.7685456 0.603463 0.001279294 0.7973901 0.6426987 0.002994418 0.7661132 0.5647085 0.003469884 0.8252832 0.4944025 7.33629e-4 0.8692328 0.5132594 6.71295e-4 0.8582332 0.5187215 0.001012623 0.8549428 0.5416882 0.001450836 0.8405783 0.4345844 0.004147648 0.9006217 0.3616335 -1.05267e-4 0.9323203 0.4370071 0.001231014 0.8994572 0.3425716 0.004344463 0.9394817 0.2683011 8.17832e-4 0.9633347 0.2470594 0.001282989 0.9689995 0.2111188 -7.31386e-4 0.9774601 0.1474488 0.002881169 0.9890656 0.04433339 -7.46295e-4 0.9990166 0.07310032 0.001413345 0.9973237 -0.003796756 0.001893758 0.9999911 -0.1020953 0.003577291 0.9947682 -0.0375837 -0.001338243 0.9992926 -0.1085411 0.001410007 0.994091 -0.1762409 0.001464486 0.984346 -0.1421548 -0.001154959 0.9898438 -0.1978118 0.001012682 0.9802395 -0.2437308 0.001049518 0.9698424 -0.2438313 0.001052916 0.9698171 -0.2921917 0.001072824 0.9563592 -0.2893508 9.59367e-4 0.9572227 -0.3478337 9.98528e-4 0.9375558 -0.386138 0.001425445 0.9224401 -0.3372086 0.001418888 0.9414289 -0.3957374 0.001821041 0.9183619 -0.4416394 8.67185e-4 0.8971922 -0.4776054 0.001617252 0.878573 -0.4672098 0.002286851 0.8841436 -0.5044682 0.001471698 0.863429 -0.562231 0.002665996 0.8269759 -0.5879619 0.002120316 0.8088859 -0.5601321 0.002812385 0.8283987 -0.6418433 0.003313124 0.7668288 -0.6679005 0.001320242 0.7442495 -0.7149511 0.004366695 0.6991609 -0.7810342 0.001510143 0.6244866 -0.793278 -5.52031e-4 0.6088593 -0.8382128 0.003819942 0.54533 -0.9027174 -8.48832e-4 0.4302334 -0.8901597 0.001831173 0.4556449 -0.9246938 0.002023994 0.3807066 -0.9211022 0.003584384 -0.3893047 -0.7374384 -0.003338098 -0.6754062 -0.7594888 -5.93716e-4 -0.6505201 -0.5863475 0.002758383 -0.810055 -0.4342728 -0.00389862 -0.9007731 -0.33723 0.002809047 -0.9414182 -0.05035191 -0.002258419 -0.9987291 -0.04498416 -0.001735329 -0.9989862 0.2602492 0.00337094 -0.9655357 0.3724007 -0.005116045 -0.928058 0.5757086 0.004892766 -0.8176404 0.6978202 -0.004386484 -0.7162596 0.8378289 0.003635525 -0.5459208 0.8897351 -0.002861976 -0.4564686 0.973128 0.003149807 -0.2302437 0.9925053 -0.004004836 -0.1221367 0.9939779 0.004885733 0.1094732 0.9597937 -0.006248116 0.2806369 0.007054328 0.9999282 -0.009684979 -0.006637692 0.9999621 -0.005651116 -0.006943583 0.9999601 -0.005628049 -0.01258957 0.9999027 -0.00602293 0.01155894 0.999929 -0.00291872 0.005325019 0.9999092 0.0123887 0.006775557 0.9999602 -0.005826115 8.91473e-4 0.9999882 0.004780471 0.004010558 0.9999868 -0.003241777 -0.002224087 0.9999951 0.002218723 0.01182556 0.9998763 0.01036947 -0.005090951 0.999987 4.19948e-4 -0.004566133 0.9999889 0.001203715 -9.52348e-4 0.9999909 0.004165351 -0.001986801 0.9999973 0.00131607 -0.001950025 0.9999974 -0.001220226 -0.001886606 0.9999982 4.13864e-4 -0.001895606 0.9999979 9.08972e-4 8.22994e-5 0.9999973 0.002324819 -0.001733958 0.9999968 0.001852989 -0.00208795 0.9999958 0.002038776 -0.001526772 0.9999969 -0.002045094 -0.005839228 0.9999822 -0.001204073 -2.01262e-4 0.9999971 0.002407908 -0.001321613 0.999995 -0.002887308 -4.04934e-4 0.9999949 0.003172338 -7.86632e-4 0.9999969 0.002409875 -0.002277791 0.9999969 -0.001081585 6.18435e-4 0.9999614 -0.008780419 -8.11108e-4 0.9999968 0.002408146 2.31624e-4 0.9999978 0.002105534 0.003426492 0.9999931 0.001473069 0 1 0 0 1 3.00349e-6 -0.003832995 0.9999927 -3.04016e-4 -0.004193723 0.9999874 -0.002775549 -0.004153549 0.9999913 -4.27862e-4 -0.01359987 0.9998924 0.005506932 0.04236119 0.9972477 -0.06084889 -0.006804585 0.999935 -0.009155809 -0.00920701 0.9999573 7.67444e-4 -0.01242667 0.9999052 0.005941331 -0.006224513 0.999919 -0.01110881 0 1 -9.81577e-7 -0.01532459 0.9998648 0.00597316 8.67877e-4 0.9997088 -0.02411502 -0.011491 0.9999322 -0.001951932 -0.003824353 0.9999242 -0.01171296 -8.69439e-5 0.9999995 -0.001094043 0.01410084 0.9996609 -0.02189403 -0.02593153 0.9995749 0.01332831 -0.006218612 0.999948 -0.008078038 0 1 1.00301e-6 -0.01406556 0.9998613 0.008922994 -0.01296174 0.9999141 -0.001985371 -0.002439796 0.999997 1.83219e-4 -1.54834e-4 0.9999954 0.003077387 0.003601551 0.9995126 -0.03101176 -0.01915526 0.9993048 0.03198534 0.001130759 0.9999876 0.00486803 0.05000275 0.996165 -0.07179856 -0.03913807 0.9980202 0.04923337 3.58436e-4 0.9999949 0.003200829 -0.01415133 0.9998872 -0.005045652 -0.009182929 0.9998895 0.01169312 0.01141434 0.9999343 -0.001114726 -0.003025352 0.9999945 0.001394629 -0.009417772 0.9999035 0.01021552 -0.008524954 0.999962 0.001837134 -0.001082539 0.9999915 0.00396806 0.001351177 0.9999991 -7.39137e-5 0.002850949 0.999996 4.77677e-5 0.006765484 0.9999748 0.002175509 0.001036286 0.9999902 0.004316151 -2.47426e-4 1 1.38577e-4 -0.004609286 0.9999861 -0.002572894 -0.004643738 0.9999852 -0.002856314 -3.99013e-4 0.999986 0.005292236 -0.005391955 0.9999827 0.002385497 0.005982518 0.9999628 0.006227314 -0.003504753 0.9999741 -0.006279528 -0.003240823 0.9999906 -0.002910733 0.005340933 0.9999657 0.006325602 -0.004910647 0.9999793 0.004178285 0.009478926 0.9998272 0.01599144 0.0014472 0.9999655 0.008190155 -0.003881156 0.9999925 5.35119e-5 -0.0449472 0.9989138 -0.01229089 -0.002717852 0.9999958 -0.001071155 0.0391581 0.9991442 0.01332449 -0.00140202 0.999997 -0.002056479 0.006061315 0.9999229 0.01083666 -0.03027528 0.9994219 0.01546621 0.04519051 0.998972 -0.00358802 0.01220923 0.9998899 0.008451104 -0.01506263 0.9996612 0.02123075 0.00162816 0.9999288 0.01182413 -0.01890522 0.9995062 0.02510315 0.01198029 0.9998707 0.01073294 -0.01669991 0.9998567 0.002806842 0.004570841 0.9999558 0.008221387 -0.003593385 0.9999775 0.005652308 0.005831599 0.9999829 -5.36738e-4 0.00421673 0.9999672 0.006922066 -0.0597015 0.9982163 -2.63693e-4 -0.002247095 0.9999973 -7.58976e-4 -0.002652406 0.9999956 0.001349329 0 1 1.35713e-6 -0.0021227 0.9999977 -5.53163e-5 -0.002005994 0.9999978 -6.39838e-4 -0.001580834 0.9999926 0.003523588 -1.82278e-4 0.9999915 -0.004125833 0 1 2.23525e-6 -2.4774e-4 0.9999927 0.00383675 -8.50811e-4 0.9998101 0.01947325 0.002431929 0.9999627 -0.008296012 -0.002753138 0.9999952 -0.001421868 -0.001805722 0.9999942 -0.002905428 -0.004498839 0.9999464 0.009335517 -0.00282514 0.999929 0.01157504 -0.00192964 0.9999952 -0.002474904 1.30726e-4 0.9999965 0.002665042 4.52867e-5 0.999994 0.003456115 -0.01555162 0.9998791 -1.19992e-4 0 1 8.24029e-7 0 1 1.11312e-6 -0.02152019 0.9997608 -0.003901302 0.001487314 0.9999679 0.007880926 0 1 -2.2745e-6 0 1 2.48612e-6 0 1 8.87214e-7 0 1 -6.05935e-7 0.001155018 0.9999961 0.002576708 -0.002121448 0.9999952 0.00226897 0 1 -6.13574e-7 0.001508891 0.9999973 0.001761615 0.001079678 0.9999974 0.001980304 0 1 2.61177e-7 7.30636e-4 0.9999976 0.002105236 0 1 -2.07027e-6 -0.001461565 0.9999945 -0.002977311 -0.00135225 0.9999957 -0.002596318 5.47992e-4 0.9999777 0.006665766 0.001672625 0.9999972 -0.001680016 7.27867e-5 0.9999964 -0.002670526 0.0110197 0.9999166 -0.006755828 0.01017898 0.9999257 -0.006704926 0.03741747 0.999195 0.01447468 0.01133793 0.9999213 -0.005377292 0.006912648 0.999936 -0.008960068 -0.0353167 0.9989097 -0.03053218 8.54157e-4 0.9997131 -0.02393722 0.003586828 0.9997981 -0.01977455 0.002635657 0.9999957 -0.001340389 0.01500815 0.9998545 0.008116483 0.005674302 0.9999566 -0.007392525 0.003987133 0.9999054 -0.01317179 0.004909336 0.9998643 0.01573228 9.20214e-4 0.9999977 0.00198996 0.005740642 0.9999731 -0.004579603 0.01793611 0.9997981 0.009066104 0.001600742 0.9999962 -0.002245604 0.002020478 0.9999203 -0.0124641 0.02076476 0.9997382 0.009618282 0.004032492 0.9999611 -0.00785607 0.001856863 0.9999963 -0.002063274 0.009722292 0.9999457 -0.003786444 0.006700992 0.9999775 3.29882e-4 0.001803338 0.9999213 -0.01241445 0.03704857 0.9970392 0.06738293 0.001230001 0.9999568 -0.009227216 0.002058029 0.9999963 -0.001810073 0.002427995 0.9999964 -0.001133203 0.002210497 0.9999963 -0.001613497 7.19168e-4 0.9999955 -0.002926647 0.002246856 0.9999948 -0.002321958 0.003738105 0.9999831 -0.004464745 0.004508078 0.9999881 -0.001857519 -0.0149554 0.9998881 -3.09954e-4 0.003337562 0.9999908 -0.002694308 0.001520514 0.9999933 -0.003350734 0.003534078 0.9999918 -0.002008974 -0.003448963 0.999947 -0.009703993 0.01661884 0.9998139 -0.009807407 -0.004668653 0.9999467 -0.0092175 -0.01543289 0.9998784 -0.00225985 2.23098e-4 0.9999789 -0.00649929 3.21628e-4 0.9998843 0.01520854 0.001369893 0.9999991 -2.46027e-4 -0.003233253 0.9999685 0.007258176 0.001909911 0.9999961 -0.002027511 0.002753794 0.9999962 -3.91011e-4 0.002451479 0.9999926 -0.003014087 0.002271234 0.9999964 -0.00147283 -2.17522e-4 0.9999948 -0.003245055 0.001596033 0.9999981 -0.001170456 0.002354979 0.9999972 -4.28679e-4 0.002339005 0.9999971 -4.61606e-4 0.001893758 0.9999975 -0.001212835 -0.005500674 0.9999827 -0.002067148 0.002656102 0.999996 9.77161e-4 0.002146422 0.9999977 -2.11283e-4 -0.005069792 0.9999859 -0.001618802 0.002416849 0.9999969 7.17378e-4 0.005955219 0.9999493 -0.008131384 0.007790267 0.9999304 -0.008874416 -0.009214222 0.9999308 -0.00732547 -1.63804e-4 -1 3.15833e-4 2.18924e-4 -0.9999999 4.12724e-4 -3.29429e-4 -1 2.38979e-5 -9.96209e-5 -1 -4.11214e-4 -6.5875e-4 -0.9999998 -3.24869e-4 5.60403e-4 -1 -2.157e-5 -0.002244055 -0.9999414 0.01059824 0.002419173 -0.9999645 0.00808537 0.003346443 -0.9999071 0.01321089 4.0184e-4 -0.9998933 0.01460915 0.008412122 -0.9999256 0.008842468 -0.002492964 -0.9999898 0.003779113 -7.76135e-4 -0.9999996 4.85033e-4 0.01118046 -0.9995787 0.02678614 -4.53122e-5 -1 -3.30738e-5 -6.72011e-4 -0.999993 0.003685295 -0.002279818 -0.9995323 0.03049755 0.003187 -0.9999942 0.001256346 -8.23317e-5 -1 -1.52817e-4 0.005356729 -0.9999857 3.81731e-4 0.005104124 -0.9999032 0.01294845 0.004200994 -0.9999752 -0.005655109 -4.83099e-5 -1 6.80192e-5 0.005623757 -0.9999518 0.008045732 3.06511e-4 -0.9999204 0.01261454 0.00848031 -0.9999561 0.004002988 0.01198691 -0.9998974 -0.007854759 -0.001773595 -0.9999729 0.007146716 -4.75787e-5 -1 -7.43503e-5 9.46049e-4 -0.9999709 -0.007574677 0.01339381 -0.9999074 -0.002456188 0.07387536 -0.9963372 0.04306614 0.005729675 -0.9999772 0.003591001 0.05571013 -0.9982913 0.01763826 0.001550734 -0.9999927 0.003530144 0.07315599 -0.9969233 0.02814346 0.04808032 -0.9979764 0.04161077 0.001624107 -0.9999924 0.003566324 0.02779394 -0.9996006 0.005120038 0.003305971 -0.9999322 0.01117175 0.0120204 -0.9999021 0.007162749 -0.010957 -0.9999182 0.006602764 -6.07333e-4 -0.9999998 2.57192e-4 0.00480473 -0.9999802 0.004100441 -0.005167543 -0.999984 0.002298593 -0.005157411 -0.9999831 0.002712726 -0.009179651 -0.9999257 -0.00801891 6.70945e-4 -0.9999998 3.87527e-4 -0.001766502 -0.9998489 0.0172984 -0.00813508 -0.999962 -0.003177523 -0.01044595 -0.9998894 0.01059156 6.21372e-5 -1 7.7042e-5 -3.58324e-4 -1 -2.6846e-4 0.008195936 -0.999966 -8.70037e-4 0.002709448 -0.9999943 0.002049505 8.66383e-5 -1 -8.99355e-5 -0.01711851 -0.9998522 0.001654803 -5.21965e-5 -0.9999997 -7.7803e-4 -0.0293973 -0.9993314 0.02174133 -0.01085186 -0.9998838 0.01070255 6.88541e-4 -0.9999996 6.70162e-4 -0.005383849 -0.9999396 0.00958687 -1.14173e-4 -1 -2.98266e-5 0.001441478 -0.999996 -0.002483487 -0.001781642 -0.9997455 0.022493 4.08943e-5 -1 -7.93971e-5 0.003825843 -0.9999927 -1.78678e-4 8.08353e-4 -0.9999742 -0.007137298 -0.002612829 -0.9999601 0.008550405 0.007520794 -0.99997 -0.001868903 -2.70014e-5 -1 1.04231e-4 0.009416997 -0.9998612 0.01374095 0.008526265 -0.9998306 -0.01631671 -8.8387e-4 -0.9999812 0.006067335 0.01302409 -0.999871 -0.009397983 0.01450455 -0.9997622 -0.01628625 0.01561266 -0.9997532 -0.01580512 -2.45488e-5 -1 9.32828e-5 -0.003793478 -0.9999797 0.005128264 0.01965671 -0.999214 -0.03442674 -0.00308144 -0.9999933 -0.002036929 -0.00225383 -0.9999822 -0.005528211 -0.003192722 -0.9999915 -0.002612411 -0.003206789 -0.9999864 -0.004103958 -0.0115717 -0.9999327 9.60027e-4 0.002814948 -0.9999935 0.002249777 -0.008066654 -0.9999449 -0.006714344 0.006756067 -0.9999521 0.007086455 -0.0172311 -0.9998453 -0.00354439 -6.92211e-4 -0.9999781 -0.006600379 0.005337834 -0.9999855 7.53299e-4 -0.01929003 -0.9997878 -0.007237732 -0.01905208 -0.9997918 -0.007313668 -0.01899981 -0.9996976 -0.01561152 -0.007965624 -0.9999683 -1.93387e-4 -0.02046698 -0.9986191 -0.04838502 -9.73744e-4 -0.9993881 -0.03496593 -0.01453465 -0.9970656 -0.07516032 -0.007544994 -0.9999527 -0.00614649 4.42996e-4 -1 -1.72476e-4 -9.21129e-5 -0.9992999 -0.03741401 0.009193897 -0.9995976 -0.02683794 -0.008154928 -0.9999654 0.001665234 -0.005398392 -0.9999836 -0.001926243 -0.01426762 -0.9998977 -0.001079916 0.002251029 -0.999997 -0.001053929 -0.01159793 -0.9997152 -0.02086323 8.8559e-5 -0.9999792 -0.00645399 0.005542457 -0.9999718 -0.005084395 0.008073627 -0.9999586 -0.004221856 6.61704e-5 -1 1.92009e-4 -0.002127349 -0.9999887 -0.004268765 -0.006877541 -0.99997 0.003580033 -0.003471553 -0.9999917 -0.002157747 5.17555e-7 -1 2.27743e-5 -0.001472115 -0.9999939 0.003177881 -4.00778e-4 -1 -7.78885e-5 0.003227412 -0.9999949 1.28156e-4 -0.003901302 -0.9999924 -1.21912e-4 -8.66086e-4 -0.9999996 -2.47211e-4 6.92033e-4 -0.9999868 -0.005103528 6.24024e-4 -0.9999875 -0.004965186 2.32028e-5 -1 1.62173e-4 6.19036e-5 -1 3.19614e-4 2.92659e-4 -1 9.15262e-5 1.76924e-4 -1 1.6446e-4 2.53174e-5 -1 -8.50495e-5 0.001015007 -0.9999995 -8.99899e-5 -4.57517e-5 -1 8.72364e-5 0.8746613 0.005120933 0.4847075 0.7465239 -0.005757749 0.6653338 0.6674607 0.003137111 0.7446385 0.3980587 -1.5939e-4 0.9173601 0.3615533 -0.003608345 0.9323446 0.1438385 0.003053188 0.9895966 0.004018545 -0.003610014 0.9999855 -0.1630061 0.002803385 0.9866211 -0.2889015 -0.002375185 0.9573559 -0.3989902 0.002180993 0.9169527 -0.5651996 -0.003160834 0.8249481 -0.6682081 0.004940986 0.7439581 -0.8045632 -0.00435847 0.5938512 -0.9119266 0.003619134 0.4103375 -0.9362791 -9.68442e-4 0.3512558 -0.9982308 -2.21776e-4 0.05945736 -0.99979 0.003318309 0.02022713 -0.9541666 -0.004831016 -0.2992373 0.9990382 0.004580199 0.04361057 0.9934848 7.95102e-4 0.1139621 0.9926242 -8.39805e-5 0.1212318 0.9749856 0.003360271 0.222243 0.9573232 0.005980253 0.2889576 0.9424257 -0.001470386 0.3344128 -0.4628758 0.003670573 -0.8864156 -0.3826175 -0.001041352 -0.9239064 -0.3835471 -0.001176059 -0.9235206 -0.2912648 0.004595577 -0.9566315 -0.1941292 0.002948939 -0.9809715 -0.1584454 -3.7423e-4 -0.9873677 -0.0957148 0.002095043 -0.9954067 -0.06288427 9.02086e-4 -0.9980205 0.003751754 0.004691362 -0.9999821 0.1295928 0.002350747 -0.9915645 0.1062136 0.001851618 -0.9943416 0.0913732 9.76395e-4 -0.9958163 0.100481 0.00100553 -0.9949386 0.1532137 0.003246724 -0.9881878 0.2375524 0.003642082 -0.9713679 0.1944238 0.001812219 -0.980916 0.2538506 0.002037286 -0.9672413 0.2231986 0.003103494 -0.9747681 0.2943853 0.003395259 -0.9556809 0.3581054 0.001110553 -0.9336806 0.3457555 0.001084268 -0.9383241 0.3456905 0.001086711 -0.9383481 0.3406199 0.0029971 -0.9401964 0.3879809 0.001168489 -0.9216668 0.4373411 0.003319859 -0.8992897 0.5107527 4.37555e-4 -0.8597276 0.475198 4.98219e-4 -0.8798787 0.4777075 3.93543e-4 -0.878519 0.5261457 4.90839e-4 -0.8503944 0.5245375 5.59812e-4 -0.8513872 0.5437952 0.001346468 -0.8392169 0.5623059 5.22865e-4 -0.8269292 0.6132574 0.003234922 -0.7898765 0.6690003 6.05198e-4 -0.7432619 0.6831045 0.001416504 -0.7303193 0.7522507 -0.001851975 -0.6588744 0.6551172 0.01290988 -0.7554169 0.8139492 -0.001758038 -0.5809335 0.8049088 3.54904e-4 -0.5933985 0.867645 0.002173423 -0.4971796 0.8698491 0.001909434 -0.4933142 0.9074103 0.001532852 -0.4202432 0.90748 0.001522779 -0.4200928 0.9315701 0.001466631 -0.3635588 0.9481404 -4.02052e-4 -0.3178518 0.9396516 0.001551389 -0.3421294 0.9665534 0.001461923 -0.2564615 0.9627404 0.002324879 -0.2704177 0.9732888 0.001375913 -0.22958 0.9855639 0.002287745 -0.1692885 0.9855147 0.002305448 -0.169575 0.9912753 0.001436173 -0.1318005 0.9975107 0.002353549 -0.07047742 0.9974923 0.002368867 -0.07073605 0.9994511 0.001513719 -0.03309923 0.9999797 0.003820419 0.005114555 0.9995995 0.002446889 0.02819436 0.9969722 0.002156913 0.07773041 0.9974653 0.00963664 0.07050102 0.9902424 0.003050923 0.1393226 0.9730613 2.82995e-4 0.2305467 0.9471392 0.004658043 0.3207894 -0.5360497 0.003830611 0.8441778 -0.6014578 -3.79255e-4 0.7989045 -0.6055126 2.03414e-4 0.7958357 -0.6862903 0.004333198 0.7273149 -0.7488962 0.001094043 0.6626865 -0.7521782 0.001570641 0.658958 -0.8073049 0.003416657 0.5901247 -0.8397936 0.001454353 0.5429039 -0.8372389 0.001090943 0.5468364 -0.8708295 0.003642797 0.4915717 -0.9169591 0.003866672 0.3989627 -0.8915653 0.001397073 0.4528901 -0.9161118 0.001625895 0.4009197 -0.9227723 0.001230657 0.3853438 -0.9112122 0.001128792 0.411936 -0.9385911 0.002010583 0.3450258 -0.9289359 0.00191003 0.3702357 -0.9795615 0.002059698 0.2011348 -0.9528925 0.003849089 0.3032838 -0.9780712 0.001923143 0.208262 -0.9730803 0.001688897 0.2304602 -0.9762225 0.001430928 0.2167662 -0.9973875 0.004919111 0.07206946 -0.9987907 8.8112e-4 0.04915773 -0.9927428 0.002174794 0.1202371 -0.9953798 9.73443e-6 0.09601736 -0.9949868 0.003794133 -0.09993374 -0.9993876 0.003495275 0.03481692 -0.9991168 0.001521766 -0.04199391 -0.9969459 7.73934e-4 -0.07809197 -0.9887139 0.00199145 -0.1498029 -0.9933381 1.21672e-4 -0.115237 -0.9862497 1.54224e-4 -0.165262 -0.9900808 -8.09186e-4 -0.1404966 -0.9920922 -7.86861e-4 -0.1255091 -0.936084 0.006975352 -0.3517075 -0.9472668 0.00455439 -0.320414 -0.9538604 0.001439571 -0.3002473 -0.9013845 0.00158447 -0.4330167 -0.8526305 0.001192033 -0.5225132 -0.8952075 0.002663552 -0.4456416 -0.8068337 0.001512289 -0.5907768 -0.8405066 0.002525389 -0.5417954 -0.7907508 0.002065777 -0.6121348 -0.7690425 0.002969324 -0.6391907 -0.7431731 -7.1932e-4 -0.6690989 -0.681673 0.002424478 -0.731653 -0.7158724 0.001512289 -0.6982296 -0.6407332 0.00131613 -0.7677626 -0.6824441 0.002364814 -0.730934 -0.5644305 0.002031445 -0.8254783 -0.6160731 0.003278553 -0.7876822 -0.60154 0.002231717 -0.7988397 -0.5255504 0.002847313 -0.8507578 -0.5406782 0.001860558 -0.8412276 -0.4800757 0.001803994 -0.8772253 -0.4808047 0.001773893 -0.876826 -0.4302181 0.001720964 -0.9027234 -0.4397768 0.001331806 -0.8981061 -0.4293633 0.001321077 -0.903131 -0.3902719 0.002866089 -0.9206952 -0.3374634 0.002784073 -0.9413346 -0.2940239 9.87003e-4 -0.9557976 -0.2984769 0.001345336 -0.9544159 -0.240323 0.003027975 -0.9706882 -0.1750714 0.00112015 -0.9845551 -0.149698 0.003010153 -0.9887272 -0.0526033 0.002828955 -0.9986116 -0.00896579 -5.37029e-4 -0.9999597 0.04873788 0.002694487 -0.998808 0.130652 0.001099407 -0.9914277 0.1197834 0.001922011 -0.9927982 -0.9687157 5.20947e-4 -0.2481724 -0.9722136 -0.0012362 -0.2340921 -0.99679 1.67779e-4 -0.08006113 -0.9971452 7.36833e-4 -0.0755046 -0.9970087 -7.37224e-4 0.07728719 -0.9958889 9.25168e-4 0.09057933 -0.9652655 4.12931e-4 0.2612711 -0.9682712 -8.42809e-4 0.2499004 -0.9254224 -9.97379e-5 0.3789375 -0.9265295 -4.12788e-4 0.376222 -0.8579633 0.001255571 0.5137095 -0.8515927 -2.97764e-4 0.524204 -0.7794123 -0.001410007 0.6265097 -0.7502926 0.002483248 0.6611013 -0.6840866 -0.002102494 0.7293978 -0.6443858 0.001480638 0.7646992 -0.5738993 -9.6602e-4 0.8189254 -0.5511625 9.66027e-4 0.8343974 -0.4748509 -0.001480698 0.880065 -0.4194949 0.002693414 0.9077538 -0.3396219 -0.003191113 0.9405567 -0.2563582 0.00258553 0.9665784 -0.1551482 -0.0023216 0.9878886 -0.1345537 -9.9808e-5 0.9909063 0.00713253 0.00117731 0.9999739 0.04367554 -0.002721369 0.9990421 0.164749 0.003069043 0.9863308 0.2330454 -0.003068923 0.9724611 0.3412889 0.002306699 0.9399557 0.383498 -0.001621246 0.9235404 0.4764131 0.001354932 0.8792206 0.5104149 -0.00122708 0.8599275 0.5753539 0.001226961 0.8179037 0.6130918 -0.001872062 0.7900096 0.6853803 0.002652823 0.7281806 0.7403576 -0.002693414 0.6722079 0.7805223 0.001480519 0.6251262 0.8478738 9.3996e-4 0.5301973 0.8336297 -9.98262e-4 0.552323 0.8997915 -0.001645445 0.4363171 0.9136403 0.001542448 0.4065206 -0.9623811 -0.002476632 -0.2716922 -0.9839454 9.71192e-4 -0.1784672 -0.9854941 0.001963496 -0.1696981 -0.9966003 -0.002260982 -0.08235788 -0.999944 3.01892e-4 0.01057952 -0.9973576 -7.44109e-4 0.07264572 -0.9995607 0.00201267 0.02956938 -0.9870389 -0.001876771 0.1604702 -0.9681577 -9.82533e-5 0.2503416 -0.9742391 0.002248227 0.2255063 -0.9526084 -0.001737594 0.3041948 -0.9190074 3.31432e-4 0.3942404 -0.9143439 0.001411318 0.4049362 -0.8684311 -0.007151663 0.4957584 -0.8840191 -0.001317381 0.4674491 -0.8590419 -1.29596e-4 0.5119054 -0.823195 2.45114e-4 0.5677586 -0.8366011 0.002082586 0.5478086 -0.768575 -0.001714229 0.6397575 -0.6314449 -0.007260799 0.7753869 -0.6984295 6.00783e-5 0.7156789 -0.7187542 0.002101778 0.6952611 -0.6481421 -4.89755e-4 0.7615193 -0.6200453 2.01288e-4 0.784566 -0.6059833 0.001272499 0.7954763 -0.5758387 -8.86297e-4 0.8175629 -0.5042695 -8.53699e-4 0.863546 -0.4699776 0.001486837 0.8826771 -0.4488851 -3.22065e-4 0.8935895 -0.3632259 -0.002099573 0.9316987 -0.3096673 0.001226305 0.9508442 -0.2735257 -9.6156e-4 0.9618643 -0.2111963 -5.35113e-4 0.9774435 -0.1808354 0.001286208 0.9835126 -0.1220667 -0.00213921 0.9925196 -0.0249933 -2.36476e-4 0.9996876 -0.0157181 6.59655e-4 0.9998763 0.07701271 -0.00117588 0.9970294 0.1170185 0.001163244 0.9931291 0.1732452 -0.002143144 0.9848765 0.2727046 -1.15712e-4 0.9620979 0.2955747 0.002196311 0.9553171 0.3621921 -0.001916468 0.9321016 0.4212854 -0.001513302 0.906927 0.471639 0.001780331 0.88179 0.5014739 -8.5974e-4 0.8651725 0.5841281 -8.80495e-4 0.811661 0.5977821 4.28121e-4 0.8016585 0.6610968 -0.001176118 0.7502998 0.6867948 8.18124e-4 0.726851 0.7344384 -0.001868128 0.6786728 0.787276 0.001351356 0.6165993 0.7970231 -1.63593e-4 0.6039488 0.8639014 -0.006628632 0.5036174 0.8490697 -0.001821458 0.5282778 0.8732458 1.91626e-4 0.4872801 0.8859253 0.002015471 0.4638238 0.9028177 -2.2706e-4 0.4300235 0 1 -3.34605e-6 0 1 -1.8556e-6 0 1 -4.59451e-6 0 1 -3.21578e-7 0 1 6.52472e-6 0 1 -8.27174e-7 0 1 3.41288e-6 0 1 -6.83112e-7 0 1 2.45618e-6 0 1 -3.60792e-6 0 1 -1.69513e-6 0 1 1.3179e-6 0 1 1.33331e-6 0 1 -4.91045e-6 0 1 -9.24614e-6 0 1 5.43683e-6 0 1 -7.86119e-6 0 1 -1.72522e-6 0 1 3.66691e-6 0 1 1.0341e-5 0 1 5.65658e-7 0 1 -8.4947e-6 0 1 2.88509e-6 0 1 -4.26148e-6 0 1 8.23884e-6 0 1 2.60497e-6 0 1 1.93793e-6 0 1 1.48418e-6 0 1 4.25049e-7 0 1 -5.9707e-6 0 1 -6.39898e-6 0 1 7.73252e-7 0 1 -3.57334e-6 0 1 -3.5078e-6 0 1 -1.56598e-6 0 1 2.8455e-6 0 1 2.97437e-6 0 1 -2.85675e-6 -0.002557337 -0.9999967 1.49332e-4 -7.55563e-4 -0.9999969 -0.002378225 0.004884243 -0.9999876 -0.001114249 -0.00996375 -0.9999466 0.002741336 9.26594e-4 -0.999991 0.004144132 -0.001526892 -0.9999989 -1.60741e-4 8.07716e-4 -0.9999993 9.19508e-4 0.005375921 -0.9999856 -1.95729e-4 0.01088398 -0.9999352 -0.00336337 -6.68719e-4 -0.9999994 -9.30318e-4 -4.12389e-4 -0.9999939 -0.003458559 -7.40286e-4 -0.9999995 -8.07504e-4 0.001351118 -0.9999989 -6.73253e-4 -0.004445612 -0.9999851 0.003173053 -0.001018941 -0.9999938 -0.003388106 -0.004034996 -0.9999917 6.45997e-4 -0.005270421 -0.9999858 9.53617e-4 0.009692907 -0.9996096 0.02620786 0.001412153 -0.999999 5.03517e-4 -0.002151489 -0.9999955 -0.002133429 -0.01407653 -0.9996544 0.02220833 5.68834e-5 -0.9999998 -6.1652e-4 0.00309962 -0.9999877 -0.003905534 -0.009236872 -0.9997259 0.02151411 -0.006453633 -0.999582 0.02818292 -0.001292526 -0.9999992 6.41916e-5 -0.01771163 -0.9997621 0.01273161 0.00455898 -0.9999875 0.002088427 0.001471579 -0.9999981 -0.001287579 -0.002051413 -0.9999965 -0.001689255 -0.002127051 -0.9999963 -0.001767277 -0.001038134 -0.9999985 -0.001440823 0.004900097 -0.999988 3.45299e-4 1.73788e-4 -0.9999998 6.55102e-4 -9.94299e-4 -0.9999947 -0.003128826 7.55073e-4 -0.9999997 5.3728e-4 2.4957e-4 -1 3.63355e-4 0.01063501 -0.9997103 0.02159243 0.01177102 -0.9997823 0.01723164 0.02209812 -0.999605 0.01736164 0.0114215 -0.9995786 0.02668774 0.02370584 -0.9995599 -0.01783704 0.6950008 -0.01417303 0.7188693 0.7000716 -0.01719421 0.7138656 0.6668376 -0.01193058 0.7451076 0.6446686 -0.01345556 0.7643438 0.6625824 -0.009268641 0.7489317 0.6268702 -0.03069978 0.7785186 0.640105 -0.01291507 0.7681789 0.5690175 0.003870785 0.8223164 0.6075626 0.00914973 0.7942191 0.5208572 -4.11748e-4 0.8536437 0.5510968 0.008949697 0.8343933 0.4534906 7.43992e-4 0.8912609 0.4752538 0.007857739 0.8798138 0.3958945 0.003872513 0.9182878 0.3904942 0.00615853 0.9205848 0.3148558 4.07071e-4 0.9491395 0.3022146 0.004282414 0.9532303 0.2230865 0.001431941 0.9747977 0.2306656 0.004024565 0.9730248 0.1746512 -6.70249e-5 0.9846304 0.1194034 0.005901455 0.9928284 0.0960471 6.42353e-4 0.9953766 0.0403096 0.003160357 0.9991823 0.01016461 3.20041e-4 0.9999484 -0.02503615 0.001346528 0.9996857 2.57377e-4 0.001596868 0.9999987 -0.07558274 0.004135906 0.9971311 -0.04818636 0.004377603 0.9988288 -0.09284114 0.006464898 0.99566 0.4274574 0.002402126 0.9040323 0.3814482 0.002560794 0.9243867 0.4289712 0.002140998 0.9033156 0.3322076 0.00228995 0.9432036 0.3849445 0.00198853 0.9229377 0.3400676 4.55096e-4 0.940401 0.2506765 5.90254e-4 0.9680708 0.295181 0.003945171 0.9554333 0.1701786 0.00485593 0.9854013 0.2542104 -1.57082e-4 0.967149 0.1684522 0.005226135 0.985696 0.1201576 -7.02809e-4 0.9927546 0.07787644 0.005270361 0.9969491 0.0314663 -8.81429e-4 0.9995045 3.56751e-4 0.005432426 0.9999852 -0.06519603 0.004362821 0.9978629 -0.07365822 4.12915e-4 0.9972835 -0.1478052 0.003545284 0.9890102 -0.1635347 -0.001988768 0.9865356 -0.2048644 0.009895503 0.9787404 -0.2715221 0.01230651 0.9623535 -0.2999926 -0.05048036 0.952605 -0.2451831 0.003554999 0.9694703 -0.2904849 0.0074808 0.9568505 -0.3403166 -0.006211817 0.9402904 -0.3364979 -0.009174644 0.9416396 -0.3274192 -0.006940186 0.9448537 -0.3709468 -0.01010525 0.9285991 -0.3634762 -0.008142173 0.9315679 -0.4119009 -0.01159411 0.9111549 -0.397328 -0.008424878 0.917638 -0.4137207 -0.01129496 0.9103338 0.01893568 -0.9997613 -0.01090031 0.001715779 -0.9997804 -0.02088898 6.08131e-4 -0.999987 0.005079984 0.01753985 -0.9995667 -0.02363884 0.0101996 -0.9997144 -0.02161419 0.005351543 -0.9998435 -0.01686775 -0.004879415 -0.9999827 -0.003296136 -0.001051068 -0.9999853 -0.005307912 -0.004431903 -0.9999902 1.12189e-4 5.66809e-4 -0.9999992 0.001199781 -8.33745e-4 -0.9999997 1.28304e-4 -8.03908e-4 -0.9999997 2.06183e-4 -0.001406371 -0.9999991 -1.55533e-4 -0.001594841 -0.9999938 0.003168404 -0.002328395 -0.9999949 0.002203762 -0.002239763 -0.9999971 9.27412e-4 -0.001251757 -0.9999981 0.00156337 -0.001913011 -0.9999973 -0.00137037 -1.78343e-4 -1 -1.17559e-4 -9.02171e-5 -1 2.70818e-4 -4.50429e-5 -1 2.96358e-4 -5.82829e-4 -0.9999991 -0.001234769 6.84718e-4 -0.9999995 -6.94882e-4 -0.001074731 -0.9999987 0.001231372 0.003364622 -0.9999898 0.003044903 -0.001047015 -0.9999985 0.001447975 -8.69814e-4 -0.9999986 0.001513719 -8.25169e-4 -0.9999988 0.001405596 -0.001071333 -0.9999985 0.001403689 6.25774e-4 -0.9999982 0.001807868 -5.36347e-4 -0.9999985 0.001653134 -0.002126872 -0.9999966 0.001562356 -4.07659e-4 -0.9999995 9.45325e-4 0.003307044 -0.9999946 -9.40771e-5 -0.004252791 -0.999991 -3.00068e-4 0.004923462 -0.9999876 8.29154e-4 0.009334921 -0.9994211 0.0327146 -5.37128e-4 -0.9999992 0.001235842 0.02764022 -0.9995818 -0.008510649 -0.002270996 -0.9999974 2.53664e-5 0.02239549 -0.9997478 -0.001641333 0.02470475 -0.999694 0.001322209 0.0115118 -0.9993405 -0.03443813 0.5704858 0.002391755 -0.821304 0.6099777 0.002439141 -0.792415 0.5685715 0.002028763 -0.8226315 0.6505333 0.002071201 -0.7594749 0.6067977 0.001836836 -0.7948542 0.6443832 2.99598e-4 -0.7647028 0.7152941 1.71346e-4 -0.6988235 0.6798353 0.003775537 -0.7333552 0.7158349 3.41075e-4 -0.6982696 0.7516375 0.004273056 -0.6595626 0.7823445 -0.001376211 -0.6228444 0.7975066 0.004216253 -0.6032956 0.847209 0.001586616 -0.5312575 0.8466405 0.002030134 -0.5321614 0.8967332 0.004155516 -0.442552 0.8982066 0.002608358 -0.439566 0.9303854 0.003346681 -0.3665679 0.9359999 -0.00208652 -0.3519944 0.9500151 0.00990808 -0.3120468 0.9691603 0.01237934 -0.2461202 0.9787734 -0.03519624 -0.2019006 0.9633259 0.005021691 -0.2682873 0.9753858 0.007175922 -0.2203887 0.9844321 -0.006965696 -0.1756275 0.9837347 -0.009175002 -0.1793935 0.982205 -0.007219433 -0.1876732 0.9896625 -0.01011228 -0.1430594 0.9884981 -0.008149564 -0.1510142 0.9935529 -0.008740007 -0.1130327 0.9933738 -0.008421897 -0.1146195 0.9954972 -0.005849659 -0.0946117 0.303344 -0.001698851 -0.9528796 0.2679724 -0.01733708 -0.9632707 0.3118631 -0.01207369 -0.9500503 0.3396126 -0.0133441 -0.9404708 0.3178319 -0.009155511 -0.948103 0.3695895 -0.04182541 -0.9282534 0.3444195 -0.01290643 -0.9387272 0.4276066 0.004169106 -0.9039554 0.3841777 0.009345412 -0.923212 0.4788218 -1.38681e-4 -0.8779121 0.4462099 0.009068846 -0.8948825 0.5458269 9.00822e-4 -0.8378975 0.5225203 0.008607983 -0.8525834 0.5971236 0.004499197 -0.8021367 0.597194 0.004535555 -0.802084 0.6651936 0.001090705 -0.7466702 0.6585855 0.003932476 -0.7524958 0.7286109 0.002107858 -0.6849246 0.7315874 0.003418385 -0.6817391 0.7628868 0.007414996 -0.6464897 0.7797091 8.75949e-4 -0.6261414 0.8134946 1.41645e-4 -0.5815727 0.8186247 0.001905918 -0.5743259 0.8606265 5.24143e-4 -0.5092366 0.8422528 0.003823399 -0.5390694 0.8787826 0.001479268 -0.4772201 0.8658905 0.001832902 -0.5002304 0.9049708 0.004070103 -0.4254544 0.8890987 0.004376292 -0.4576946 0.9086949 0.00526911 -0.4174278 -0.008987426 -0.9997747 -0.01923209 -0.03393751 -0.9993774 0.00965178 -0.003886997 -0.9997503 -0.02200996 -0.0216723 -0.9995601 -0.02025169 -0.009294927 -0.9997852 -0.01852834 0.001275658 -0.9999986 -0.001068532 0.001687347 -0.9999983 -8.13501e-4 0.001629889 -0.9999985 -5.54393e-4 0.001011073 -0.9999958 -0.002755939 7.34296e-4 -0.9999977 -0.001999914 0.001996994 -0.9999961 0.001996278 -0.001710534 -0.999998 -0.001056969 -5.46802e-4 -0.9999877 0.004946291 0.00153315 -0.9999988 -5.71292e-4 8.63156e-4 -0.9999967 -0.002425014 4.57773e-6 -1 -7.04073e-6 6.28626e-6 -1 2.72736e-6 0 -1 1.18145e-5 1.10661e-6 -1 0 -1.96179e-6 -1 2.896e-6 -7.92649e-4 -0.9999997 -4.17431e-4 2.54642e-4 -0.9999993 -0.001182615 0.003598809 -0.9999935 -2.85558e-4 -0.001962304 -0.999993 0.003181636 0.002072989 -0.9999915 0.003567755 7.91538e-4 -0.9999977 -0.001999974 -5.27409e-5 -0.9999999 -6.07656e-4 1.86826e-6 -1 0 9.86065e-6 -1 -1.07919e-5 3.38429e-7 -1 1.08299e-5 7.47113e-6 -1 5.45546e-6 -0.009340822 -0.9998151 0.01681363 0.001785337 -0.999998 9.61058e-4 -0.001062452 -0.9999966 0.002443194 -0.02948147 -0.9995598 -0.003320872 0.001500844 -0.9999971 0.001892387 0.001403927 -0.9999973 0.001897096 0.002256751 -0.9999975 -1.83673e-4 -7.25856e-4 -0.9999994 8.24521e-4 -0.0165131 -0.9998529 0.00463742 -0.01767814 -0.9997385 -0.01450479 -0.017879 -0.9998021 0.008727312 -2.24408e-4 -1 -7.5287e-5 -0.9967036 0.002693176 -0.08108466 -0.9965468 0.002413153 -0.08299785 -0.9913332 0.002289831 -0.1313524 -0.9917561 0.00274384 -0.1281108 -0.9840011 0.002259373 -0.1781488 -0.984438 0.002603948 -0.1757133 -0.9743878 0.002172172 -0.2248638 -0.9750154 0.002564489 -0.2221229 -0.9642531 0.003330349 -0.264962 -0.9626219 0.002481102 -0.2708374 -0.9470937 0.00372219 -0.3209356 -0.9392539 -7.51964e-4 -0.3432226 -0.9198764 0.004189372 -0.3921861 -0.9211119 0.004669308 -0.3892699 -0.8946452 0.004484415 -0.4467549 -0.8720358 0.003985702 -0.4894259 -0.8830193 0.008590579 -0.4692581 -0.8514935 0.003120541 -0.524356 -0.8245729 0.008078575 -0.5656982 -0.8280966 0.009896039 -0.5604981 -0.7977598 0.004595518 -0.6029579 -0.7703104 0.005253553 -0.6376477 -0.7827047 0.007977068 -0.6223422 -0.7540036 0.007809042 -0.6568239 -0.7396999 0.005206525 -0.6729168 -0.7200209 0.009326398 -0.6938897 -0.7048937 0.004442095 -0.7092991 -0.6739631 -0.04816645 -0.7371932 -0.6785973 0.006783604 -0.7344792 -0.6452663 -0.00699371 -0.7639259 -0.6472318 -0.009170651 -0.7622382 -0.6536284 -0.007222414 -0.7567813 -0.6187203 -0.01014572 -0.7855458 -0.6251677 -0.008138775 -0.7804481 -0.5993898 -0.007306516 -0.800424 -0.5949243 -0.008384466 -0.8037381 -0.5802072 -0.003339946 -0.8144621 -0.9767133 -0.004449605 0.2145029 -0.9720164 -0.01330637 0.2345361 -0.9786065 -0.01785671 0.2049647 -0.9842804 -0.01312214 0.1761249 -0.9867193 -0.02383363 0.1606776 -0.9865772 -0.006886959 0.1631508 -0.9839832 -0.005018651 0.1781907 -0.9964075 0.004011988 0.08459407 -0.9945957 0.00948584 0.1033896 -0.9993875 0.004221916 0.0347414 -0.9999785 0.00193566 -0.006268501 -0.9997297 0.008124291 0.02178525 -0.9987236 0.002837121 -0.05043077 -0.9953558 0.002607464 -0.09622979 -0.9973777 0.00845915 -0.07187747 -0.9899038 6.62473e-4 -0.1417397 -0.982015 0.008000671 -0.1886339 -0.9829153 0.006327748 -0.1839501 -0.9735165 6.33763e-4 -0.2286159 -0.9610421 0.002678573 -0.2763893 -0.9564459 0.006015181 -0.291848 -0.9402714 -6.71998e-5 -0.3404256 -0.9323737 0.00424993 -0.3614712 -0.9147716 0.00274831 -0.4039623 -0.8924704 0.00390017 -0.4510892 -0.9069766 0.004987418 -0.4211516 -0.8684598 0.003988802 -0.4957438 -0.8879746 0.005024671 -0.4598652 -0.8438813 0.003802597 -0.5365166 -0.8661501 0.004552125 -0.4997634 -0.8224963 0.004161715 -0.5687552 -0.8409217 0.00451076 -0.5411381 -0.815778 0.005744636 -0.5783366 1.21105e-6 1 1.41925e-6 1.447e-6 1 3.10954e-6 9.56446e-7 1 2.92537e-6 1.61124e-6 1 1.71263e-6 6.74026e-7 1 3.36227e-6 9.23532e-7 1 2.66604e-6 1.62813e-6 1 1.51622e-6 1.11938e-6 1 1.0968e-6 1.55767e-7 1 4.50502e-6 0 1 2.60102e-6 1.06681e-6 1 5.04175e-7 -3.02898e-7 1 3.55234e-6 2.86632e-5 1 -1.15396e-5 -2.46068e-5 1 -1.87542e-5 -6.89897e-7 1 2.66343e-6 -2.73968e-5 1 -1.48795e-5 -5.64922e-7 1 2.4293e-6 -1.60624e-5 1 1.19895e-5 -1.18215e-6 1 0 -4.78452e-7 1 9.90591e-7 -1.26158e-6 1 1.89219e-6 -8.43957e-7 1 9.07622e-7 -3.08135e-7 1 -4.80054e-7 -6.22563e-7 1 9.44889e-7 -2.31698e-5 1 -3.24166e-5 -5.23395e-7 1 -2.2382e-5 -5.00642e-5 1 2.60758e-5 9.45037e-7 1 0 1.56939e-5 1 -1.83727e-5 1.02783e-6 1 2.86867e-7 1.29976e-5 1 7.75057e-6 1.60772e-6 1 0 2.34941e-7 1 4.82766e-7 5.11463e-7 1 -1.85013e-6 1.87566e-6 1 1.89811e-7 2.74038e-6 1 -9.86521e-7 1.04654e-6 1 -4.58263e-7 8.52239e-6 1 -1.51801e-5 2.61992e-6 1 -5.7141e-7 2.69077e-6 1 -7.60164e-7 1.61467e-5 1 -8.00344e-6 9.97732e-6 1 7.3714e-6 2.79001e-6 1 -2.02437e-6 -3.62572e-6 1 1.21376e-6 2.828e-6 1 -1.50191e-6 -3.63517e-6 1 7.09223e-7 -5.10594e-6 1 1.9605e-6 2.92842e-6 1 -2.68916e-6 1.85385e-6 1 -3.03178e-6 -5.70659e-6 1 0 1.83249e-6 1 -2.06905e-6 -3.09439e-6 1 -1.91719e-6 -1.28145e-6 1 -3.64305e-7 1.55624e-6 1 -1.99467e-6 1.40692e-6 1 -2.28354e-6 0 1 -1.51728e-6 1.22684e-6 1 -2.98094e-6 9.2608e-7 1 4.39477e-7 -2.79839e-7 1 -1.50197e-6 2.41126e-6 1 -6.03298e-7 2.62801e-6 1 1.02463e-6 2.47729e-7 1 -7.55552e-7 -4.64286e-7 1 1.89876e-6 -8.41791e-6 1 3.1079e-6 -2.04351e-6 1 1.50617e-5 -1.08604e-6 1 -5.81738e-7 -9.49976e-7 1 -5.6928e-7 -5.19283e-6 1 -1.56256e-6 0 1 1.45216e-5 9.1997e-6 1 1.78256e-6 -3.87375e-7 1 1.24003e-6 -3.9427e-6 1 -4.41835e-6 2.09303e-7 1 1.4568e-6 -2.05336e-6 1 -3.53411e-6 -9.03559e-6 1 7.06712e-6 -2.21291e-6 1 -3.49365e-6 7.60784e-6 1 2.0643e-5 2.03771e-5 1 1.07132e-5 -1.72961e-6 1 -3.39596e-6 0.9309621 0.02774 0.3640608 0.8804768 -0.1045089 0.4624267 0.8931435 -0.03719294 0.4482313 0.8455654 0.04871678 0.5316445 0.7749748 -0.1258251 0.6193402 0.7965759 -0.04077315 0.603162 0.7574797 -0.01824599 0.6526037 0.6938292 0.04615938 0.7186588 0.6376818 -0.1406548 0.7573495 0.6140913 -0.008008182 0.7891944 0.5610677 0.05413019 0.8259983 0.4792252 -0.1109679 0.8706489 0.4719784 -0.06534755 0.8791849 0.3855107 0.04056346 0.9218114 0.3084287 -0.05002009 0.9499315 0.2936843 -0.08069658 0.9524902 0.3161191 -0.01621943 0.9485809 0.1851871 0.04600369 0.9816259 0.1548614 -0.01647019 0.987799 0.02668082 -0.02278029 0.9993844 0.0556007 -0.09068745 0.9943261 0.0322231 -0.01083183 0.9994221 -0.04778611 0.04002344 0.9980555 -0.1378701 -0.06337779 0.9884205 -0.1517986 -0.1236354 0.9806485 -0.2171522 0.0133838 0.976046 -0.2937837 0.01896154 0.9556838 -0.3417592 -0.1251375 0.931419 -0.3620384 -0.05406618 0.930594 -0.4275833 0.04166948 0.9030151 -0.5185697 -0.1229673 0.8461469 -0.5058501 -0.04706567 0.8613364 -0.5871466 0.04831534 0.8080375 -0.6745948 -0.1274219 0.7271077 -0.6573102 -0.03127729 0.7529708 -0.7049373 -0.02224743 0.7089206 -0.7647629 0.04540729 0.6427099 -0.8046342 -0.1262452 0.580195 -0.8237851 -0.03651601 0.5657252 -0.8761563 0.05095112 0.4793268 -0.902105 -0.1344927 0.4100226 -0.9221323 -0.02269971 0.3862084 -0.9550968 0.04328459 0.2931153 -0.9682726 -0.1084325 0.2251456 -0.9691095 -0.1030714 0.2240605 -0.9900951 0.04855602 0.1317351 -0.9959725 -0.07697224 0.04598057 -0.9987806 -0.03606462 0.03371727 -0.9967576 -0.01462888 -0.07912373 -0.9903951 -0.1290119 -0.04973441 -0.9920547 0.004065275 -0.1257421 -0.9174817 -0.1219687 -0.3786174 -0.9788889 -0.0116744 -0.2040592 -0.9785558 -0.02250301 -0.2047494 -0.9771919 -0.03278267 -0.2098128 -0.9464765 -0.01645332 -0.3223533 -0.1515913 -0.9356419 -0.318739 0.05446392 -0.9158942 -0.3977079 -0.04061067 -0.9205725 -0.3884549 0.009217023 -0.9175534 -0.3975057 -0.1153637 -0.9167767 -0.3823765 -0.06966012 -0.9183071 -0.3896916 -0.03599548 -0.9200595 -0.3901215 -0.162101 -0.9231106 -0.3486977 -0.146968 -0.9185456 -0.3669803 -0.03276497 -0.9189419 -0.3930295 -0.03622353 -0.9020001 -0.4302137 -0.1040722 -0.9196166 -0.3787804 -0.05624973 -0.947444 -0.314938 -0.07086527 -0.9634961 -0.2581736 -0.2149934 -0.9264554 0.3089635 -0.3339586 -0.9273133 0.1690019 -0.3397452 -0.9201374 0.1947321 -0.328301 -0.9184725 0.2205151 -0.2417161 -0.9190596 0.3112922 -0.295186 -0.9200146 0.2577566 -0.3026806 -0.9192045 0.2518878 -0.3219308 -0.9199592 0.2236867 -0.2720054 -0.9180184 0.2885401 -0.2744016 -0.9200696 0.2795993 0.3817921 -0.9238666 0.0265569 0.3738014 -0.9188957 0.126108 0.3922511 -0.9184174 0.0514642 0.3916534 -0.9184688 0.05498147 0.3731539 -0.9202654 0.1177622 0.6231596 -0.6858006 -0.3759652 0.6271606 -0.6716499 -0.394406 0.6305788 -0.6662569 -0.3980857 0.5993053 -0.6798816 -0.4226042 0.5832101 -0.6784798 -0.4466891 0.5877648 -0.6454985 -0.4877135 0.5794931 -0.6668428 -0.4685174 0.5816554 -0.6489961 -0.4903889 0.5398778 -0.6674516 -0.5128747 0.5018721 -0.669535 -0.5475832 0.5106895 -0.6276134 -0.5876204 0.5166807 -0.617392 -0.593185 0.4628287 -0.6477731 -0.6051278 0.4431483 -0.6493023 -0.6180828 0.3990325 -0.7049241 -0.5863916 0.4394728 -0.6880562 -0.5774447 0.4396716 -0.700237 -0.5624563 0.4521991 -0.7124162 -0.536637 0.4766678 -0.7148813 -0.5115981 0.5131822 -0.6969541 -0.5008983 0.4833235 -0.7191423 -0.4992324 -0.3493642 -0.6846996 -0.6396336 -0.2725616 -0.7057614 -0.6539198 -0.2077801 -0.7002125 -0.68303 -0.1767084 -0.6846737 -0.707104 -0.1379046 -0.7046609 -0.6960139 -0.06657469 -0.7192413 -0.6915634 0.002591192 -0.7099497 -0.7042477 0.06862854 -0.6777909 -0.7320448 0.08337867 -0.6668288 -0.7405319 0.1480628 -0.7061053 -0.6924542 0.1056413 -0.6836817 -0.7220938 0.2113127 -0.717769 -0.6634415 0.1681771 -0.7124829 -0.6812375 0.2806768 -0.7061141 -0.6500949 0.2349958 -0.7163863 -0.6569381 0.3611553 -0.667277 -0.6513895 0.3084315 -0.6954959 -0.648965 0.3310298 -0.6867833 -0.6471074 0.4055604 -0.7062451 -0.5802919 0.3682879 -0.701493 -0.6101408 0.4428921 -0.7026313 -0.5569164 0.4911186 -0.6948876 -0.5252939 0.4876354 -0.6864318 -0.5394657 0.5229638 -0.7186257 -0.4583516 0.5665604 -0.7178548 -0.404591 0.6259417 -0.6923234 -0.3590061 0.6300771 -0.7204746 -0.2896884 0.5744857 -0.7236196 -0.3825453 0.6878899 -0.688947 -0.2283846 0.6561448 -0.708801 -0.2589887 0.71386 -0.6689171 -0.2072532 0.7071579 -0.6812011 -0.1894538 0.6909814 -0.7129586 -0.1193095 0.6905074 -0.7216299 -0.04949545 0.7072898 -0.7066529 0.01957029 0.7344998 -0.6725937 0.09015494 0.7471885 -0.656044 0.1063756 0.6546959 -0.7227684 0.2213128 0.5870954 -0.7185705 -0.3727942 0.5674872 -0.6951139 -0.4413331 0.6098756 -0.711175 -0.3496883 0.6497059 -0.6831889 -0.3333695 0.643378 -0.7059412 -0.296162 0.626466 -0.7029699 -0.3367103 0.4554589 -0.5924066 -0.6645387 0.4855908 -0.5736665 -0.6596276 0.503921 -0.5396492 -0.6744202 0.535901 -0.5691025 -0.6236446 0.5743513 -0.5734187 -0.5842188 0.6168785 -0.5362609 -0.5760948 0.6603506 -0.5172881 -0.5443806 0.6415858 -0.4845008 -0.5946652 0.6924518 -0.5188124 -0.5013424 0.7288445 -0.4934208 -0.4746806 0.725884 -0.4772399 -0.4953126 0.7499707 -0.5018267 -0.4309454 0.7709487 -0.482737 -0.4154555 0.3508576 -0.5887467 0.7282007 0.3313488 -0.5711083 0.7510282 0.3345327 -0.53844 0.7734147 0.2722306 -0.5691929 0.7758286 0.2179348 -0.5734038 0.7897547 0.1901133 -0.5344762 0.8235242 0.13992 -0.5143793 0.8460713 0.1946676 -0.4753333 0.8579993 0.07511126 -0.5209198 0.8502946 0.04737758 -0.4827692 0.8744652 0.0486961 -0.5000563 0.8646228 -0.01450687 -0.5027319 0.8643207 0.02183103 -0.7168798 0.696855 0.09636515 -0.691843 0.7155887 -0.002103626 -0.711167 0.70302 -0.03613513 -0.6831842 0.7293515 -0.06524282 -0.705663 0.7055375 -0.02184319 -0.7026702 0.7111805 0.01296359 -0.6847292 0.7286823 0.02431666 -0.6702941 0.7416971 0.03850746 -0.6767621 0.7351942 0.07434254 -0.6878293 0.7220554 0.1109188 -0.6901007 0.7151629 0.1280543 -0.6841605 0.7180018 0.145442 -0.6666739 0.7310217 0.1569473 -0.6257536 0.7640681 0.1564612 -0.6364614 0.7552727 0.2161648 -0.6622157 0.7174561 0.2500545 -0.6641713 0.7045206 0.2769233 -0.642763 0.7142614 0.2818051 -0.6310594 0.7227379 0.305831 -0.6457537 0.6996211 0.7254581 -0.6878639 0.02353674 0.7010443 -0.7070036 0.09318166 0.6584087 -0.7175023 0.2273512 0.7075009 -0.6880533 0.1613229 0.689752 -0.7020727 0.1770203 0.3079234 -0.7047972 0.6390964 0.2803706 -0.6880369 0.6693263 0.2673437 -0.7001723 0.662032 0.238638 -0.7124136 0.6599385 0.204715 -0.7148764 0.6686132 0.1791529 -0.698255 0.6930688 0.1849979 -0.7080587 0.6814901 -0.8100159 -0.5822649 -0.06958442 -0.8220714 -0.5583736 -0.1114345 -0.8311014 -0.547868 -0.09545338 -0.8000203 -0.5732797 -0.1769689 -0.8038233 -0.5530232 -0.2191656 -0.8029611 -0.5290969 -0.2744269 -0.830711 -0.503874 -0.2367075 -0.7916585 -0.5067438 -0.3413026 -0.8139595 -0.457008 -0.3586277 -0.7762609 -0.4922391 -0.3938525 -0.7579079 -0.487412 -0.4335959 -0.7609974 -0.4563899 -0.4610764 -0.6954516 -0.6512258 -0.3037301 -0.6163935 -0.7185727 -0.3220441 -0.6485923 -0.7039954 -0.2893417 -0.6077856 -0.711165 -0.3533287 -0.6135781 -0.683168 -0.3959842 -0.5727348 -0.7126567 -0.4050868 -0.6014944 -0.7100645 -0.3660778 -0.3751531 -0.6940513 0.6144535 0.1003135 -0.6964282 -0.7105807 -0.4285665 -0.7164898 0.55043 -0.4751129 -0.7125957 0.5162125 -0.5516364 -0.6800105 0.4829938 -0.539434 -0.6878375 0.4856858 -0.5710344 -0.707207 0.4168669 -0.6038056 -0.7068578 0.368471 -0.6427596 -0.6613023 0.3867033 -0.647473 -0.706582 0.2855183 -0.6431419 -0.689139 0.3338502 -0.6368718 -0.6969299 0.329671 -0.6566742 -0.71573 0.2377175 -0.6650413 -0.7161855 0.2116568 -0.7085158 -0.6870097 0.161317 -0.7024062 -0.697117 0.143713 -0.7000885 -0.7089774 0.08501344 -0.708233 -0.7055978 0.02319127 -0.7206041 -0.6928079 -0.0273329 -0.7227784 -0.6906654 -0.02393054 -0.6934219 -0.7135818 -0.0998364 -0.6973369 -0.7119478 -0.08277511 -0.6945267 -0.6708976 -0.2598638 -0.6802031 -0.7009001 -0.2146229 -0.6302765 -0.710891 -0.3120669 -0.5619626 -0.700441 -0.4399778 -0.587515 -0.7179546 -0.3733195 -0.5326573 -0.7017434 -0.4731093 -0.5581861 -0.691421 -0.4586561 -0.4764679 -0.7095339 -0.5191723 -0.4369263 -0.6937367 -0.57256 -0.4400588 -0.6920664 -0.5721821 -0.3344058 -0.7116319 -0.6178614 -0.3707089 -0.7113679 -0.5971019 -0.2998146 -0.7042782 -0.6435088 -0.2911624 -0.6858437 -0.6669656 -0.2757673 -0.6931132 -0.6659929 -0.2085289 -0.7065426 -0.6762495 -0.2503898 -0.6996185 -0.6692078 -0.1703813 -0.7059466 -0.6874662 -0.1067651 -0.6863842 -0.7193594 -0.1104544 -0.6838302 -0.7212324 -0.03560125 -0.7129873 -0.7002726 0.0333423 -0.7161098 -0.6971908 -0.696489 -0.7157056 -0.05165737 -0.7198131 -0.688064 -0.09185451 -0.6949719 -0.7111123 -0.106458 -0.6908134 -0.7124434 -0.1232939 -0.6813717 -0.7149056 -0.1569799 -0.6903659 -0.696977 -0.193954 -0.6762266 -0.7162675 -0.1722745 -0.6365099 -0.6886028 -0.3473923 -0.6640784 -0.6637836 -0.3440806 -0.6588073 -0.6696177 -0.3429068 -0.6675543 -0.6756364 -0.3128686 -0.6759251 -0.6845557 -0.2729631 -0.6886559 -0.6815466 -0.2474824 -0.7106837 -0.6629542 -0.2354156 -0.7388987 -0.6302933 -0.2382417 -0.7293623 -0.642635 -0.2346293 -0.728085 -0.6653562 -0.1649044 -0.7414163 -0.6595968 -0.1234259 -0.7592962 -0.6409087 -0.1127185 -0.7753904 -0.6207874 -0.1157267 -0.762029 -0.6427819 -0.07838052 -3.83276e-5 -1 -9.16021e-5 -3.5183e-5 -1 -9.65294e-5 -1.38718e-5 -1 -5.03952e-5 -1.52143e-4 -1 -1.24006e-5 -5.70859e-5 -1 -5.64336e-5 1.19593e-5 -1 -1.03079e-4 -6.07299e-5 -1 1.57939e-5 4.97182e-5 -1 -5.60268e-5 -6.28431e-5 -1 6.04281e-5 1.61972e-5 -1 -7.56119e-5 2.35209e-6 -1 -1.19135e-4 3.91501e-5 -1 -7.37093e-5 -6.41703e-5 -1 -3.54294e-5 3.45922e-5 -1 -6.35764e-5 6.06011e-5 -1 -5.61887e-5 -4.531e-5 -1 2.60496e-5 -5.93164e-5 -1 6.83681e-5 9.33312e-5 -1 -2.7267e-6 -4.6798e-5 -1 2.2854e-5 9.88847e-5 -1 3.82968e-5 -4.34568e-5 -1 5.3168e-5 5.52095e-5 -1 -2.61016e-5 -2.20688e-4 -1 -6.44273e-5 5.89653e-5 -1 -4.70787e-5 -8.45979e-5 -1 1.58839e-4 1.16079e-4 -1 1.37471e-4 2.77222e-5 -1 1.832e-4 1.10745e-4 -1 1.46175e-4 -9.22614e-5 -1 8.08963e-5 1.33998e-4 -1 -8.88707e-6 9.38964e-5 -1 1.12647e-5 1.12583e-4 -1 1.36358e-5 3.18866e-5 -1 8.23107e-5 3.87461e-5 -1 6.90503e-5 -3.43977e-5 -1 6.8245e-5 -0.96478 -0.002635061 -0.2630454 -0.9781337 -0.03093147 -0.2056641 -0.9866169 -0.002858042 -0.163031 -0.9996871 0.005005002 0.0245102 -0.9973073 -0.02798378 0.06778711 -0.9753788 0.008654356 0.2203665 -0.9599809 -0.02298194 0.2791209 -0.9284276 0.004609405 0.3714849 -0.8861342 -0.00454545 0.4634064 -0.8694012 -0.03112512 0.4931257 -0.7945342 0.001290023 0.6072182 -0.7770299 -0.01500308 0.6292849 -0.7179602 0.005429804 0.696063 -0.6178871 -0.02734929 0.785791 -0.6154019 -0.02981269 0.7876495 -0.4819589 0.02262771 0.8759016 -0.3348473 -0.03859353 0.9414818 -0.3345531 -0.03892475 0.9415727 -0.1640651 0.02030944 0.9862405 -0.04253315 -0.01336365 0.9990057 -0.0189827 -0.03121834 0.9993324 0.08522039 0.002837896 0.9963582 0.201126 -0.02078646 0.9793449 0.2299171 -0.003068208 0.9732054 0.3513551 -0.002208828 0.9362397 0.3906341 -0.02319741 0.9202538 0.4799409 0.007238268 0.8772709 0.564768 -0.02238541 0.8249461 0.6093692 0.005396306 0.7928683 0.7282028 -0.02315634 0.6849706 0.7214043 -0.03111135 0.691815 0.8135247 0.01676666 0.5812887 0.8910481 -0.04089337 0.4520631 0.8874399 -0.03482395 0.459606 0.9320819 0.008296847 0.3621529 -0.4817954 -0.8701588 -0.1034265 -0.4682211 -0.8789659 -0.09048765 -0.4640648 -0.8818908 0.08314114 -0.5143218 -0.856813 0.03667163 -0.4952616 -0.8567227 0.1440217 -0.4158642 -0.8754766 0.2461659 -0.4512923 -0.8605956 0.2360312 -0.3984362 -0.8585494 0.3227098 -0.3375535 -0.8758916 0.3447776 -0.3235649 -0.8526103 0.4103187 -0.2233206 -0.8812662 0.4165307 -0.1794884 -0.8443421 0.5048468 -0.1033431 -0.8778728 0.4676105 0.0176208 -0.8749924 0.4838161 -0.009087979 -0.8598753 0.5104233 0.1054676 -0.8514708 0.5136867 0.1883915 -0.8760602 0.4438776 0.1893937 -0.8779308 0.4397359 0.296147 -0.8515509 0.4326177 0.3556841 -0.8645132 0.355114 0.3490495 -0.8775261 0.3288046 0.4529452 -0.8603893 0.2336043 0.4390801 -0.8669413 0.2358422 0.9371331 -0.00444585 0.3489438 0.8934515 0.004919052 0.4491328 0.5882691 -0.007184624 0.8086334 0.4941112 0.003644049 0.8693912 0.1019819 0.002533316 0.9947831 -0.003318607 -0.005405426 0.99998 -0.2798368 0.003548145 0.960041 -0.4553501 -0.004283666 0.8903021 -0.6364463 0.005464076 0.7713017 -0.8062196 -0.005456686 0.5915914 -0.9172602 0.004015922 0.3982683 -0.9811037 -0.004404246 0.1934331 -0.9998119 0.00444746 0.01887995 -0.9386643 -0.005880773 -0.3447823 0.6082018 -0.7343226 0.3014318 0.5588479 -0.6675313 0.4920274 0.3332656 -0.7360095 0.5892572 0.242812 -0.6752508 0.6964759 0.06683349 -0.7247785 0.6857329 -0.07680207 -0.6831141 0.7262622 -0.1900561 -0.7244985 0.6625562 -0.3496798 -0.686764 0.6372436 -0.4363877 -0.7295353 0.5266347 -0.5739732 -0.6785113 0.4584509 -0.6324678 -0.724611 0.2737216 -0.691577 -0.6925486 0.2051773 -0.6944918 -0.7193696 0.01373386 -0.7187241 -0.6939408 -0.04338002 0.9032511 -0.008144319 0.4290352 0.9277104 -0.002444803 0.3732928 0.7218685 0.00697714 0.6919951 0.4141469 -0.001304984 0.9102092 0.3856974 -0.004858851 0.9226126 -0.2066941 0.002505958 0.9784024 -0.1647061 -0.003329873 0.9863371 -0.6642022 0.006084144 0.7475283 -0.7748359 -0.006290555 0.6321312 -0.9160155 0.004042983 0.4011228 -0.9826998 -0.005534768 0.185123 -0.9987183 0.006799697 -0.05015593 0.6450867 -0.7166303 0.2651495 0.6473391 -0.6767498 0.3506591 0.4985839 -0.7252735 0.4747552 0.3944515 -0.6671997 0.6318643 0.2864 -0.7248456 0.6265572 -0.03386372 -0.675203 0.7368543 -0.1105886 -0.7305448 0.6738505 -0.3418445 -0.6803802 0.6482477 -0.460601 -0.7238132 0.513752 -0.5586469 -0.6800997 0.47474 -0.6192401 -0.7379452 0.2682886 -0.7401486 -0.6641973 0.1049862 -0.6822053 -0.7306066 -0.02846229 0.8032026 0.007164597 0.5956628 0.5280526 -0.005442023 0.8491942 0.4698649 7.89139e-4 0.8827381 -0.02724093 -0.001060783 0.9996284 -0.009305536 -0.002969861 0.9999524 -0.4077918 0.005065202 0.9130609 -0.5804255 -0.007325232 0.8142804 -0.7947412 0.007154464 0.6069062 -0.9063163 -0.005903184 0.4225589 -0.9962719 0.003760457 0.08618789 -0.9999914 -0.002005517 0.003645956 -0.9402815 0.003171086 -0.3403832 0.675766 -0.6735019 0.299559 0.5537478 -0.7288978 0.402581 0.3218696 -0.7244924 0.6095169 0.4230761 -0.6691346 0.6109546 -0.005064129 -0.6859701 0.7276121 0.00643891 -0.67593 0.7369377 -0.2816884 -0.7291072 0.6237422 -0.3957571 -0.6758275 0.6217988 -0.5478193 -0.7275692 0.4129614 -0.577886 -0.7112952 0.4001337 -0.6786792 -0.7317289 0.06298786 -0.6990749 -0.6860685 0.2015054 -0.6308825 -0.740352 -0.2320911 -0.7310889 -0.6777583 -0.07843983 -0.2531365 -0.4684506 -0.8464492 -0.3919364 0.3832048 -0.8363851 0.0475912 0.2998664 -0.9527934 -0.4548802 -0.1113163 -0.8835683 -0.7633468 -0.4503448 -0.4631319 -0.7241396 -0.3994885 -0.5621663 -0.644748 -0.3200884 -0.6941496 0.1809238 -0.006669938 -0.9834745 -0.7812528 -0.4523025 -0.4301937 -0.9495303 -0.00553292 0.3136269 -0.2257226 -0.9375936 -0.2645136 -0.2216207 -0.8042771 -0.5513824 -0.4150695 -0.7049204 -0.575156 0.01081502 0.009931266 -0.9998923 -0.7937898 -0.3353812 -0.5073632 0.4037514 -0.8847016 -0.2329977 -0.8893612 0.4255948 -0.1670506 -0.8169266 -0.5673574 -0.1036178 -0.9886503 0.02473431 -0.1481853 -0.9808276 0.1784989 -0.07820135 -0.9972912 0.01164001 0.07262891 -0.9671418 0.2471122 0.05976819 -0.9636473 0.1682776 0.207525 -0.9710129 0.1094619 0.2124901 -0.7411824 -0.5946274 0.3115559 -0.9078698 -0.1576384 0.3884875 -0.9153317 0.03678363 0.4010171 -0.674947 -0.7188246 0.166547 -0.4435453 -0.8935676 0.06931477 0.253028 0.9023862 0.3488209 0.1382954 -0.9349649 0.3266727 -0.7338964 -0.2221685 0.6419013 -0.9011526 -0.01555395 0.433223 -0.5502336 0.5330834 0.6427014 0.001664161 -0.00301969 0.9999942 0.3759327 -0.004888713 0.9266341 0.2544223 -0.9520346 0.1699984 -0.2251946 -0.9282327 0.2960937 -0.8617554 0.01246386 0.5071711 0.07798856 -0.8247206 0.5601372 -0.546315 -0.8179577 0.1802366 -0.05604314 0.9345044 0.3515121 0.01368373 0.9364052 0.3506539 0.2119745 -0.3918548 0.8952746 0.3736703 0.3842915 0.84421 0.5099253 0.1882815 0.8393607 0.5085089 0.1969509 0.8382298 0.6392822 0.03821307 0.7680222 0.6349776 0.08807629 0.7674934 0.6897634 0.3116821 0.6535142 0.8024564 0.1175144 0.585025 0.7998402 0.1365069 0.5844841 0.40478 -0.7484651 0.5253124 -0.3974115 -0.8811414 -0.2562304 -0.1997431 0.9518634 -0.2325053 -0.1114004 -0.9779786 -0.1764879 -0.1282697 0.9486339 -0.2892071 0.02489012 0.9247294 -0.3798107 0.1852656 0.8839078 -0.4293994 -0.06502956 -0.9924377 0.1041089 0.09780496 -0.8854103 0.4544038 0.6065815 -0.7549283 -0.2492837 0.9791498 0.01218581 0.2027743 0.8398143 0.52193 0.1493356 0.9035915 -0.001313745 -0.4283934 0.6487765 -0.3109602 -0.6945451 0.5763421 -3.06598e-4 -0.8172086 0.01292735 -0.9319774 -0.3622859 0.1374535 -0.9265823 -0.3500741 0.2233697 -0.9113552 -0.3457422 0.3706896 -0.9114077 -0.1786763 0.4485859 -0.8917286 0.0599249 0.6617833 -0.7349861 -0.1477782 0.6482179 -0.7582482 -0.06981003 0.8394312 -0.2109286 -0.5008638 0.4932172 -0.6251593 0.6049072 0.2925627 0.9452488 0.1446098 0.8598071 -0.4609257 0.2197256 0.3186765 0.9400804 -0.1212196 0.09275859 0.9924684 -0.08001571 0.6577198 0.1386127 -0.7403994 0.5126695 -0.2357935 -0.8255736 0.4737086 -0.4101192 -0.7793603 0.4682189 0.2147413 -0.8571215 0.3453559 0.05303227 -0.9369723 0.3465276 0.09248888 -0.9334691 0.2277653 0.1523356 -0.961726 0.1060609 0.05490267 -0.9928429 0.1111857 0.1753996 -0.9781987 -0.0488286 -0.9164195 -0.3972293 0.1873028 -0.7421008 -0.643587 -0.007880985 -0.9696035 0.2445545 -0.08380037 0.9650568 0.24828 -0.3583402 0.9284673 0.09767681 -0.5623767 -0.8237565 -0.07181853 0.4112344 -0.8318697 -0.3726647 -0.2528926 -0.6256282 -0.7379937 -0.3493636 0.007206916 -0.9369596 -0.242701 0.8839875 -0.3995779 -0.03795099 0.4370372 -0.8986425 0.05744391 -0.9884884 -0.1399675 0.03050875 -0.9982701 -0.05025976 0.02689558 -0.999305 -0.02581018 0.347868 0.922589 -0.1667859 0.766244 0.613571 -0.1907897 0.3231461 0.9463467 -0.002185523 0.6069521 -0.7206462 0.3350793 0.6449756 -0.6872506 0.3342053 0.4593169 -0.7280138 0.5089441 0.5100305 -0.6851283 0.5200655 0.31225 -0.6674851 0.6759908 0.2839728 -0.6977435 0.6576576 0.103692 -0.7100653 0.6964591 0.06909406 -0.6462858 0.759961 -0.1124809 -0.7430664 0.6596972 -0.2539913 -0.6151654 0.7463645 -0.279728 -0.7109042 0.6452654 -0.4562465 -0.7289421 0.510375 -0.5256532 -0.661008 0.5354973 -0.648146 -0.690148 0.3218736 -0.6166227 -0.7380812 0.2738847 -0.7539916 -0.6477115 0.1093919 -0.6389178 -0.7692024 0.01057749 -0.7539117 -0.6387506 -0.1536712 1.77245e-6 1 -1.37269e-6 -4.74138e-6 1 -2.4161e-5 1.37109e-5 1 2.08075e-5 1.17976e-5 1 -2.31644e-6 8.40891e-6 1 -7.69938e-6 1.67066e-5 1 8.73074e-6 1.22051e-5 1 -4.33319e-7 -2.98162e-6 1 -8.07316e-6 9.6488e-6 1 -9.52684e-6 1.16344e-5 1 4.25618e-6 2.31308e-6 1 -5.72402e-6 9.36856e-6 1 -1.31307e-6 5.57056e-6 1 3.56816e-6 -8.28294e-6 1 -4.38016e-6 4.6505e-6 1 3.73623e-6 -3.12514e-7 1 -5.72165e-6 8.17489e-6 1 -5.18663e-6 -3.2614e-5 1 -1.05632e-5 -5.62652e-6 1 1.01595e-5 -9.651e-6 1 -2.02445e-5 3.23886e-5 1 -2.47075e-5 -2.3295e-5 1 1.71943e-5 7.85054e-6 1 2.04282e-5 -1.93465e-5 1 8.65231e-6 -8.72829e-6 1 -8.20294e-6 0 1 6.02992e-6 2.96082e-5 1 1.59078e-5 -3.35322e-5 1 1.40332e-5 5.84863e-6 1 6.21636e-6 -9.05045e-7 1 3.43518e-6 -2.7681e-5 1 -8.19877e-6 -8.48155e-6 1 1.75672e-6 -5.22831e-6 1 -4.43154e-5 -3.36637e-6 1 4.67398e-6 -3.94598e-5 1 -1.09729e-5 -6.01145e-6 1 0 -7.55012e-6 1 6.09198e-6 -2.07303e-5 1 1.47857e-5 -2.13925e-6 1 8.12876e-7 -1.11947e-5 1 -1.39693e-5 1.61533e-5 1 4.81071e-5 0.9307145 -0.02438551 0.3649327 0.8866893 0.01852339 0.4619945 0.7510303 -0.01061654 0.6601825 0.7554698 -0.01483488 0.6550157 0.5918934 0.01767933 0.8058223 0.485751 -0.02777242 0.873656 0.3743946 0.0219379 0.9270099 0.1739887 -0.01935893 0.9845574 0.1011878 0.01423001 0.9947656 -0.07516729 -0.01077592 0.9971128 -0.1639372 0.0157507 0.9863451 -0.263234 -0.01504838 0.9646148 -0.4246252 0.01666879 0.9052159 -0.5018277 -0.0146268 0.8648439 -0.6220965 0.01485121 0.7827997 -0.6934812 -0.01777738 0.7202555 -0.8006763 0.01482391 0.5989139 -0.8545027 -0.01266372 0.5192925 -0.8994386 0.01015281 0.4369294 -0.9478889 -0.01427108 0.3182815 -0.9736222 0.01389086 0.2277435 -0.9964655 -0.01241898 0.08307939 -0.9993162 0.00450617 0.03670203 -0.9896589 0.001554191 -0.1434323 -0.9884737 -0.002154529 -0.1513776 -0.9419053 -0.004098773 -0.3358538 0.6696414 0.6556258 0.3489058 0.532382 0.7808601 0.326844 0.5822212 0.6317163 0.5118137 0.4333039 0.7558187 0.4909034 0.4467895 0.6560618 0.6082451 0.2986371 0.764837 0.5708243 0.2977894 0.6064106 0.737284 0.1110832 0.7697832 0.6285654 0.07731902 0.6449041 0.7603424 -0.05516391 0.7479634 0.6614437 -0.1267989 0.6337975 0.7630354 -0.1902036 0.7642171 0.616275 -0.3276674 0.6362616 0.6984306 -0.3361821 0.7510608 0.5682337 -0.47675 0.6424552 0.5999674 -0.4451596 0.7682417 0.4600409 -0.6174662 0.63677 0.4618003 -0.5692773 0.749374 0.3381745 -0.6705409 0.6670841 0.3246132 -0.6235881 0.7551674 0.2021391 -0.7417867 0.6471334 0.1759858 -0.6662286 0.7454121 0.0223661 -0.6710524 0.741117 0.02084273 -0.7583037 0.642965 -0.107571 -0.6139733 0.772602 -0.1616266 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.002103626 0.05712109 -7.31706e-4 -0.002141177 0.05710804 -7.93526e-4 -0.002154469 0.05708664 -8.80894e-4 -0.001806735 0.05712151 -0.001285851 -0.00200361 0.05711191 -0.001071095 -0.002253472 0.05706214 -7.14746e-4 -0.00223726 0.0570361 -8.41124e-4 -0.00223726 0.05699539 -9.14735e-4 -0.002093851 0.05708098 -0.001036345 -0.0023216 0.0569573 -7.42367e-4 -0.002264559 0.05691599 -9.2546e-4 -0.002171754 0.05702131 -0.001020014 -0.002327859 0.05690568 -7.63806e-4 -0.002182841 0.05695039 -0.001081109 -0.002090632 0.05705296 -0.001114666 -0.001877009 0.0571109 -0.001277863 -0.002125144 0.05700588 -0.001133441 -0.002185463 0.05689597 -0.001100778 -0.001980781 0.05707788 -0.001245021 -0.002012491 0.05703514 -0.001281797 -0.002049803 0.05696719 -0.001301407 -0.00209552 0.05690401 -0.001258373 -0.00177288 0.05709099 -0.001490831 -0.001958489 0.05701673 -0.00138694 -0.001854062 0.05706739 -0.001445829 -0.001717805 0.05711382 -0.001468956 -0.001992225 0.05689913 -0.001416265 -0.001941382 0.05696964 -0.001454055 -0.001775741 0.0570513 -0.001568496 -0.001817822 0.05699735 -0.001584291 -0.001459538 0.05712133 -0.001665353 -0.001472592 0.05711191 -0.00172466 -0.001877009 0.05691593 -0.001561105 -0.001589655 0.05708438 -0.00169897 -0.001794159 0.05692195 -0.001654088 -0.001619338 0.0570392 -0.001745402 -0.001641392 0.05697172 -0.001783907 -0.001708269 0.05690997 -0.00174421 -0.001374959 0.05707585 -0.001894831 -0.001175761 0.05711776 -0.001909732 -0.00148946 0.05702608 -0.001870393 -0.001300811 0.05709642 -0.001903593 -0.001563251 0.05690681 -0.001876652 -8.62569e-4 0.05712133 -0.0020473 -0.001455783 0.05697685 -0.001935005 -0.001345813 0.05702096 -0.001981735 -0.001236915 0.05704736 -0.002025306 -0.001422464 0.05690997 -0.001984477 -0.00115776 0.05708104 -0.002024352 -0.001269102 0.05696219 -0.002070546 -0.001056432 0.0571112 -0.002010047 -0.00113511 0.05700773 -0.002121567 -0.001263082 0.05690157 -0.002092003 -9.30797e-4 0.05709576 -0.002113819 -0.001024305 0.05706125 -0.002126276 -0.001038193 0.05694198 -0.002204656 -7.09291e-4 0.05711132 -0.002158999 -9.7743e-4 0.05701208 -0.002196371 -0.001052021 0.05689173 -0.002207815 -3.3861e-4 0.05712121 -0.002202153 -7.71052e-4 0.05708301 -0.002201199 -7.78963e-4 0.05704343 -0.002250373 -8.63333e-4 0.05699479 -0.002256631 -4.81167e-4 0.05711048 -0.002227008 -8.772e-4 0.05690997 -0.002282202 -5.42929e-4 0.05708688 -0.00226432 -7.56727e-4 0.05696874 -0.002308607 -6.18363e-4 0.05706042 -0.002282023 -6.29844e-4 0.05699485 -0.002334952 -6.92001e-4 0.05690652 -0.002347946 -4.40672e-4 0.05704963 -0.002337098 -5.09426e-4 0.05700671 -0.002357482 -3.43492e-4 0.05708366 -0.002311408 -1.54981e-4 0.05710983 -0.002280592 -5.18227e-4 0.05694442 -0.002384543 -3.2536e-4 0.05700898 -0.002390921 -4.49253e-4 0.05690222 -0.002409338 4.44513e-4 0.05712163 -0.002194404 -2.15955e-4 0.0570656 -0.002354323 -3.28904e-4 0.05695784 -0.002416431 2.55872e-4 0.05711805 -0.002248108 -8.23575e-5 0.0570566 -0.002374231 3.81163e-5 0.05709642 -0.002320766 -7.61027e-5 0.0570169 -0.002409934 -2.15124e-4 0.05689555 -0.002444863 -1.52322e-4 0.05695724 -0.002436459 3.77654e-5 0.05696302 -0.002441525 9.61926e-5 0.05705016 -0.002382814 2.58815e-4 0.05709421 -0.002314507 3.5614e-5 0.05690413 -0.002457082 1.61732e-4 0.05700808 -0.002415418 2.73961e-4 0.05705749 -0.002364695 2.23772e-4 0.05694943 -0.002439141 4.79858e-4 0.05709409 -0.002283394 3.94891e-4 0.05701869 -0.002385139 2.84675e-4 0.05689227 -0.002445638 4.0226e-4 0.05695772 -0.002417385 7.03831e-4 0.05711376 -0.002176702 4.58445e-4 0.05705231 -0.002344131 6.32226e-4 0.05707359 -0.002282619 6.26788e-4 0.05703097 -0.002329528 7.97369e-4 0.05709719 -0.00219357 4.69381e-4 0.05689799 -0.002419233 6.51342e-4 0.05698776 -0.002353072 5.91129e-4 0.05691593 -0.002393126 9.69048e-4 0.05711936 -0.00205177 8.58682e-4 0.05705147 -0.002240061 7.11844e-4 0.05691599 -0.002362549 8.71244e-4 0.05699187 -0.002284109 9.80195e-4 0.05706608 -0.002174317 8.33051e-4 0.05690896 -0.002325952 0.001077711 0.05709373 -0.00208491 0.001217544 0.05711162 -0.001960515 9.50229e-4 0.05691689 -0.0022825 0.001105725 0.05701196 -0.002172589 0.001498341 0.0571208 -0.001715421 0.001057744 0.05696016 -0.002223372 0.001145899 0.05704331 -0.002123653 0.001064777 0.0568971 -0.002236068 0.001276671 0.05708378 -0.001994848 0.001229643 0.05694741 -0.00214374 0.001409173 0.05710893 -0.001843333 0.001306056 0.0570513 -0.00202465 0.001311957 0.05701303 -0.002059102 0.00123316 0.05689084 -0.002153694 0.001539111 0.05708336 -0.001812398 0.001480817 0.05706793 -0.001883387 0.001385688 0.05696094 -0.002044618 0.001517117 0.05703723 -0.001896381 0.001451432 0.05690675 -0.00201869 0.001537024 0.05698132 -0.001928985 0.001689732 0.05711871 -0.001550555 0.001674354 0.05710268 -0.001641511 0.001698017 0.05704158 -0.001738727 0.001593828 0.05690401 -0.001912772 0.001666188 0.05699998 -0.001808643 0.002075016 0.05712157 -9.58378e-4 0.00175029 0.05707931 -0.001626253 0.001735746 0.0569455 -0.001779079 0.001733005 0.05689609 -0.001795172 0.001809418 0.05699211 -0.001679301 0.001952826 0.05711948 -0.001215815 0.001903414 0.05710536 -0.001374423 0.001854538 0.05704891 -0.001568794 0.001937627 0.05708616 -0.001394033 0.001868605 0.05691683 -0.001656353 0.001925766 0.0569992 -0.001544713 0.002014279 0.05704355 -0.001376986 0.001951038 0.05691492 -0.001563251 0.002042174 0.05698752 -0.00140661 0.00202775 0.05690991 -0.001468062 0.002096652 0.05708396 -0.001160204 0.002067267 0.05711174 -0.001089215 0.002122282 0.05703097 -0.001233875 0.00210011 0.05691564 -0.001366376 0.002181589 0.05697888 -0.001198649 0.002188086 0.05706328 -0.001050591 0.002167403 0.05690932 -0.001264035 0.002209901 0.05709779 -8.81326e-4 0.002233505 0.05701035 -0.001067757 0.002248704 0.05711132 -6.82316e-4 0.002231299 0.05691492 -0.001152276 0.002283573 0.05708098 -7.75642e-4 0.002301156 0.0570445 -8.4741e-4 0.002286851 0.05691754 -0.00104314 0.002332329 0.05699318 -8.73216e-4 0.002233386 0.05712121 -5.56432e-4 0.002338349 0.05690932 -9.32053e-4 0.002316415 0.05711323 -3.94298e-4 0.002383291 0.05692201 -8.13977e-4 0.002377331 0.05704706 -6.12028e-4 0.002396106 0.05699497 -6.90144e-4 0.002363443 0.05708241 -4.94218e-4 0.002424359 0.05690962 -6.96142e-4 0.002448081 0.05699068 -5.05533e-4 0.002308845 0.05712157 1.35862e-4 0.002340376 0.05711591 -1.27137e-4 0.002456426 0.05692136 -5.78588e-4 0.002427875 0.05703628 -4.4525e-4 0.002390623 0.05709439 -2.2074e-4 0.002438485 0.0570563 -2.63427e-4 0.002486526 0.05690896 -4.53138e-4 0.002475321 0.05700081 -3.27232e-4 0.002507448 0.05691689 -3.29943e-4 0.002476155 0.05702978 -1.39148e-4 0.002438127 0.05707204 -2.32605e-5 0.002507567 0.05696696 -2.09276e-4 0.002530872 0.05689805 -1.43391e-4 0.002414047 0.05708688 1.82717e-4 0.002515971 0.05696958 -8.35326e-5 0.002358615 0.05711203 1.32102e-4 0.002474248 0.05703997 9.11874e-5 0.002515137 0.05697697 1.02949e-4 0.002535521 0.05691492 4.221e-5 0.002339959 0.0571075 4.45948e-4 0.002488136 0.05701297 2.30702e-4 0.002441942 0.05705302 3.47014e-4 0.002533078 0.05690997 1.64317e-4 0.002385258 0.05708414 4.56698e-4 0.002508699 0.05696332 2.87377e-4 0.002273559 0.05711764 5.84398e-4 0.002524197 0.05690485 2.90392e-4 0.002475082 0.05700254 4.07456e-4 0.002432823 0.05703181 5.27827e-4 0.002507448 0.05691689 4.14555e-4 0.002350389 0.05708265 6.29045e-4 0.002473831 0.05696117 5.305e-4 0.002155363 0.05711328 9.91217e-4 0.002384245 0.05703842 7.05684e-4 0.00228548 0.05709296 7.93328e-4 0.002487838 0.05689769 5.35361e-4 0.00241959 0.05698269 7.16584e-4 0.00229907 0.057051 9.19842e-4 0.00245881 0.05691623 6.56547e-4 0.002333164 0.05700629 9.33819e-4 0.0023548 0.05694675 9.54607e-4 0.002425134 0.05691087 7.78297e-4 0.00236541 0.05689084 9.55541e-4 -0.002264857 3.33434e-4 -9.26291e-4 -0.002310156 3.31915e-4 -8.0994e-4 -0.002272486 2.66334e-4 -8.53476e-4 -0.002245724 2.29753e-4 -8.64588e-4 -0.002187967 3.51074e-4 -0.001096367 -0.002180933 2.9518e-4 -0.001086592 -0.002170205 1.79552e-4 -9.2792e-4 -0.002255022 1.84789e-4 -7.25557e-4 -0.002150595 2.3562e-4 -0.001084089 -0.002146184 1.39421e-4 -8.14623e-4 -0.002123653 1.91814e-4 -0.001056373 -0.002079606 1.22243e-4 -7.95357e-4 -0.002062857 3.3941e-4 -0.001311957 -0.002069413 1.47138e-4 -0.001022875 -0.001988768 1.25392e-4 -0.001047074 -0.00205028 2.81601e-4 -0.001303493 -0.002032339 1.64496e-4 -0.00115478 -0.002052903 2.16956e-4 -0.001231551 -0.001992106 2.27271e-4 -0.001338422 -0.001923143 3.36685e-4 -0.001506984 -0.001907229 1.34977e-4 -0.00124675 -0.001926183 1.85969e-4 -0.001369178 -0.001898229 2.7832e-4 -0.001512885 -0.001858353 1.49841e-4 -0.001376688 -0.001883506 2.2741e-4 -0.001486301 -0.001797556 3.27486e-4 -0.001651465 -0.001784265 1.98394e-4 -0.001568078 -0.001726269 2.42632e-4 -0.001680433 -0.001709282 1.63082e-4 -0.001590013 -0.001706838 3.21458e-4 -0.001743733 -0.001698553 1.23068e-4 -0.001448929 -0.001676619 1.47585e-4 -0.001583695 -0.00161612 3.27434e-4 -0.001828968 -0.001611709 1.97368e-4 -0.001742362 -0.001597225 2.4806e-4 -0.001806557 -0.00152117 3.33439e-4 -0.001909554 -0.001502871 1.3002e-4 -0.001687645 -0.001460969 2.59987e-4 -0.001927256 -0.00150913 1.658e-4 -0.00178337 -0.001392126 1.22149e-4 -0.001729309 -0.00142157 3.27443e-4 -0.001984357 -0.00148344 2.0302e-4 -0.00186026 -0.001427054 1.48558e-4 -0.001815319 -0.001275658 3.43238e-4 -0.002084434 -0.001338601 1.89282e-4 -0.00195229 -0.001250267 2.83106e-4 -0.002083301 -0.001244723 2.23133e-4 -0.002047955 -0.001201868 1.29554e-4 -0.001916289 -0.001057028 3.3692e-4 -0.002204298 -0.00120294 1.44316e-4 -0.001960158 -0.001113653 1.7306e-4 -0.002067744 -0.001040339 2.80861e-4 -0.002195835 -0.001029491 2.3097e-4 -0.00217235 -8.27636e-4 3.36651e-4 -0.002302229 -9.78574e-4 1.49961e-4 -0.002096533 -9.0717e-4 1.9862e-4 -0.002198517 -8.70204e-4 2.58138e-4 -0.002258658 -8.31173e-4 1.2222e-4 -0.002063393 -7.5507e-4 2.75609e-4 -0.00230962 -7.97262e-4 1.31756e-4 -0.002125918 -7.74462e-4 1.58668e-4 -0.002198934 -5.81204e-4 3.51117e-4 -0.002380013 -7.42881e-4 2.1274e-4 -0.002273201 -6.40301e-4 2.9999e-4 -0.002353549 -5.67273e-4 2.34129e-4 -0.00234282 -4.6152e-4 2.98927e-4 -0.002397596 -5.63821e-4 1.81832e-4 -0.002295851 -5.08159e-4 1.51034e-4 -0.002264142 -3.36894e-4 3.51056e-4 -0.002429604 -4.14798e-4 1.31312e-4 -0.002237081 -3.35184e-4 2.38253e-4 -0.002392113 -2.73892e-4 2.93011e-4 -0.002426207 -3.85562e-4 1.85555e-4 -0.002338886 -2.11083e-4 1.22513e-4 -0.002224445 -9.06113e-5 3.4429e-4 -0.002454161 -8.14438e-5 2.76667e-4 -0.002437829 -1.85947e-4 2.04408e-4 -0.002385616 -2.02588e-4 1.56755e-4 -0.002324938 1.60341e-4 3.51147e-4 -0.002454817 4.21789e-5 2.26615e-4 -0.002412676 9.9718e-5 2.93877e-4 -0.002445399 -9.73791e-5 1.33222e-4 -0.002280473 -2.5142e-5 1.77959e-4 -0.002365708 4.61527e-5 1.53048e-4 -0.002331078 2.79111e-4 2.89654e-4 -0.002433538 1.60056e-4 1.87013e-4 -0.002374529 2.71547e-4 2.34078e-4 -0.002406537 3.46729e-4 3.45356e-4 -0.002437591 4.69678e-4 3.27498e-4 -0.002417564 2.27642e-4 1.44144e-4 -0.00230664 2.55181e-4 1.28114e-4 -0.002258598 2.81524e-4 1.62715e-4 -0.002333939 3.98944e-4 2.0293e-4 -0.002366423 5.22967e-4 2.59862e-4 -0.002384662 6.39714e-4 3.37052e-4 -0.002383351 5.1614e-4 1.81768e-4 -0.002324104 5.35115e-4 1.21665e-4 -0.002177 8.31453e-4 3.27462e-4 -0.002325773 6.61433e-4 2.17673e-4 -0.002326011 5.08676e-4 1.53762e-4 -0.002284169 7.11644e-4 2.93859e-4 -0.002353191 5.40694e-4 1.32695e-4 -0.00222969 8.1801e-4 2.41758e-4 -0.002295911 6.72615e-4 1.53413e-4 -0.002246081 9.47386e-4 3.40411e-4 -0.002285003 0.001063406 3.27472e-4 -0.002234935 8.57823e-4 1.84672e-4 -0.002231538 9.43645e-4 2.70832e-4 -0.002265989 8.37288e-4 1.56071e-4 -0.002197384 0.001175224 3.21452e-4 -0.002180397 9.79737e-4 2.0365e-4 -0.002205312 8.28974e-4 1.32075e-4 -0.002142906 0.001106619 2.43132e-4 -0.002180218 0.001099288 1.50993e-4 -0.00207746 0.001006722 1.26857e-4 -0.002050399 0.001334965 3.35714e-4 -0.002093851 0.001188278 1.81746e-4 -0.002080202 0.001273989 2.64528e-4 -0.002103567 0.001494586 3.3343e-4 -0.001987099 0.001323521 2.27441e-4 -0.002049982 0.001431763 2.7654e-4 -0.002011656 0.001593112 3.21421e-4 -0.001910924 0.001308679 1.33728e-4 -0.00191158 0.001378715 1.72349e-4 -0.001952707 0.001531064 2.28887e-4 -0.001908957 0.001727044 3.37123e-4 -0.001799643 0.001577615 1.74585e-4 -0.001805722 0.001715362 2.52782e-4 -0.001772999 0.001458287 1.22637e-4 -0.0017488 0.001655399 2.17382e-4 -0.001794755 0.001543343 1.44459e-4 -0.001770079 0.001818716 2.96968e-4 -0.001697838 0.001910984 3.51121e-4 -0.001613676 0.001778542 1.98706e-4 -0.001656234 0.001887023 2.48223e-4 -0.001592934 0.001742243 1.51775e-4 -0.001608014 0.001943707 2.98991e-4 -0.001559793 0.001721858 1.2331e-4 -0.001508414 0.002061426 3.38178e-4 -0.001424729 0.001950263 2.1358e-4 -0.001481056 0.002057731 2.71684e-4 -0.001398086 0.001926541 1.81353e-4 -0.001459717 0.001894414 1.5265e-4 -0.001434266 0.002169311 3.32812e-4 -0.00126034 0.001846969 1.32018e-4 -0.001415312 0.002090334 2.12657e-4 -0.001285135 0.002178609 2.58362e-4 -0.00119841 0.002040147 1.60289e-4 -0.001256763 0.002230405 3.27512e-4 -0.001153707 0.002035558 1.32417e-4 -0.001150071 0.002287864 3.22094e-4 -0.001040518 0.002176105 2.02685e-4 -0.001122415 0.0021739 1.69148e-4 -0.001049339 0.002251923 2.32146e-4 -0.001027047 0.002339243 3.26759e-4 -9.275e-4 0.002403974 3.37575e-4 -7.62847e-4 0.002095162 1.22953e-4 -9.58996e-4 0.002342104 2.5435e-4 -8.54129e-4 0.00220406 1.49101e-4 -9.11272e-4 0.002277195 1.99503e-4 -9.07164e-4 0.002457618 3.27754e-4 -5.76051e-4 0.002338826 1.97741e-4 -7.41154e-4 0.002423882 2.78118e-4 -6.45789e-4 0.00233823 1.73652e-4 -6.61464e-4 0.002213716 1.23122e-4 -6.5273e-4 0.002400398 2.24411e-4 -6.19331e-4 0.002254128 1.37424e-4 -7.0993e-4 0.002484977 3.26571e-4 -4.56744e-4 0.002518117 3.45335e-4 -2.70636e-4 0.00245583 2.46406e-4 -4.48689e-4 0.002359271 1.56017e-4 -4.77372e-4 0.002441227 2.05847e-4 -3.71031e-4 0.002492606 2.76416e-4 -3.27541e-4 0.002318322 1.32427e-4 -4.1557e-4 0.002518534 2.91041e-4 -1.44708e-4 0.002497255 2.45031e-4 -1.52535e-4 0.002400338 1.57839e-4 -2.63232e-4 0.002533376 3.40429e-4 -8.57608e-5 0.002457261 1.91882e-4 -1.28981e-4 0.00230515 1.21983e-4 -1.1844e-4 0.002537131 3.4874e-4 1.05871e-4 0.002527654 2.98951e-4 4.00044e-5 0.002355098 1.31106e-4 -9.65922e-5 0.002496719 2.3217e-4 3.95452e-5 0.00239861 1.47066e-4 -3.40786e-5 0.002515316 2.77996e-4 2.13147e-4 0.002448141 1.78622e-4 1.02553e-4 0.002523839 3.33494e-4 2.89203e-4 0.002507805 3.27476e-4 4.12766e-4 0.002479791 2.18752e-4 2.33439e-4 0.002393901 1.46842e-4 2.06448e-4 0.002316653 1.22688e-4 2.1675e-4 0.002425193 1.7488e-4 3.36656e-4 0.002470612 2.49054e-4 4.65574e-4 0.002475023 3.48749e-4 5.99959e-4 0.002434849 2.00451e-4 4.63432e-4 0.002478778 2.98946e-4 5.33394e-4 0.002426683 3.40399e-4 7.75419e-4 0.002358794 1.42203e-4 4.19368e-4 0.002432286 2.75674e-4 6.98034e-4 0.002300262 1.28471e-4 5.09612e-4 0.002371311 1.6632e-4 5.83017e-4 0.002386689 3.32576e-4 8.92984e-4 0.002399623 2.27269e-4 7.14822e-4 0.002346336 2.65598e-4 9.42212e-4 0.002309203 2.12952e-4 9.47479e-4 0.00229597 1.46632e-4 7.36682e-4 0.002326071 1.80806e-4 8.08742e-4 0.002218902 1.23921e-4 7.43546e-4 0.001966476 1.21999e-4 0.001247644 0.002318859 3.35703e-4 0.001063585 0.002201557 3.47248e-4 0.001294791 0.002071976 3.47469e-4 0.001495838 0.00195384 3.26551e-4 0.001644372 0.001871705 3.28458e-4 0.001738071 0.001784801 3.26568e-4 0.00182718 0.001646101 3.39416e-4 0.001955747 0.001447856 3.45415e-4 0.002106726 0.00129038 3.3861e-4 0.002204418 0.00112462 3.51193e-4 0.002294063 9.52066e-4 3.27471e-4 0.002366602 7.68251e-4 3.36532e-4 0.002432465 5.44345e-4 3.42496e-4 0.002490222 3.52263e-4 3.38585e-4 0.002521157 2.26449e-4 3.27427e-4 0.00253278 1.02063e-4 3.27421e-4 0.002539098 -2.05302e-5 3.34475e-4 0.002539932 -1.44003e-4 3.20514e-4 0.002532482 -2.68852e-4 3.34448e-4 0.002521753 -3.93969e-4 3.2749e-4 0.002502322 -5.14126e-4 3.32569e-4 0.002478718 -6.97009e-4 3.51136e-4 0.002432167 -9.22373e-4 3.36707e-4 0.002349793 -0.001098155 3.32579e-4 0.002267181 -0.001263797 3.45349e-4 0.002176642 -0.001418888 3.33512e-4 0.002071857 -0.001517891 3.27507e-4 0.001996219 -0.001613616 3.50488e-4 0.001918435 -0.001746535 3.47925e-4 0.001793324 -0.001874446 3.46302e-4 0.001651346 -0.001989781 3.49826e-4 0.001505017 -0.002092242 3.38546e-4 0.001348435 -0.002184212 3.45304e-4 0.001187741 -0.00226283 3.27458e-4 0.001014292 -0.002309024 3.33449e-4 8.9857e-4 -0.00236833 3.5113e-4 7.21647e-4 -0.002410948 3.44524e-4 5.40911e-4 -0.002442657 3.51111e-4 3.55539e-4 -0.002461552 3.5259e-4 1.08791e-4 -0.002455472 3.36868e-4 -1.30173e-4 -0.002432703 3.33424e-4 -3.2809e-4 -0.002409815 3.21442e-4 -4.50559e-4 -0.002384424 3.38598e-4 -5.70571e-4 -0.002349436 3.27188e-4 -6.91715e-4 6.16809e-4 0.05712133 0.002244293 -4.02373e-4 0.05712145 0.002272248 0.001778006 0.05712175 0.001502513 0.002155303 0.05712157 8.48097e-4 -0.001312434 0.05712133 0.00187385 -0.002038478 0.05712145 9.66941e-4 -0.002239167 0.05712157 3.70077e-6 0.001149773 1.22147e-4 0.002031505 -6.71729e-4 1.21817e-4 0.002198576 0.002246975 2.63404e-4 0.001162946 0.002221286 1.64528e-4 0.001018106 0.002237379 2.07842e-4 0.001098453 0.002175569 1.4022e-4 0.001009345 0.002225577 2.99006e-4 0.001231074 0.002119839 1.25788e-4 0.00101602 0.00215137 2.11013e-4 0.001267492 0.002157092 2.75559e-4 0.001334369 0.002113997 1.64221e-4 0.001230478 0.002053797 1.35135e-4 0.001216769 0.002090096 2.75603e-4 0.001438438 0.002022743 2.16607e-4 0.001475691 0.002022743 2.93013e-4 0.001542806 0.001981616 1.69033e-4 0.001446604 0.001919329 1.34701e-4 0.001424074 0.001927793 2.42608e-4 0.001625359 0.001890957 1.86586e-4 0.001597106 0.001843035 2.37869e-4 0.001718103 0.001823186 1.53464e-4 0.001605927 0.001761496 1.32243e-4 0.00160408 0.001766264 1.81747e-4 0.001727998 0.001758813 2.41709e-4 0.001806974 0.00167638 1.22724e-4 0.001624882 0.001679599 2.59575e-4 0.001894593 0.00162208 1.45636e-4 0.001792132 0.001610934 1.94867e-4 0.001891851 0.001535832 2.85119e-4 0.00202614 0.001568257 1.62093e-4 0.001875281 0.001529753 2.34593e-4 0.001998782 0.00138688 1.29663e-4 0.001928627 0.001451671 1.89367e-4 0.002009093 0.001348972 2.76933e-4 0.002151012 0.001372456 1.55259e-4 0.002008676 0.001301884 2.20805e-4 0.002142429 0.00129646 1.73654e-4 0.002091169 0.001128256 2.90258e-4 0.002278864 0.001112103 2.09714e-4 0.002235889 0.001129925 1.36132e-4 0.002108752 0.001087427 1.65209e-4 0.002192318 9.93953e-4 2.51507e-4 0.002320408 9.50791e-4 1.52749e-4 0.002232313 8.80547e-4 1.965e-4 0.00232172 8.31375e-4 2.81432e-4 0.002396225 7.60994e-4 2.30415e-4 0.002390861 7.90868e-4 1.32299e-4 0.002242803 6.51797e-4 2.75718e-4 0.002447307 7.48478e-4 1.55933e-4 0.002311706 6.44462e-4 1.84734e-4 0.002382457 7.13789e-4 1.21997e-4 0.002209305 5.86816e-4 2.27264e-4 0.002435266 4.21002e-4 2.90323e-4 0.002500593 4.97074e-4 1.2949e-4 0.002312064 4.02421e-4 2.33991e-4 0.002475202 5.05974e-4 1.51034e-4 0.002365052 4.6398e-4 1.90772e-4 0.002428293 2.73282e-4 1.88299e-4 0.002452135 2.27184e-4 2.4347e-4 0.00250101 2.48418e-4 1.22219e-4 0.002312481 3.13775e-4 1.49876e-4 0.002394199 4.30973e-5 2.59593e-4 0.002517402 1.50534e-4 1.589e-4 0.002422153 9.83384e-5 1.98024e-4 0.002472519 5.13086e-5 1.34508e-4 0.002375721 -8.9732e-5 2.30726e-4 0.002497255 -1.63501e-5 1.74598e-4 0.00244683 -1.90856e-4 1.83789e-4 0.002447783 -3.27639e-4 2.64383e-4 0.002492249 -1.97567e-4 1.47614e-4 0.00239408 -2.6444e-4 2.22437e-4 0.002474904 -2.16602e-4 1.25607e-4 0.002326548 -4.39163e-4 2.1975e-4 0.002445042 -4.40516e-4 1.81607e-4 0.002408564 -5.12535e-4 2.63675e-4 0.002456426 -3.85575e-4 1.39751e-4 0.002350032 -6.3349e-4 2.87065e-4 0.002436637 -5.79636e-4 1.65947e-4 0.002356171 -6.91495e-4 2.24605e-4 0.002385199 -7.52316e-4 2.91236e-4 0.002401113 -6.38728e-4 1.293e-4 0.002257704 -7.86027e-4 1.855e-4 0.002315938 -9.35998e-4 2.84136e-4 0.002329051 -9.09106e-4 2.35148e-4 0.002313554 -7.93461e-4 1.51442e-4 0.002262592 -0.001021027 1.96093e-4 0.002229213 -0.001090347 2.58015e-4 0.002243578 -9.9205e-4 1.55999e-4 0.002186 -9.75607e-4 1.2733e-4 0.002117335 -0.001246809 2.79553e-4 0.002168536 -0.001243472 2.26305e-4 0.00213623 -0.001234173 1.87866e-4 0.002102494 -0.0012483 1.54656e-4 0.002041459 -0.001253485 1.32339e-4 0.001978158 -0.001452982 2.58599e-4 0.002017259 -0.001414656 2.04167e-4 0.001999795 -0.001291811 1.22073e-4 0.001883983 -0.001606404 2.9122e-4 0.001908957 -0.001395642 1.30265e-4 0.001863539 -0.001511693 1.81877e-4 0.001893818 -0.001586437 2.30974e-4 0.001886188 -0.001492142 1.5338e-4 0.001857519 -0.001746952 2.963e-4 0.001778066 -0.001722455 2.44845e-4 0.001770377 -0.001589059 1.39823e-4 0.001733839 -0.001695036 1.89852e-4 0.001737654 -0.001910924 2.963e-4 0.001591622 -0.001779139 1.86273e-4 0.001639544 -0.001598298 1.23223e-4 0.001635253 -0.001884996 2.38171e-4 0.001581609 -0.001752138 1.59022e-4 0.001616001 -0.001793026 1.3363e-4 0.001483321 -0.002015113 2.87095e-4 0.001445114 -0.001898348 1.70719e-4 0.001463413 -0.002016425 2.24761e-4 0.0013839 -0.002117097 2.74314e-4 0.001273691 -0.00200361 1.93665e-4 0.001354515 -0.001886308 1.22025e-4 0.001258373 -0.001966416 1.51073e-4 0.001309812 -0.002129018 2.05588e-4 0.001161575 -0.0021981 2.77406e-4 0.00112158 -0.002002358 1.29271e-4 0.001136362 -0.002094745 1.59538e-4 0.001110732 -0.002238094 2.53589e-4 0.001004397 -0.002209782 1.93362e-4 9.58273e-4 -0.002281129 2.47695e-4 8.89447e-4 -0.002187192 1.62092e-4 9.08723e-4 -0.002141892 1.37284e-4 8.91948e-4 -0.002359271 2.95173e-4 7.14203e-4 -0.002331912 2.40933e-4 7.18523e-4 -0.002294421 1.9162e-4 7.07107e-4 -0.002147555 1.2239e-4 6.99967e-4 -0.002253413 1.50331e-4 6.44788e-4 -0.00241357 2.93441e-4 4.72648e-4 -0.00222063 1.31213e-4 5.82361e-4 -0.002389907 2.42771e-4 4.71673e-4 -0.00236386 2.06366e-4 4.65034e-4 -0.002326071 1.70402e-4 4.5661e-4 -0.002435386 2.86158e-4 2.94332e-4 -0.002394497 2.12356e-4 2.82038e-4 -0.00227946 1.34419e-4 3.15855e-4 -0.002452433 3.00864e-4 1.06755e-4 -0.002338171 1.62857e-4 2.85839e-4 -0.002425968 2.40621e-4 1.01208e-4 -0.002380967 1.86054e-4 1.0473e-4 -0.002334475 1.53117e-4 1.15908e-4 -0.002439975 2.83562e-4 -1.55788e-4 -0.002239823 1.2238e-4 6.32857e-5 -0.002408027 2.23584e-4 -1.41619e-4 -0.002362132 1.73642e-4 -1.1511e-4 -0.002287089 1.33088e-4 -9.09761e-5 -0.002398133 2.53982e-4 -3.79123e-4 -0.002321124 1.61538e-4 -3.3012e-4 -0.002370059 2.01603e-4 -3.1837e-4 -0.002231419 1.23577e-4 -2.63383e-4 -0.002273917 1.40094e-4 -3.55296e-4 -0.00233829 2.04608e-4 -4.99966e-4 -0.002363026 2.6439e-4 -5.66712e-4 -0.002271771 1.67232e-4 -5.93724e-4 -0.002320468 2.46405e-4 -6.82821e-4 -0.00221157 1.32169e-4 -5.54459e-4 0.002215623 0.05708241 0.001018822 0.00205928 0.05711722 0.001143574 0.002232968 0.05704003 0.001097619 0.002072513 0.05709916 0.001229465 0.002233147 0.05700069 0.001164376 0.002116084 0.05707544 0.001235008 0.002251744 0.05694818 0.001181006 0.002144753 0.05704444 0.001257002 0.002263784 0.05689227 0.001180946 0.001921772 0.05711436 0.001386582 0.001980423 0.05708247 0.001428902 0.002147674 0.05699014 0.0013296 0.002023398 0.05703729 0.001458883 0.00217086 0.05690997 0.001342833 0.00188589 0.05709737 0.001509368 0.00204885 0.05698454 0.001484394 0.001741528 0.05710846 0.001637995 0.002103388 0.05690997 0.001447558 0.001843214 0.05706441 0.001641452 0.002030313 0.05691593 0.001548349 0.001888871 0.0570079 0.001664698 0.001582682 0.0571177 0.001744866 0.001898527 0.05695152 0.0016945 0.001915991 0.05689698 0.001692354 0.001621067 0.05709636 0.001796662 0.001679301 0.0570544 0.001823902 0.001760482 0.05700087 0.001806139 0.001377463 0.05711138 0.001942813 0.001783549 0.05691599 0.001828491 0.001474499 0.05708366 0.001945495 0.001618504 0.05701607 0.001921057 0.001171171 0.05712133 0.002014279 0.001632332 0.05697935 0.001937747 0.001504004 0.05704998 0.001975893 0.001692771 0.05690997 0.001913785 0.001595318 0.05691492 0.001995027 0.001296043 0.05708134 0.002073109 0.001479804 0.05699098 0.002049148 0.001159131 0.05711185 0.002075612 0.001324236 0.0570271 0.002125263 0.001498281 0.05690997 0.002069175 0.001321792 0.05697596 0.002163052 0.001343131 0.05690395 0.00217396 0.001078426 0.05707764 0.002198398 9.77762e-4 0.0571103 0.002174258 0.001103699 0.05703312 0.002239882 0.001102626 0.05698454 0.002276122 0.001179575 0.05691593 0.002263665 8.60072e-4 0.05708259 0.00228244 6.16927e-4 0.05710995 0.00230056 8.72817e-4 0.05704778 0.00232321 0.001067638 0.05690991 0.002318441 9.41625e-4 0.05699545 0.002339065 8.8823e-4 0.05695557 0.002379119 7.62541e-4 0.05700135 0.002398848 8.88597e-4 0.0569027 0.002392709 6.85256e-4 0.05708467 0.002335309 6.4526e-4 0.05704253 0.002399384 5.20113e-4 0.05707514 0.002390027 7.14346e-4 0.05691689 0.002446472 3.89434e-4 0.05709826 0.002373754 5.23804e-4 0.05700188 0.00245881 5.40418e-4 0.05695277 0.002478778 4.04731e-4 0.05703985 0.002450764 5.32094e-4 0.05689811 0.002492904 2.7538e-4 0.05706548 0.002440273 1.41823e-4 0.05709707 0.002400875 3.47334e-4 0.0569899 0.002493977 1.40564e-4 0.05711841 0.002338588 3.48641e-4 0.05691492 0.00252062 1.66976e-4 0.05702424 0.002488136 1.58919e-4 0.05698221 0.002514898 4.39475e-5 0.05705612 0.002462625 2.27105e-4 0.05691599 0.00253272 -5.27252e-5 0.05709409 0.002408027 -2.17073e-4 0.05711209 0.002349495 1.00609e-4 0.05691087 0.002539694 -2.15298e-5 0.05701088 0.002499997 -1.92452e-4 0.05708038 0.002421259 -7.87265e-5 0.05696725 0.002522408 -1.9572e-4 0.05703765 0.002469778 -9.63406e-5 0.05690753 0.002537906 -4.82127e-4 0.05711108 0.00230956 -4.95577e-4 0.05708813 0.002360224 -3.27414e-4 0.05701482 0.002471029 -3.2393e-4 0.05697429 0.002495288 -4.38613e-4 0.05705398 0.002417743 -2.70347e-4 0.05690407 0.002521991 -7.34824e-4 0.05711054 0.002238571 -3.93329e-4 0.05691593 0.002502441 -5.73444e-4 0.05700391 0.002429127 -6.79194e-4 0.05704945 0.002361118 -5.80016e-4 0.05694609 0.002454459 -5.17195e-4 0.05689889 0.002479016 -8.2627e-4 0.05708146 0.002269506 -8.60214e-4 0.0571193 0.002150893 -7.96415e-4 0.05700653 0.002358734 -6.9696e-4 0.05689227 0.002432167 -7.53123e-4 0.05694442 0.00240314 -9.01782e-4 0.05705273 0.002276301 -9.20997e-4 0.05696243 0.002334237 -0.00101912 0.05710917 0.002121806 -0.001015841 0.05701202 0.002263903 -8.72615e-4 0.05690395 0.002369284 -0.001085162 0.05706721 0.002172172 -0.001183867 0.05709785 0.002059578 -0.00104314 0.05689549 0.002296626 -0.001095056 0.05695217 0.002256989 -0.001329183 0.05711114 0.001923859 -0.001223564 0.05704534 0.002120435 -0.001244008 0.05700916 0.00214219 -0.001308739 0.05707949 0.002017736 -0.001257777 0.05695044 0.002167463 -0.001266837 0.05689227 0.002175152 -0.001537263 0.05711477 0.001737356 -0.001383841 0.05704069 0.002019286 -0.001491129 0.0570833 0.001873314 -0.00140661 0.05697911 0.002054631 -0.001535058 0.05704289 0.001899242 -0.00141859 0.05690395 0.002072691 -0.001542568 0.0570057 0.001930713 -0.001510381 0.05694961 0.001990556 -0.001644492 0.05709826 0.001694262 -0.001572668 0.05689507 0.001954555 -0.001828491 0.05712056 0.00136137 -0.001677751 0.05707281 0.001719951 -0.001650273 0.05696308 0.00186479 -0.001667082 0.05703097 0.001793503 -0.001821756 0.05710649 0.001461565 -0.001785337 0.05704516 0.001650869 -0.001704633 0.05690997 0.001832485 -0.001812934 0.05700248 0.001669585 -0.00183022 0.05707925 0.001534938 -0.001784741 0.05695039 0.001736223 -0.001835286 0.05689227 0.001698315 -0.001903831 0.05695652 0.001596033 -0.001944839 0.05702781 0.001476824 -0.001963376 0.05708903 0.001321017 -0.001992821 0.05706059 0.001350283 -0.001983284 0.05711239 0.001184284 -0.001987516 0.05690211 0.001507222 -0.002042949 0.05696481 0.001398146 -0.002058863 0.05709958 0.00111562 -0.00208503 0.05702036 0.001269876 -0.002112925 0.05706226 0.001137733 -0.002123236 0.05690211 0.001298367 -0.002141058 0.05696785 0.001231014 -0.002142369 0.05711138 8.54581e-4 -0.002180874 0.05700176 0.001115918 -0.002156376 0.05708414 9.72573e-4 -0.002229511 0.05704009 9.33858e-4 -0.002228856 0.05694305 0.001074552 -0.002242624 0.05689728 0.001066565 -0.002258718 0.05699086 9.54614e-4 -0.002229273 0.05707865 8.0457e-4 -0.002252459 0.05709606 6.27375e-4 -0.002201557 0.05711835 5.50562e-4 -0.002307534 0.05692201 8.98702e-4 -0.002304553 0.05704009 7.13779e-4 -0.002339959 0.05698996 7.18197e-4 -0.002348542 0.05690997 7.81193e-4 -0.002319693 0.05707681 4.62892e-4 -0.002384781 0.05696505 5.90097e-4 -0.002279102 0.05711144 2.51096e-4 -0.002363383 0.05703562 4.77621e-4 -0.002399563 0.05689811 5.97581e-4 -0.002339899 0.05708396 2.29511e-4 -0.002396285 0.05701994 3.48452e-4 -0.002425014 0.05696696 3.52167e-4 -0.00244224 0.05690771 3.50406e-4 -0.00240904 0.0570271 1.20256e-4 -0.002316296 0.05709964 4.08161e-6 -0.00235641 0.05707669 -1.32843e-5 -0.002439141 0.05697679 1.12012e-4 -0.002270758 0.05711019 -2.75205e-4 -0.002457082 0.05690997 1.69466e-4 -0.002458989 0.05692201 4.48689e-5 -0.002383291 0.05704981 -1.31812e-4 -0.002317667 0.05708497 -3.17903e-4 -0.00243324 0.0569846 -7.87718e-5 -0.002210378 0.05711507 -4.96793e-4 -0.00245732 0.05690896 -8.16754e-5 -0.002411961 0.057006 -2.01035e-4 -0.002362787 0.05704933 -3.18435e-4 -0.00244683 0.05692195 -2.03694e-4 -0.002393305 0.05699759 -3.79514e-4 -0.002321064 0.05705744 -4.94965e-4 -0.002432167 0.05691599 -3.2738e-4 -0.002220451 0.05709433 -6.66104e-4 -0.002401232 0.05694937 -4.50657e-4 -0.002333998 0.05700618 -6.20781e-4 -0.002412438 0.05689233 -4.50637e-4 -0.002382397 0.05691689 -5.73751e-4 + + + + + + + + + + -0.4093827 0.8985885 -0.1579383 -0.5260063 0.8286974 -0.1912542 -0.5861223 0.7754168 -0.2349241 -0.1989754 0.976308 -0.08503884 -0.3659024 0.9152422 -0.1686632 -0.3805363 0.9068056 -0.1813723 -0.8106947 0.5122539 -0.2834966 -0.1144827 0.9915778 -0.06055861 -0.5906412 0.764544 -0.2581001 -0.8705574 0.34641 -0.3494711 -0.6197001 0.7303928 -0.2872251 -0.9065806 0.2511677 -0.3391553 -0.7473321 0.5813974 -0.3216706 -0.8012844 0.4572775 -0.3857986 -0.8599895 0.3462291 -0.3748914 -0.6197223 0.7306143 -0.2866133 -0.6757459 0.6404769 -0.3649069 -0.8853909 0.1957311 -0.4216306 -0.3925192 0.8915856 -0.2258405 -0.7972359 0.4605513 -0.3902662 -0.1600747 0.9817346 -0.102827 -0.5380512 0.7864568 -0.303293 -0.5821459 0.7336282 -0.350565 -0.6672189 0.640441 -0.3803345 -0.3592951 0.9058513 -0.2243668 -0.7239825 0.526274 -0.4459653 -0.1616716 0.9795735 -0.1195753 -0.796629 0.4033989 -0.4501684 -0.8323112 0.2744993 -0.4815685 -0.8530556 0.2138131 -0.4760045 -0.3671382 0.8922642 -0.2628197 -0.7158247 0.5257313 -0.4595668 -0.4202013 0.8529205 -0.3097701 -0.5502692 0.7404853 -0.3858566 -0.5763687 0.7016265 -0.4189504 -0.81289 0.2216135 -0.538607 -0.2933027 0.9278847 -0.2302252 -0.7269328 0.4610503 -0.5089218 -0.5838748 0.668597 -0.4605087 -0.7868502 0.2706026 -0.554654 -0.6086437 0.620392 -0.494638 -0.6751029 0.5118 -0.5313163 -0.09590524 0.9914852 -0.08808815 -0.451357 0.8010048 -0.393279 -0.1261186 0.9836807 -0.1283218 -0.7160997 0.3477334 -0.605213 -0.7724824 0.2430418 -0.586687 -0.2750269 0.9225862 -0.2705455 -0.2768803 0.9212958 -0.2730413 -0.4248341 0.8121868 -0.3998358 -0.454918 0.7657809 -0.4545649 -0.712281 0.3429009 -0.6124335 -0.5733591 0.6086203 -0.5484894 -0.5970889 0.5361033 -0.596723 -0.6676878 0.3816967 -0.6391407 -0.6729236 0.2914612 -0.6798707 -0.2872353 0.8902084 -0.3535888 -0.102687 0.9856716 -0.133817 -0.4128523 0.7704017 -0.4858336 -0.4312529 0.7336732 -0.5251139 -0.6511915 0.2428725 -0.7190011 -0.2881051 0.8897929 -0.3539269 -0.5536044 0.54215 -0.6321358 -0.03642803 0.9977155 -0.05689382 -0.5567364 0.495028 -0.6670771 -0.6039682 0.3171899 -0.7311725 -0.1749708 0.9520991 -0.250784 -0.4257702 0.6935724 -0.5810999 -0.50341 0.5405291 -0.674097 -0.5895459 0.2699804 -0.7612794 -0.1750239 0.9467004 -0.2704164 -0.4036789 0.7061786 -0.581683 -0.2159724 0.9033394 -0.370586 -0.2872499 0.8467777 -0.4477222 -0.4973381 0.4609709 -0.7349563 -0.08296769 0.9830726 -0.1633548 -0.3294341 0.7875789 -0.5207617 -0.5430472 0.3078737 -0.7812258 -0.5351378 0.2347485 -0.8114928 -0.2113488 0.89661 -0.3891302 -0.4186335 0.593944 -0.6870055 -0.2451418 0.8399468 -0.4841437 -0.4522538 0.5124938 -0.729943 -0.3179528 0.7618384 -0.5643655 -0.3528711 0.6730217 -0.6500183 -0.4393066 0.3804686 -0.8137896 -0.09214001 0.9725245 -0.2137904 -0.1263667 0.9474932 -0.2937486 -0.4691281 0.2535333 -0.845955 -0.3414472 0.6465777 -0.6821665 -0.4662303 0.183173 -0.8654924 -0.2282755 0.8128901 -0.5358173 -0.2395986 0.7745541 -0.5853703 -0.3951052 0.4377654 -0.8076221 -0.2903397 0.6810373 -0.6722285 -0.2963133 0.608657 -0.7360266 -0.1444334 0.9067333 -0.3961993 -0.3727918 0.4207286 -0.8270512 -0.04379022 0.9878574 -0.1490644 -0.3578044 0.3227102 -0.8762615 -0.1298004 0.9010762 -0.4137796 -0.1130059 0.9137139 -0.3903288 -0.4005445 0.1672994 -0.9008747 -0.2556068 0.5459782 -0.7978553 -0.1632351 0.8261321 -0.5393145 -0.1997563 0.7785878 -0.5948936 -0.0455935 0.9852468 -0.1649546 -0.3499785 0.3224226 -0.8795219 -0.2135747 0.6355715 -0.7419129 -0.3202628 0.2455287 -0.9149577 -0.2760083 0.5385318 -0.7961174 -0.1369863 0.7901972 -0.5973467 -0.2544332 0.3138023 -0.9147633 -0.2023763 0.6359251 -0.7447438 -0.1881129 0.6513282 -0.735109 -0.08602768 0.9003974 -0.4264785 -0.1253694 0.8003723 -0.5862481 -0.03470057 0.9742438 -0.2228115 -0.2070304 0.4138308 -0.8865001 -0.2612882 0.3181187 -0.9113336 -0.06295108 0.9169129 -0.3940916 -0.1490575 0.6094982 -0.7786489 -0.2387092 0.1717536 -0.9557818 -0.1651273 0.4489861 -0.8781483 -0.1031559 0.7697942 -0.6299014 -0.1797364 0.4127494 -0.8929349 -0.1784834 0.2653007 -0.9475016 -0.104133 0.6742474 -0.731127 -0.0412172 0.8715693 -0.4885368 -0.007064402 0.9871086 -0.1598964 -0.06674367 0.6616216 -0.7468616 -0.078489 0.6438899 -0.7610818 -0.1423025 0.1838032 -0.9726081 -0.04105389 0.871599 -0.4884975 1.38333e-4 0.9977207 -0.06748008 -0.08176916 0.4898235 -0.8679786 -0.02702087 0.8301185 -0.556932 -0.09909868 0.4492528 -0.8878915 0.004476964 0.95467 -0.2976329 -0.1084463 0.2417976 -0.9642476 -0.03755259 0.4450958 -0.8946953 2.27258e-4 0.8020765 -0.5972214 0.01893818 0.9413245 -0.3369712 -0.01168829 0.6676473 -0.744386 -0.03373616 0.2562305 -0.9660269 -0.05431842 0.1889122 -0.9804905 0.004801511 0.617168 -0.7868168 -0.001168072 0.5038992 -0.8637617 0.02457278 0.8125388 -0.5823891 0.02631556 0.8104457 -0.5852226 0.0494771 0.6587247 -0.7507555 0.0419439 0.4122072 -0.9101241 0.04762589 0.9408013 -0.3355962 0.03110903 0.2539424 -0.966719 0.07153999 0.6310194 -0.7724614 0.05325734 0.1689727 -0.9841809 0.09211999 0.4735105 -0.8759576 0.08098703 0.8158734 -0.5725309 0.08737218 0.4513018 -0.8880839 0.04492747 0.9737197 -0.2232744 0.08760446 0.8062069 -0.585112 0.09916615 0.6885867 -0.7183415 0.05582672 0.9545008 -0.2929365 0.1076615 0.2251358 -0.968361 0.1105889 0.8004726 -0.5890788 0.1501899 0.72297 -0.6743571 0.0963276 0.9231827 -0.3720954 0.1466683 0.6411995 -0.7532275 0.1208001 0.8811336 -0.4571774 0.1337557 0.1808778 -0.9743678 0.1684794 0.5430832 -0.8226028 0.1655419 0.4759573 -0.863748 0.1946169 0.3486798 -0.9168133 0.1724264 0.2238658 -0.9592462 0.03887563 0.9911326 -0.1270629 0.1837067 0.8110893 -0.5553252 0.2330205 0.3177202 -0.9191057 0.116079 0.9502537 -0.2890393 0.1961475 0.7143703 -0.6717153 0.2382041 0.6089695 -0.7565811 0.2373884 0.5647206 -0.7904034 0.196079 0.815981 -0.5438089 0.2744926 0.3495963 -0.8957881 0.2904908 0.3216654 -0.9011917 0.1293559 0.9437659 -0.3042581 0.1960427 0.8557198 -0.4788644 0.1352902 0.9480471 -0.2879294 0.3124168 0.3098664 -0.8979859 0.2941967 0.6607185 -0.6905791 0.2982368 0.6069421 -0.7366656 0.00962305 0.9997656 -0.01939594 0.3441908 0.4753553 -0.8096729 0.2756416 0.7911236 -0.5460269 0.3428079 0.3423765 -0.8747921 0.299279 0.6729539 -0.6764357 0.3987216 0.2234463 -0.889434 0.2121104 0.9052266 -0.3682039 0.07670569 0.9892006 -0.1248936 0.2830944 0.7945192 -0.5372123 0.4072653 0.418851 -0.8116027 0.3016621 0.7781955 -0.5508283 0.3749063 0.6517261 -0.6593167 0.4233921 0.2238665 -0.8778514 0.4376712 0.1822229 -0.8804765 0.3819337 0.6036808 -0.6997829 0.4242449 0.4675953 -0.7754811 0.1203631 0.9772953 -0.1743755 0.2257747 0.9097552 -0.3483841 0.2642654 0.8871611 -0.3782973 0.3029058 0.8485819 -0.4337706 0.457074 0.4301905 -0.7784727 0.3431521 0.7843289 -0.516793 0.3972299 0.714801 -0.5755589 0.4295864 0.6400973 -0.6369702 0.5093596 0.220252 -0.8318907 0.5078855 0.1798105 -0.8424491 0.4718664 0.5628523 -0.6786306 0.4873914 0.4883012 -0.7238865 0.5534464 0.3000644 -0.7769545 0.191717 0.9559444 -0.2222945 0.2527248 0.9186801 -0.3035739 0.434935 0.7356299 -0.5193075 0.4339093 0.737648 -0.5172988 0.1833426 0.9623194 -0.2008154 0.5791601 0.2637223 -0.7713781 0.5076791 0.6186965 -0.5995637 0.5198523 0.5602675 -0.6448673 0.03393054 0.9990636 -0.02685022 0.339989 0.8659316 -0.3668379 0.4185487 0.7844476 -0.4576672 0.5991237 0.3836526 -0.7027528 0.6088271 0.2926359 -0.737356 0.6382129 0.2060331 -0.7417781 0.569589 0.56577 -0.5962153 0.01882207 0.9996795 -0.01693123 0.6175891 0.4318646 -0.6573255 0.4758386 0.7431188 -0.4704807 0.2296127 0.9510936 -0.2066377 0.3346761 0.8944358 -0.2966087 0.3333123 0.8955516 -0.2947717 0.5661369 0.6157061 -0.5480831 0.4473427 0.8073577 -0.3847835 0.1776134 0.9738281 -0.1418177 0.6775366 0.3333698 -0.6555981 0.6879671 0.1898357 -0.700474 0.5956072 0.5888659 -0.5463415 0.6965153 0.3587216 -0.6214381 0.5114881 0.7579749 -0.4047886 0.7055093 0.3474273 -0.6176982 0.6046505 0.6310762 -0.4859431 0.6455056 0.582111 -0.4944384 0.7312411 0.3482774 -0.5865061 0.7453147 0.3232408 -0.5831136 0.2416106 0.9570499 -0.160249 0.3418204 0.9144104 -0.2168236 0.3663243 0.8988175 -0.2406941 0.5136394 0.7870366 -0.341684 0.5533307 0.7554172 -0.3509561 0.7679099 0.3038479 -0.563907 0.6751433 0.5778513 -0.4585515 0.7237928 0.5105683 -0.4641594 0.1578723 0.9839745 -0.08288991 0.5733507 0.746524 -0.3375958 0.7855598 0.3469094 -0.5123962 0.8022571 0.3136069 -0.5079706 0.6507002 0.672632 -0.352357 0.3774816 0.9045611 -0.1981846 0.7266584 0.5443745 -0.4190753 0.4726442 0.8495744 -0.2341597 0.1919074 0.9777758 -0.08441549 0.8248636 0.2885607 -0.4861408 0.26294 0.9577923 -0.1161746 0.5238061 0.818925 -0.2344979 0.152097 0.9865983 -0.0590797 0.5803965 0.7745912 -0.2512937 0.8310421 0.3670879 -0.4178703 0.8361999 0.335174 -0.4340831 0.6694784 0.6750308 -0.3100519 0.7310008 0.6037614 -0.317978 0.8384522 0.3780775 -0.3924987 0.8667192 0.3265025 -0.3770862 0.4081686 0.9020022 -0.1406789 0.197098 0.9789482 -0.05303794 0.6426704 0.7350621 -0.2160058 0.8736007 0.3197704 -0.366836 0.7354795 0.6317591 -0.2448478 0.7570609 0.5952004 -0.2694353 0.4338709 0.8918731 -0.1277438 0.8762282 0.3699826 -0.3087672 0.5831064 0.7945044 -0.1695579 0.9047299 0.3193896 -0.2818762 0.3912371 0.9150351 -0.09820568 0.7806064 0.5900406 -0.2061694 0.1380971 0.9901698 -0.02220559 0.8979268 0.3660921 -0.2443442 0.6474727 0.747606 -0.1478659 0.9055147 0.3194671 -0.2792564 0.7743014 0.6017599 -0.1958122 0.4197044 0.9040055 -0.08137822 0.09151375 0.9957481 -0.01053774 0.5684898 0.8174905 -0.09235078 0.6368761 0.7614086 -0.1210207 0.9297409 0.3144026 -0.1916587 0.3306502 0.9429454 -0.03904491 0.7618144 0.6375782 -0.1145992 0.8102665 0.5649491 -0.1558877 0.9200894 0.3571276 -0.1609205 0.9295176 0.3226846 -0.1785262 0.7720466 0.627642 -0.1000475 0.8508703 0.5186764 -0.08363413 0.5934306 0.8032218 -0.05171954 0.9219169 0.3574558 -0.1493141 0.674624 0.7366476 -0.0472514 0.3736011 0.9275068 -0.01239043 0.9673841 0.2336068 -0.0979588 0.4187818 0.9080574 -0.007327675 0.4600797 0.8878201 -0.01011717 0.859861 0.5059498 -0.06822019 0.1886058 0.9820519 0.001394629 0.7073986 0.7063578 -0.02541571 0.9633545 0.2589274 -0.07003563 0.8409944 0.5407783 -0.01695621 0.840377 0.5417211 -0.01745921 0.6312485 0.7753735 0.01792758 0.9473063 0.3202242 -0.008211374 0.9695656 0.2404019 -0.04636192 0.3853456 0.9220603 0.03624683 0.8368895 0.5469117 0.02244794 0.1901745 0.9814658 0.0236358 0.2040563 0.978605 0.02632886 0.6549515 0.7543678 0.04435974 0.9579459 0.2852654 0.03103834 0.7331235 0.6776081 0.05811423 0.446587 0.8929998 0.05577957 0.8940207 0.4434683 0.06373965 0.5797327 0.8118865 0.06892359 0.9505095 0.3056949 0.05551862 0.9628683 0.2583121 0.0784828 0.7765401 0.6229888 0.09418308 0.8779302 0.4697487 0.0926001 0.6476833 0.7522439 0.1209778 0.9222264 0.3600926 0.1408259 0.9602436 0.258955 0.1042817 0.7627363 0.6367298 0.1131747 0.4374735 0.8940431 0.0964567 0.06423169 0.997838 0.01391291 0.8480643 0.4996352 0.1764984 0.1598278 0.9855021 0.05692917 0.6352647 0.7603682 0.1351999 0.9238888 0.359827 0.130208 0.6445977 0.750053 0.1480349 0.3341485 0.9380553 0.09163522 0.2937443 0.9511036 0.09547996 0.9554261 0.2253826 0.1906923 0.4000967 0.9109065 0.1008561 0.8090513 0.5525657 0.2002679 0.8458684 0.4988241 0.1888947 0.5966846 0.780447 0.1867353 0.6001012 0.7762431 0.1931975 0.9147555 0.3334721 0.2280764 0.7290539 0.6360741 0.2527654 0.9546616 0.2254949 0.194354 0.7929835 0.5531339 0.2553823 0.8597416 0.4155807 0.2968789 0.9160954 0.2993495 0.2667568 0.9002878 0.321302 0.2936785 0.9255252 0.1819202 0.3321268 -0.8932699 -0.2801727 -0.3515284 -0.8881588 -0.1848647 -0.4207127 -0.6787145 -0.6842151 -0.2668266 -0.8698899 -0.3140774 -0.3803248 -0.8192458 -0.4336295 -0.3752356 -0.8017019 -0.4770104 -0.3601878 -0.5064221 -0.8409703 -0.1905404 -0.6938837 -0.6483389 -0.3133404 -0.7023992 -0.6351001 -0.321377 -0.4691762 -0.8590226 -0.2048268 -0.8533858 -0.1916555 -0.4847691 -0.2979006 -0.9435504 -0.1448031 -0.8357035 -0.2528444 -0.4875136 -0.2234906 -0.9702784 -0.09280085 -0.7884079 -0.421025 -0.4484986 -0.5306276 -0.803785 -0.2690058 -0.7633723 -0.4666803 -0.4466233 -0.5016189 -0.8282502 -0.24976 -0.6728087 -0.6439647 -0.3641951 -0.5887989 -0.7319435 -0.3428915 -0.7367724 -0.4896314 -0.4662913 -0.3765915 -0.898899 -0.2239632 -0.3035819 -0.9377027 -0.1689721 -0.7881079 -0.2532483 -0.5610269 -0.6143187 -0.671593 -0.4142166 -0.779683 -0.2761904 -0.5619728 -0.5679 -0.7423333 -0.3555713 -0.728028 -0.4446171 -0.5218151 -0.4727583 -0.8224002 -0.3164771 -0.7084251 -0.4765488 -0.5206105 -0.05055218 -0.9982485 -0.03073352 -0.3916913 -0.8858468 -0.2487036 -0.615648 -0.6450486 -0.4526478 -0.7381318 -0.2520787 -0.6257936 -0.5718106 -0.6853444 -0.4509276 -0.6879153 -0.3628193 -0.6285974 -0.1677755 -0.9790357 -0.1155004 -0.4673945 -0.7999586 -0.3763091 -0.4832484 -0.7819395 -0.3937535 -0.6587746 -0.488881 -0.5718492 -0.6143592 -0.5729619 -0.5424736 -0.2501685 -0.9468011 -0.202444 -0.6793857 -0.3500964 -0.644878 -0.3593309 -0.8816648 -0.305857 -0.544325 -0.6460343 -0.5351169 -0.2543843 -0.9433445 -0.2130489 -0.4846488 -0.7341669 -0.4755149 -0.6303262 -0.3462162 -0.6948549 -0.6383419 -0.37994 -0.6694515 -0.5516445 -0.5897855 -0.5897809 -0.2215412 -0.952414 -0.209349 -0.6019589 -0.3174096 -0.7327324 -0.6047092 -0.3464255 -0.7171583 -0.4214962 -0.7887967 -0.447371 -0.5244108 -0.5535795 -0.6469492 -0.3193013 -0.8834322 -0.3429201 -0.3393208 -0.8652039 -0.3691664 -0.5226684 -0.6079872 -0.5976365 -0.267611 -0.9181712 -0.2921401 -0.584597 -0.297906 -0.7546513 -0.431859 -0.7469538 -0.5055273 -0.1169448 -0.985296 -0.1245626 -0.4733113 -0.5861883 -0.6575407 -0.531255 -0.2396066 -0.8126236 -0.5347155 -0.3422476 -0.7726228 -0.3928141 -0.769572 -0.5034442 -0.3528472 -0.8098259 -0.4687014 -0.4891908 -0.4758272 -0.7309452 -0.4705986 -0.5783835 -0.6663405 -0.1931397 -0.9481803 -0.2522922 -0.1359089 -0.974799 -0.1769063 -0.3047136 -0.8410844 -0.4469078 -0.4740737 -0.2162308 -0.8535212 -0.2157686 -0.9270108 -0.3067489 -0.3621629 -0.7083082 -0.6059189 -0.4577254 -0.2644547 -0.8488529 -0.423389 -0.4592963 -0.7808896 -0.4231122 -0.4886473 -0.7630203 -0.3019573 -0.8284009 -0.4717774 -0.3540503 -0.6677582 -0.6547881 -0.2404713 -0.8693624 -0.4317207 -0.3806414 -0.2478387 -0.8908919 -0.3213061 -0.6948274 -0.6434107 -0.1654016 -0.9359266 -0.3109402 -0.3653617 -0.2924506 -0.8837327 -0.3609652 -0.4599906 -0.8112416 -0.2535642 -0.7919868 -0.5553937 -0.05913072 -0.9932782 -0.09950917 -0.313292 -0.5716025 -0.758366 -0.1409866 -0.9489518 -0.2821583 -0.3466212 -0.3045303 -0.8871951 -0.09971147 -0.9741433 -0.2027375 -0.2421941 -0.7988032 -0.5506866 -0.2782418 -0.5209874 -0.806941 -0.2945175 -0.5824919 -0.7576032 -0.2890825 -0.1547247 -0.9447178 -0.1535642 -0.9106722 -0.3835288 -0.3005313 -0.2455653 -0.9216174 -0.2247478 -0.7399855 -0.6339637 -0.2465751 -0.4160547 -0.875271 -0.2588135 -0.5209584 -0.8133991 -0.2346083 -0.2189305 -0.9471158 -0.2052811 -0.6613466 -0.7214432 -0.2086581 -0.7464762 -0.6318506 -0.2222445 -0.3919228 -0.8927508 -0.1548355 -0.8305578 -0.5349764 -0.1974371 -0.1252044 -0.9722872 -0.1183558 -0.919166 -0.375667 -0.09947603 -0.9356964 -0.3384919 -0.1779273 -0.4495495 -0.8753555 -0.05308544 -0.982469 -0.1787087 -0.1538673 -0.2233633 -0.9625143 -0.151161 -0.6270315 -0.7641872 -0.1621176 -0.6651731 -0.7288777 -0.1506724 -0.3955785 -0.9059888 -0.03443455 -0.9903283 -0.1344035 -0.1215751 -0.8101211 -0.5735185 -0.1023666 -0.1685092 -0.9803702 -0.07920926 -0.2437638 -0.9665946 -0.1147244 -0.6493461 -0.7517899 -0.0740146 -0.7743805 -0.6283763 -0.09199541 -0.4501775 -0.8881875 -0.07792443 -0.5073812 -0.8581913 -0.09112578 -0.8387686 -0.5368085 -0.06758338 -0.9028825 -0.4245418 -0.04719918 -0.5392608 -0.8408153 0.001779317 -0.1650191 -0.9862889 -0.04628717 -0.9241265 -0.3792726 -0.01786756 -0.2366154 -0.9714392 -0.02081084 -0.6794934 -0.7333865 -0.02700382 -0.9703372 -0.2402432 -0.05053114 -0.7787154 -0.6253391 0.004524886 -0.4401953 -0.8978907 -0.02598732 -0.8359273 -0.5482247 0.05891138 -0.2232935 -0.9729694 -0.02393108 -0.9060217 -0.4225543 -3.98004e-4 -0.6944063 -0.7195831 0.01059645 -0.8010548 -0.5984972 0.03880023 -0.4633979 -0.8853005 0.04867762 -0.4418294 -0.8957775 0.08532661 -0.1750102 -0.9808623 0.04124605 -0.6268111 -0.7780789 0.002515912 -0.9335719 -0.3583814 0.006106019 -0.9475271 -0.3196174 -0.002291023 -0.9813533 -0.1921991 0.02679669 -0.8204064 -0.5711525 0.02867913 -0.8520101 -0.5227394 0.1250814 -0.2222555 -0.9669318 0.069651 -0.6685078 -0.7404364 0.1450487 -0.338476 -0.9297285 0.07215303 -0.745833 -0.6622138 0.1229904 -0.44717 -0.8859529 0.004950165 -0.9954037 -0.09564042 0.1279942 -0.544143 -0.8291717 0.2043818 -0.2937063 -0.9337905 0.08909446 -0.7703632 -0.6313499 0.09040427 -0.8229783 -0.5608331 0.06744152 -0.8818966 -0.4665942 0.1550992 -0.5911431 -0.7915139 0.06269049 -0.9179809 -0.3916391 0.1510908 -0.6514774 -0.7434708 0.04963165 -0.9385459 -0.3415677 0.2094218 -0.3013877 -0.9302194 0.2257094 -0.4558951 -0.8609384 0.2723947 -0.2036262 -0.9403922 0.3021639 -0.3553461 -0.8845486 0.1780521 -0.7545565 -0.6316186 0.03605651 -0.9789172 -0.2010502 0.2352912 -0.4604291 -0.8559458 0.1269464 -0.8228465 -0.5539028 0.09232664 -0.9093295 -0.4057043 0.2386375 -0.6487925 -0.7225791 0.3460311 -0.2643744 -0.9002048 0.2935348 -0.3550444 -0.8875701 0.1770824 -0.7547612 -0.6316466 0.1803234 -0.8048397 -0.5654348 0.311178 -0.539649 -0.7822706 0.1282299 -0.9146329 -0.3834109 0.3572452 -0.2638223 -0.8959764 0.2554716 -0.6397004 -0.7249261 0.1029325 -0.9316058 -0.348591 0.3879708 -0.3533731 -0.8512381 0.05769407 -0.9783717 -0.1986461 0.3208155 -0.5342842 -0.78206 0.3956894 -0.3484362 -0.8497189 0.2431979 -0.7954072 -0.5551416 0.05324512 -0.9860104 -0.1579514 0.2310041 -0.8098837 -0.5391898 0.1554191 -0.9125288 -0.3783335 0.1456822 -0.9317698 -0.3325384 0.3373497 -0.6542181 -0.6769002 0.4755442 -0.2939991 -0.8291093 0.2547076 -0.7867114 -0.5623249 0.4252986 -0.3743251 -0.8240157 0.4083482 -0.5291471 -0.7438112 0.3658767 -0.6297854 -0.6852041 0.4955084 -0.3136968 -0.8099789 0.4734662 -0.456153 -0.7534947 0.02463799 -0.9984022 -0.05085343 0.5365565 -0.2436662 -0.8079196 0.3726628 -0.7005844 -0.608526 0.158351 -0.94141 -0.2977792 0.4840205 -0.5157161 -0.7069377 0.2749389 -0.8373044 -0.4725781 0.2477192 -0.8804857 -0.4042032 0.4236072 -0.6636687 -0.6165232 0.5635719 -0.2880336 -0.7742244 0.5631955 -0.3933562 -0.7266924 0.0921992 -0.9841011 -0.1518039 0.4249691 -0.7079226 -0.5641337 0.6285106 -0.3120177 -0.7124742 0.5766164 -0.4020234 -0.71126 0.5472233 -0.5282803 -0.6492047 0.3168594 -0.8525296 -0.4156844 0.267551 -0.886939 -0.3765048 0.4570015 -0.6854945 -0.5667865 0.1857356 -0.9539057 -0.2357248 0.6424487 -0.31024 -0.7007216 0.7095871 -0.1341415 -0.6917314 0.5599926 -0.5937818 -0.5777816 0.468125 -0.7194581 -0.5130684 0.6435663 -0.4422467 -0.6246922 0.4261645 -0.7872095 -0.4457412 0.347208 -0.8539034 -0.3876802 0.5931007 -0.5588976 -0.5795388 0.7247487 -0.220467 -0.6527891 0.1934661 -0.95848 -0.2094923 0.2192872 -0.9490415 -0.2263482 0.6924095 -0.3666913 -0.6213749 0.5870673 -0.6179359 -0.5229793 0.7665929 -0.1617765 -0.6214208 0.762669 -0.2765058 -0.5847057 0.5367768 -0.7030578 -0.4664552 0.4607957 -0.7837875 -0.4163466 0.7077814 -0.4175679 -0.5698094 0.4337616 -0.8189455 -0.3757385 0.6826233 -0.493923 -0.5385774 0.2976543 -0.9196994 -0.2560368 0.2319514 -0.9467941 -0.2231135 0.674949 -0.5558273 -0.4852833 0.8035399 -0.2591851 -0.5358608 0.5785276 -0.7010022 -0.4170153 0.8005697 -0.3209248 -0.5060588 0.5524952 -0.7388507 -0.3858092 0.4602028 -0.8190906 -0.3424969 0.7240498 -0.5030631 -0.4718891 0.3144741 -0.9238072 -0.2183725 0.3205167 -0.9197764 -0.2264518 0.8209259 -0.3010686 -0.48522 0.1431951 -0.9845982 -0.1003076 0.7017961 -0.5855331 -0.4057502 0.5750357 -0.7402241 -0.3484283 0.8320507 -0.339553 -0.4386291 0.5628429 -0.7575628 -0.3306156 0.8232818 -0.3904474 -0.4120169 0.1313543 -0.987253 -0.08987617 0.7189696 -0.5718051 -0.3951224 0.3945317 -0.8930645 -0.2162885 0.6495296 -0.6982969 -0.3008205 0.8590446 -0.3472852 -0.376079 0.8356713 -0.3913987 -0.385306 0.7497467 -0.5813223 -0.3161395 0.394242 -0.8933109 -0.2157986 0.6484919 -0.6887937 -0.3240702 0.2874771 -0.9479912 -0.136637 0.8939932 -0.301091 -0.3318438 0.5602021 -0.7935596 -0.2375644 0.7433592 -0.6063207 -0.2824754 0.8937164 -0.3201545 -0.3142806 0.5935594 -0.7716399 -0.2286025 0.5615802 -0.7967215 -0.2232996 0.8271998 -0.4936758 -0.2683745 0.4697239 -0.8668599 -0.167074 0.774389 -0.5742921 -0.265538 0.9298915 -0.2392974 -0.279354 0.2833042 -0.9507716 -0.125587 0.2225918 -0.971142 -0.08565109 0.6979084 -0.6870476 -0.2022117 0.9212382 -0.3244951 -0.2145305 0.9131178 -0.3525758 -0.2047101 0.8516373 -0.4780361 -0.2149316 0.4572513 -0.8787978 -0.1365129 0.7741 -0.6090034 -0.1728703 0.9610553 -0.2336364 -0.1476033 0.3806586 -0.919441 -0.09862703 0.6887004 -0.7057741 -0.1660564 0.916181 -0.3523159 -0.1910126 0.6451089 -0.750074 -0.1456831 0.2439299 -0.9672908 -0.06961941 0.8367196 -0.5338932 -0.1218957 0.9588141 -0.2596898 -0.1150514 0.9095858 -0.4041503 -0.09652149 0.6182268 -0.777996 -0.1118845 0.8360819 -0.5357256 -0.118174 0.414304 -0.9073103 -0.07169574 0.7771638 -0.6232008 -0.08739113 0.9777024 -0.1916725 -0.08578896 0.6538435 -0.751653 -0.08664107 0.1514167 -0.9880733 -0.02800482 0.9849889 -0.1721971 -0.01204133 0.3742533 -0.926135 -0.04699522 0.9683789 -0.2466713 -0.03736048 0.907105 -0.4200439 -0.02690386 0.9090132 -0.4159938 -0.02538383 0.1904889 -0.9813442 -0.02603262 0.5712214 -0.8200808 -0.03425598 0.790279 -0.6115176 -0.03879773 0.3945246 -0.9180062 -0.04018843 0.9703233 -0.2384532 0.04015785 0.7349107 -0.6780914 -0.009922325 0.9072412 -0.4203892 0.01365101 0.5825938 -0.8124207 -0.02360761 0.8628119 -0.5039032 0.04046249 0.9738706 -0.2209779 0.05239188 0.7523012 -0.6585122 0.02011412 0.5186246 -0.8549504 0.009409904 0.2990262 -0.9542319 0.004994392 0.3258071 -0.9453234 0.01461243 0.9494574 -0.2944626 0.1087313 0.6874933 -0.7240389 0.05586355 0.9261834 -0.3563781 0.1232035 0.1813024 -0.9834186 -0.004155993 0.5636343 -0.8249509 0.04210066 0.8677725 -0.4872325 0.09785449 0.7985639 -0.5919952 0.1088004 0.9650245 -0.1808757 0.1897674 0.7167025 -0.6921986 0.08484488 0.9279728 -0.3444703 0.1421507 0.504039 -0.8612874 0.06425726 0.9427322 -0.239383 0.2322751 0.3018158 -0.9529265 0.02895212 0.2783692 -0.9598544 0.03449976 0.8917269 -0.4089268 0.1939123 0.6215559 -0.7757541 0.108968 0.5232625 -0.8479254 0.08496505 0.8430266 -0.5007352 0.1963936 0.7897463 -0.5883699 0.173556 0.9437725 -0.2169827 0.2494234 0.9162738 -0.2723239 0.2937381 0.6973156 -0.6958084 0.1720514 0.8981111 -0.3187016 0.3030278 0.8384199 -0.4701114 0.275767 0.7980322 -0.5350494 0.2772485 0.435137 -0.8949458 0.09862935 0.7182654 -0.6534473 0.2389593 0.3447268 -0.9351763 0.081294 0.6808167 -0.7095025 0.1819201 0.5455495 -0.8222606 0.1620602 0.1329866 -0.9907503 0.02699178 0.288302 -0.9540445 0.08173865 0.0195142 -0.9997918 0.005960404 -0.9310835 1.06467e-5 -0.3648064 -0.9318329 4.29299e-6 -0.3628878 -0.9116207 7.86529e-6 -0.4110326 -0.9112027 1.12214e-5 -0.4119586 -0.8685492 -3.2432e-5 -0.4956031 -0.8649554 -1.32136e-6 -0.5018489 -0.8368474 3.499e-5 -0.5474364 -0.8129379 -5.92665e-5 -0.5823506 -0.7823759 4.29649e-5 -0.6228066 -0.7466275 1.40991e-5 -0.6652425 -0.7546079 -1.15766e-5 -0.656176 -0.724013 -2.39842e-5 -0.6897863 -0.7131888 1.04263e-5 -0.700972 -0.6743069 8.5765e-6 -0.7384513 -0.6848922 -2.33506e-5 -0.7286444 -0.6471691 -3.69006e-5 -0.7623465 -0.6082726 -1.12953e-5 -0.7937282 -0.6004592 1.95561e-5 -0.7996556 -0.559309 1.28073e-5 -0.8289594 -0.5654978 -1.07001e-5 -0.8247498 -0.4809316 -1.24149e-5 -0.8767581 -0.4806503 -1.10753e-5 -0.8769124 -0.3913629 -1.69191e-5 -0.9202365 -0.3926442 -2.29215e-5 -0.9196905 -0.3345698 4.06749e-5 -0.942371 -0.3009778 -4.89777e-5 -0.9536312 -0.2451938 6.92821e-5 -0.9694741 -0.1989713 -4.40327e-5 -0.9800053 -0.1499821 5.64173e-5 -0.9886887 -0.09920328 -5.46548e-5 -0.9950672 -0.04876857 5.70062e-5 -0.9988101 -0.002766191 -4.57213e-5 -0.9999962 0.04590409 6.1659e-5 -0.9989459 0.09213733 -4.05339e-5 -0.9957463 0.1415743 -2.79201e-5 -0.9899277 0.1606367 3.58776e-5 -0.9870136 0.209463 1.10481e-5 -0.9778166 0.1972503 -2.73512e-5 -0.9803532 0.2457852 4.3701e-5 -0.9693244 0.2887964 -1.17712e-5 -0.9573906 0.2877774 -1.41197e-5 -0.9576973 0.3480077 2.43341e-5 -0.9374917 0.3316898 -1.29299e-5 -0.9433886 0.3753562 -2.80399e-5 -0.9268807 0.3962346 2.10482e-5 -0.9181494 0.4395041 -2.62479e-5 -0.8982406 0.438385 -2.89754e-5 -0.8987873 0.4764449 -7.30514e-5 -0.8792043 0.5259708 4.64799e-5 -0.8505027 0.5557163 -4.01992e-5 -0.831372 0.5969719 -3.32453e-5 -0.8022621 0.6117156 2.49758e-5 -0.7910778 0.6453285 -7.36433e-6 -0.7639052 0.6390432 -3.27011e-5 -0.7691709 0.7152827 8.52676e-6 -0.6988353 0.7109828 -1.90393e-5 -0.7032094 0.7486668 6.06164e-5 -0.6629465 0.782328 1.04427e-6 -0.6228668 0.7788472 -1.63996e-5 -0.6272138 0.8145594 4.09771e-5 -0.5800803 0.8356951 -5.34076e-6 -0.5491939 0.8360107 -7.29034e-6 -0.5487133 0.867717 -2.79338e-6 -0.4970585 0.8680382 -1.35761e-6 -0.4964975 0.8916891 -2.81495e-6 -0.4526485 0.8911359 -5.5121e-6 -0.4537366 0.9074465 -3.66564e-6 -0.4201678 0.9103935 -1.86206e-5 -0.4137437 0.9306065 -1.44536e-5 -0.3660214 0.9345816 2.08861e-5 -0.355749 0.9442828 4.84911e-5 -0.3291354 0.9646648 -3.62599e-5 -0.2634805 0.961226 6.92072e-6 -0.2757619 0.9746873 9.54074e-6 -0.2235727 0.9724673 -1.19772e-5 -0.2330398 0.9845091 -1.59771e-5 -0.175334 0.9859002 1.06137e-5 -0.1673352 0.9922038 5.65689e-5 -0.1246259 0.9966106 -3.97418e-5 -0.08226436 0.9996809 0 -0.02526319 0.9998039 2.40516e-5 -0.01980388 0.9997949 5.11967e-5 0.02025353 0.9975131 -7.3618e-6 0.07048112 0.9973701 -2.94121e-6 0.07247668 0.9910523 2.28505e-6 0.1334738 0.9917033 -8.5493e-6 0.1285476 0.9871153 -4.18396e-5 0.1600108 0.9724492 4.50098e-5 0.2331149 0.984973 1.00324e-6 0.1727092 0.9637615 1.35696e-5 0.2667655 0.9641502 1.03832e-5 0.2653575 0.947727 3.20249e-6 0.3190824 0.9466695 1.02547e-5 0.3222064 0.9292539 -5.94317e-5 0.3694418 0.9116188 3.45676e-5 0.411037 0.891762 -7.08327e-5 0.4525049 0.867254 4.74153e-5 0.497866 0.8405757 -4.40034e-6 0.5416941 0.8405601 -4.30222e-6 0.5417184 0.8096653 5.13584e-5 0.586892 0.7832327 -3.69918e-6 0.6217288 0.7826279 -1.59368e-6 0.6224899 0.7520219 -5.63367e-5 0.6591382 0.7168434 -9.30903e-7 0.6972343 0.7159078 3.52753e-6 0.6981948 0.6845639 -2.42508e-5 0.7289529 0.6797842 -2.59806e-6 0.7334122 0.6401677 4.15189e-5 0.7682353 0.607494 -1.51229e-5 0.7943243 0.6058332 -8.28417e-6 0.7955918 0.5595736 5.04538e-5 0.8287808 0.5272182 -3.43449e-5 0.84973 0.4810616 3.07408e-6 0.8766869 0.4757415 2.9778e-5 0.8795852 0.4392542 5.53184e-5 0.8983629 0.3831718 3.58378e-6 0.9236772 0.3875504 -6.92702e-6 0.9218487 0.3374204 -5.5896e-5 0.9413541 0.2947881 4.47999e-5 0.9555627 0.249716 -1.29274e-6 0.9683191 0.2469965 7.4089e-6 0.9690164 0.1588876 -1.2548e-5 0.9872968 0.1493537 1.85016e-5 0.9887838 0.09915614 -2.77893e-7 0.995072 0.09219402 1.49053e-5 0.9957411 0.05468732 -8.77584e-6 0.9985035 0.05060219 2.88553e-7 0.9987189 -0.008874714 2.40154e-5 0.9999607 0.007010698 -1.00159e-5 0.9999755 -0.0606302 -4.54033e-5 0.9981604 -0.09126186 -6.69854e-6 0.995827 -0.08556103 -2.42311e-5 0.996333 -0.1570032 -1.76582e-7 0.9875982 -0.1533706 -8.30662e-6 0.9881687 -0.1857208 -1.53087e-5 0.9826025 -0.1927387 2.39819e-7 0.9812501 -0.2522017 0 0.9676747 -0.2467505 -1.85477e-5 0.9690791 -0.3370127 -2.81563e-5 0.9415001 -0.3432593 0 0.9392407 -0.3920319 2.76698e-5 0.9199517 -0.4251881 -5.71182e-5 0.9051051 -0.4771635 -2.58665e-6 0.8788146 -0.4797049 1.02716e-5 0.87743 -0.5596077 -9.54661e-6 0.8287578 -0.5598902 -8.44112e-6 0.828567 -0.6084706 -5.17818e-6 0.7935765 -0.6071649 -8.82391e-6 0.7945759 -0.630451 -3.92447e-5 0.7762292 -0.6790302 -4.5482e-6 0.7341104 -0.6852234 3.09679e-5 0.728333 -0.7163192 4.82548e-5 0.6977728 -0.7430469 -4.16547e-5 0.6692394 -0.7853993 2.94046e-5 0.6189895 -0.782227 7.05259e-6 0.6229937 -0.8368393 1.21936e-5 0.5474487 -0.8384776 2.22747e-5 0.5449362 -0.8679342 -3.65966e-5 0.4966793 -0.8890277 6.20673e-5 0.4578535 -0.9107869 -5.6816e-5 0.4128771 -0.9287708 -1.14017e-5 0.3706544 -0.9327561 2.34151e-5 0.3605083 -0.9481515 2.39123e-5 0.3178188 -0.9441052 -1.74353e-5 0.3296447 -0.9634868 5.44716e-5 0.2677558 -0.9732558 -3.43709e-5 0.2297242 -0.9857023 2.94988e-5 0.1684969 -0.9854444 2.28643e-5 0.1699979 -0.9970866 1.44571e-5 0.07627946 -0.9966509 -9.17309e-6 0.08177548 -0.9998847 6.25092e-5 0.01518899 -0.9999153 -2.17405e-5 -0.0130214 -0.9996771 1.66199e-5 -0.02541512 -0.99632 4.07151e-5 -0.08571231 -0.9930555 1.0534e-5 -0.1176471 -0.9934448 3.09345e-6 -0.1143136 -0.9874695 -4.62634e-5 -0.1578107 -0.9830313 1.12733e-5 -0.183438 -0.9714344 2.14124e-5 -0.2373086 -0.9783049 -4.59068e-5 -0.2071704 -0.9612414 1.49128e-5 -0.2757083 -0.9607478 1.87864e-5 -0.2774235 -0.9490378 -4.00084e-5 -0.3151624 -0.001856267 0.9999973 -0.001390695 0.001036345 0.9999961 -0.00260818 0.005077064 0.9999865 -0.001146793 1.0975e-5 1 4.41306e-5 -0.003268122 0.9999864 0.004076421 1.16234e-4 1 -1.5862e-4 -1.88386e-5 1 1.58505e-4 -0.004035174 0.999991 -0.001371622 -7.2672e-4 0.9999991 -0.001161456 -1.02e-4 1 3.36599e-5 -1.60916e-5 0.9999983 0.001862883 2.16816e-4 1 4.09486e-5 -2.43803e-5 1 -4.77241e-5 -5.03383e-4 0.999997 -0.002438366 -5.51749e-5 1 -2.94983e-5 4.29934e-4 0.9999991 -0.001349389 2.3437e-4 1 5.86225e-5 0.007406234 -0.999971 0.001847684 4.80209e-4 -0.9999998 3.34257e-4 -2.22715e-4 -1 -4.3523e-5 -8.72763e-4 -0.9999992 9.06107e-4 0.01240521 -0.9999141 -0.004252731 -3.00921e-4 -0.9999997 7.93393e-4 5.52696e-4 -0.9999995 -9.35242e-4 0.008253812 -0.9999464 -0.006256103 0.00279057 -0.9999944 -0.001850903 -4.32462e-4 -1 7.88226e-5 -0.001466274 -0.999999 3.18459e-5 -0.008907079 -0.9999396 -0.006455421 -1.15047e-4 -1 -9.5338e-5 -5.56931e-5 -1 -3.21103e-5 -8.19897e-4 -0.9999873 -0.004978239 3.32963e-4 -1 3.45726e-4 9.63747e-6 -1 -5.57502e-5 2.55688e-4 -0.9999998 -5.34226e-4 -1.84298e-4 -0.9999964 0.002667605 0.8921093 -0.2734379 0.3596844 0.8626269 -0.3283963 0.3847477 0.612932 -0.7500419 0.2484989 0.7824877 -0.5171318 0.3468255 0.506017 -0.84182 0.1878458 0.7689977 -0.5365614 0.3474833 0.4366856 -0.8830066 0.1720615 0.8767754 -0.1615229 0.4529629 0.8631452 -0.2817962 0.4190124 0.2896143 -0.9513098 0.1055147 0.2607861 -0.9600614 0.1013547 0.622395 -0.7342596 0.2710856 0.7284659 -0.5690454 0.3814772 0.8332488 -0.2417104 0.4972651 0.6010229 -0.7325167 0.319673 0.5815067 -0.7590789 0.292659 0.8095523 -0.3755688 0.4511908 0.07740789 -0.9963864 0.03496134 0.7464572 -0.5098434 0.4276232 0.4264065 -0.87882 0.2141335 0.3873384 -0.8987615 0.2054187 0.8206609 -0.2157232 0.5291308 0.8206906 -0.2165383 0.5287514 0.2632436 -0.9557733 0.1311501 0.715268 -0.5252561 0.4609749 0.7125059 -0.5346184 0.454443 0.7964408 -0.2418838 0.5542332 0.5630276 -0.740162 0.3676414 0.5783298 -0.7268263 0.3704838 0.1845816 -0.9770573 0.1062487 0.7049317 -0.4680542 0.5329132 0.3925274 -0.8821915 0.2601159 0.3766794 -0.8940738 0.2423731 0.7809166 -0.1936872 0.5938474 0.7136623 -0.3575872 0.6023433 0.1893103 -0.9744693 0.120711 0.7084242 -0.4657527 0.530292 0.5953161 -0.6379731 0.4884558 0.5474417 -0.7269836 0.4144909 0.6986258 -0.3577749 0.6196121 0.6984219 -0.3569296 0.620329 0.4468104 -0.8170565 0.3643889 0.3791723 -0.8783274 0.291152 0.3073448 -0.9162148 0.2570788 0.5844975 -0.6376043 0.5018203 0.5518884 -0.6665219 0.5011665 0.6727713 -0.3559992 0.6485704 0.6694174 -0.3598506 0.6499138 0.1374439 -0.9846485 0.1075941 0.4445252 -0.8045749 0.3937725 0.5408812 -0.6445221 0.5404064 0.6382862 -0.2809237 0.7167097 0.6548612 -0.3589909 0.6650432 0.1360543 -0.9850262 0.1058902 0.3781561 -0.8473918 0.3727269 0.5340329 -0.5922496 0.6033651 0.3034793 -0.9077782 0.2895499 0.5214169 -0.6551859 0.5466771 0.6140292 -0.3009936 0.7296377 0.420858 -0.7809951 0.4614382 0.5600451 -0.4452401 0.6986492 0.3906784 -0.8214294 0.4154806 0.006357491 -0.9999567 0.006812453 0.5265421 -0.5848842 0.6169797 0.5918589 -0.184751 0.7845827 0.1841803 -0.9612874 0.2049492 0.1492589 -0.9750135 0.1645311 0.5431035 -0.2699514 0.7950879 0.4604532 -0.6592555 0.5944452 0.3960075 -0.7690317 0.5017653 0.5081263 -0.4562247 0.730525 0.3472766 -0.8125315 0.4681791 0.07051694 -0.9934509 0.08990341 0.4800216 -0.5116872 0.7125697 0.2606142 -0.9050077 0.3362161 0.2632453 -0.8995991 0.3484586 0.4447102 -0.6203019 0.6461102 0.5212203 -0.2191401 0.8248074 0.3883393 -0.6984128 0.6011757 0.3416838 -0.799851 0.493448 0.4559909 -0.1892274 0.8696352 0.4685475 -0.2804101 0.8377551 0.42069 -0.4714589 0.7750785 0.4076284 -0.4923034 0.7690749 0.2415794 -0.8757008 0.418076 0.2094334 -0.9198313 0.3317351 0.3446016 -0.7088643 0.6154357 0.3137308 -0.7473417 0.5857076 0.3835344 -0.4935931 0.7805559 0.2415564 -0.8717682 0.4262288 0.4028893 -0.198334 0.8935009 0.3641427 -0.3292682 0.871196 0.120544 -0.9709305 0.2067925 0.2015953 -0.8887019 0.4117867 0.305431 -0.6117126 0.7297396 0.3170322 -0.2402064 0.917492 0.3450782 -0.3416082 0.8741996 0.2685685 -0.7457662 0.6096751 0.2389782 -0.7848098 0.5718069 0.2926237 -0.4908111 0.8206559 0.2848981 -0.5683441 0.7718926 0.1409858 -0.9334216 0.32992 0.2700104 -0.2937244 0.9169626 0.090029 -0.9756876 0.1998215 0.2053058 -0.8057159 0.5555821 0.2577776 -0.446572 0.8568105 0.1419861 -0.9062281 0.3982346 0.2147991 -0.6770023 0.7039384 0.2376877 -0.2250153 0.9449195 0.1929782 -0.776516 0.5998186 0.06392675 -0.9856926 0.1559601 0.2220727 -0.5045922 0.8343084 0.1998935 -0.6451284 0.7374631 0.1987519 -0.283344 0.9381971 0.05221456 -0.9819577 0.1817492 0.173245 -0.4495237 0.8763074 0.1735013 -0.4518796 0.8750442 0.1349591 -0.8325123 0.5373167 0.1598152 -0.1850336 0.9696503 0.1427268 -0.6276501 0.7653002 0.1017535 -0.9200993 0.3782376 0.09402507 -0.9276641 0.3613842 0.1598628 -0.6764122 0.7189649 0.02920168 -0.9905729 0.1338381 0.1215843 -0.8020673 0.5847268 0.1016288 -0.6617558 0.7427994 0.1112716 -0.2507511 0.9616353 0.08698791 -0.3522776 0.9318442 0.08443892 -0.8022227 0.5910235 0.09190648 -0.8145028 0.5728338 0.1076383 -0.438026 0.892495 0.06134277 -0.9281651 0.3670786 0.08100569 -0.6217324 0.7790296 0.04756587 -0.3415723 0.9386512 0.05233407 -0.3534001 0.9340073 0.05373251 -0.8144837 0.5776931 0.02247548 -0.5756098 0.8174157 0.05426275 -0.6359361 0.7698317 0.03372788 -0.9498562 0.3108631 -0.01035392 -0.2964454 0.9549938 0.02858 -0.9608195 0.2756976 0.0306068 -0.7739391 0.63252 0.004629373 -0.5862814 0.8100943 0.02291703 -0.9042198 0.4264522 -0.02317428 -0.3063298 0.9516434 -0.02332204 -0.6850235 0.7281476 -0.05389028 -0.3924017 0.9182139 0.01913118 -0.7800729 0.625396 -0.01082682 -0.8753131 0.4834355 -0.03238588 -0.6912521 0.7218877 -0.1149352 -0.3016281 0.9464727 -0.07624512 -0.4034143 0.9118354 -0.0404008 -0.8264606 0.5615432 -0.08767616 -0.4909005 0.8667928 -0.01048415 -0.8751776 0.4836882 -0.06549924 -0.6536856 0.7539265 -0.1311402 -0.2888315 0.9483559 -0.02662771 -0.9481858 0.3165985 -0.001528084 -0.9825292 0.1861026 -0.1331711 -0.5436692 0.8286671 -0.1052557 -0.6976309 0.7086836 -0.1124179 -0.6849298 0.7198843 -0.1959372 -0.305664 0.9317609 -0.1780009 -0.3344469 0.9254518 -0.08138102 -0.8219922 0.5636543 -0.08727753 -0.8472291 0.524009 -0.1634934 -0.4943973 0.853722 -0.2604291 -0.1922137 0.9461663 -0.03500288 -0.947227 0.3186472 -0.2112445 -0.305005 0.9286268 -0.231655 -0.4809429 0.8455945 -0.09848564 -0.8508587 0.5160817 -0.005761504 -0.9987286 0.05007994 -0.2029069 -0.5490924 0.8107568 -0.2864386 -0.21893 0.9327501 -0.182305 -0.6764277 0.7135899 -0.1837239 -0.6944099 0.6957302 -0.04771423 -0.9694561 0.2405788 -0.2701886 -0.4498266 0.8512663 -0.03198915 -0.9891922 0.143093 -0.327666 -0.1783022 0.9278165 -0.1097886 -0.9082111 0.4038553 -0.1988668 -0.7121705 0.6732498 -0.3430966 -0.2666447 0.9006583 -0.3135347 -0.4385242 0.8422545 -0.2966375 -0.4693058 0.8317201 -0.1841533 -0.8164705 0.5472328 -0.1167829 -0.9058532 0.4071755 -0.2695398 -0.6335025 0.7252743 -0.4079074 -0.2418531 0.8804083 -0.2834368 -0.669819 0.6862989 -0.4186038 -0.3134648 0.852356 -0.2377595 -0.8031892 0.5462212 -0.2379626 -0.7862407 0.5702626 -0.369611 -0.4585277 0.8081708 -0.3570694 -0.5717886 0.7386199 -0.1556292 -0.924278 0.3485539 -0.4805331 -0.2282652 0.8467484 -0.1248677 -0.9415582 0.312852 -0.4455555 -0.312088 0.8390957 -0.06024837 -0.9855341 0.1584067 -0.431377 -0.4871992 0.7593095 -0.3781797 -0.5896209 0.7136718 -0.3633702 -0.6632102 0.6543044 -0.2900899 -0.7905715 0.5393002 -0.282411 -0.8135731 0.5082745 -0.1869214 -0.9216712 0.3399743 -0.5314102 -0.2372403 0.813216 -0.1869615 -0.9215984 0.3401497 -0.5385627 -0.322054 0.7786087 -0.4889621 -0.4742909 0.7320958 -0.03778159 -0.9965674 0.07366079 -0.4741858 -0.5536692 0.6845425 -0.4175359 -0.6548892 0.6299078 -0.5676212 -0.3000968 0.7666474 -0.3601999 -0.7817854 0.5089871 -0.08991676 -0.9854733 0.1440746 -0.646142 -0.1960559 0.7376061 -0.5900954 -0.3304372 0.736613 -0.3594916 -0.7905954 0.4957065 -0.5769696 -0.4489662 0.6823015 -0.3419625 -0.8199844 0.4590067 -0.2517338 -0.9061102 0.3399918 -0.513677 -0.5681084 0.6429532 -0.6699967 -0.1955132 0.7161557 -0.6710625 -0.2064687 0.7120715 -0.4868449 -0.6505392 0.5829072 -0.2396749 -0.9186934 0.3139399 -0.6325848 -0.3998653 0.6632829 -0.1072575 -0.9827229 0.1508368 -0.6055718 -0.4489156 0.6570828 -0.5480109 -0.6122353 0.5699581 -0.2400357 -0.926536 0.2896794 -0.4972438 -0.6715933 0.5492822 -0.3970672 -0.8137397 0.4244588 -0.1017036 -0.9874601 0.1207442 -0.381473 -0.8377218 0.3907692 -0.7284159 -0.1900942 0.6582359 -0.729839 -0.2345361 0.6421276 -0.1679113 -0.9694221 0.1789601 -0.6823633 -0.4144639 0.6021628 -0.6848332 -0.4098312 0.6025297 -0.4450844 -0.7958135 0.4105862 -0.3813689 -0.8375369 0.391267 -0.5901659 -0.6092271 0.5296666 -0.7771461 -0.1600371 0.6086314 -0.5890098 -0.6124135 0.5272734 -0.01666277 -0.9997347 0.01590883 -0.7861716 -0.2299883 0.5736198 -0.3013973 -0.9150688 0.2679718 -0.5799084 -0.677589 0.4523047 -0.1923627 -0.9645931 0.1804352 -0.4665237 -0.7958363 0.3860055 -0.7274227 -0.4186397 0.5436884 -0.7135841 -0.4830673 0.5073893 -0.3656522 -0.886882 0.282381 -0.8146999 -0.1928986 0.5468587 -0.6028094 -0.6617071 0.4458304 -0.8177662 -0.2729997 0.506685 -0.6017283 -0.6654765 0.4416607 -0.1364166 -0.9848168 0.1073612 -0.749905 -0.4553244 0.4799191 -0.3651887 -0.8891961 0.2756223 -0.8495851 -0.2257751 0.4766871 -0.512786 -0.7930833 0.3287391 -0.7249423 -0.5501272 0.4145105 -0.6610012 -0.6410903 0.3899755 -0.8538181 -0.262996 0.4492526 -0.2702923 -0.9467442 0.174979 -0.5385337 -0.7868631 0.3013769 -0.2006325 -0.9705625 0.1332483 -0.5523316 -0.7683758 0.3233086 -0.7622294 -0.5124964 0.3954163 -0.8769889 -0.2310402 0.4213205 -0.3525271 -0.9166756 0.1882298 -0.867151 -0.3386375 0.365204 -0.7641722 -0.5292146 0.3687451 -0.7335835 -0.5956344 0.3272234 -0.5943201 -0.7533947 0.2813899 -0.8844907 -0.3234463 0.336242 -0.8755035 -0.3386827 0.344656 -0.5583213 -0.7924497 0.2455622 -0.7470651 -0.5883383 0.3094381 -0.4198446 -0.8893755 0.1809474 -0.9364503 -0.1899722 0.2949091 -0.3488591 -0.9218213 0.1689464 -0.8935858 -0.3237204 0.310982 -0.1990349 -0.9765878 0.08161777 -0.8672252 -0.4155125 0.274354 -0.120408 -0.9911614 0.05568712 -0.7434082 -0.6220728 0.2457028 -0.7277861 -0.6387381 0.2496819 -0.6048603 -0.7683733 0.2091569 -0.5534107 -0.8143023 0.1750673 -0.43214 -0.8895776 0.148009 -0.9549977 -0.1846103 0.2321607 -0.9471501 -0.238567 0.2144591 -0.343138 -0.9333364 0.1055434 -0.2488284 -0.9650542 0.08218783 -0.880608 -0.4278919 0.2035633 -0.8859413 -0.4175007 0.2019935 -0.973131 -0.1651122 0.1604807 -0.7623284 -0.6214379 0.1807498 -0.7843962 -0.5936464 0.1797408 -0.6644476 -0.7329574 0.1458868 -0.587004 -0.7971131 0.141553 -0.9652838 -0.2279154 0.1276013 -0.8978025 -0.4216161 0.1272428 -0.8629887 -0.4951643 0.1003143 -0.4495734 -0.8897764 0.07862442 -0.798157 -0.5915265 0.1142012 -0.9816122 -0.175942 0.07404106 -0.9808368 -0.1798959 0.07481241 -0.3912303 -0.9172044 0.07533401 -0.67583 -0.7316467 0.08914524 -0.6612191 -0.7459167 0.07998514 -0.9125947 -0.4056816 0.05092579 -0.1553247 -0.9876093 0.02240717 -0.8669403 -0.4929278 0.07373577 -0.4641582 -0.8828199 0.07201677 -0.7724005 -0.6341587 0.03521573 -0.6613836 -0.7476037 0.060503 -0.5829247 -0.8118253 0.03374177 -0.1558981 -0.9875144 0.02260708 -0.9848189 -0.173047 -0.01365131 -0.4523048 -0.890914 0.04114186 -0.963517 -0.2661705 -0.02807509 -0.915961 -0.4009094 -0.01694393 -0.8788668 -0.4760248 -0.03152126 -0.7713128 -0.6363368 -0.01232886 -0.7298673 -0.683167 -0.02401101 -0.3531481 -0.9355173 0.009688079 -0.2449719 -0.9694991 0.007769644 -0.5773137 -0.8165155 -0.003403246 -0.4697582 -0.8825173 -0.02214974 -0.9674406 -0.2292125 -0.1073333 -0.9373961 -0.3219163 -0.1328848 -0.8683369 -0.4861564 -0.09819984 -0.8195783 -0.5630723 -0.1060246 -0.4653187 -0.8842873 -0.03891682 -0.7166324 -0.6941663 -0.06761002 -0.9380914 -0.314929 -0.1442373 -0.6432051 -0.761531 -0.07973557 -0.1941974 -0.980925 -0.008581817 -0.4330828 -0.9002099 -0.04540574 -0.7895582 -0.5955768 -0.1479401 -0.2862946 -0.9573222 -0.0396173 -0.9301451 -0.2804223 -0.2370516 -0.6466849 -0.752354 -0.1255471 -0.9131247 -0.3601551 -0.1910275 -0.8188296 -0.543897 -0.1835593 -0.9289425 -0.2803223 -0.241837 -0.8984402 -0.3102134 -0.3107618 -0.6216318 -0.7719292 -0.1330394 -0.2720409 -0.9611423 -0.04689812 -0.8952431 -0.351447 -0.273907 -0.8898017 -0.3513956 -0.2911599 -0.8125596 -0.5069747 -0.2876175 -0.0237562 -0.9997087 -0.004272758 -0.8007844 -0.5621852 -0.2066206 -0.4494248 -0.8873259 -0.1032968 -0.4584279 -0.8820987 -0.1083782 -0.7408559 -0.6354644 -0.2175264 -0.7454687 -0.6179329 -0.2498707 -0.6634662 -0.7259784 -0.1810198 -0.4981641 -0.8489532 -0.1763836 -0.4322953 -0.8917897 -0.1335369 -0.2261205 -0.9704796 -0.08389818 -0.1457238 -0.9885522 -0.03910553 0.3893219 0.9065797 0.1629161 0.1312409 0.9896982 0.05721259 0.5519981 0.8073027 0.2087118 0.0596143 0.9976416 0.034024 0.6035324 0.7501398 0.2702573 0.2842357 0.946174 0.1548064 0.7093427 0.6366188 0.3025715 0.3790303 0.906629 0.1853644 0.7452269 0.5752694 0.3371973 0.4424208 0.8663801 0.2316232 0.8252686 0.4280344 0.3683996 0.8299961 0.4128876 0.3750069 0.5642935 0.7725833 0.2910123 0.5878399 0.7532704 0.2950056 0.6914557 0.6231512 0.3654747 0.8938356 0.1915789 0.4054077 0.8974986 0.1777608 0.4036056 0.1116595 0.9909152 0.07496058 0.2618568 0.9518254 0.1595607 0.3312969 0.9151788 0.2295433 0.7091859 0.5778422 0.403923 0.4333776 0.8591804 0.2720165 0.7946397 0.4203513 0.43801 0.5478119 0.757171 0.3558012 0.5465975 0.7581576 0.3555679 0.8166713 0.3159139 0.4829561 0.3349729 0.9151092 0.2244287 0.6726356 0.6052408 0.4257287 0.8609892 0.1844527 0.4739988 0.6910795 0.5564011 0.4613318 0.7921332 0.3236025 0.5175004 0.797643 0.3155214 0.5140156 0.2556659 0.9446939 0.2053983 0.4262626 0.8356062 0.3465005 0.1633634 0.9765951 0.1399088 0.5176544 0.7569826 0.3987622 0.7807198 0.3000394 0.5481359 0.5794814 0.6631197 0.4737864 0.6538815 0.5609241 0.5077431 0.3652863 0.8685535 0.3349341 0.1486187 0.979461 0.1362671 0.7043216 0.4226511 0.5703485 0.737564 0.3429113 0.5817312 0.7507313 0.2159098 0.6243281 0.3640171 0.8662073 0.3423109 0.4018653 0.820832 0.4058808 0.2122107 0.9489324 0.2334396 0.5453914 0.6528819 0.5256363 0.543188 0.6549965 0.5252871 0.6547638 0.438173 0.6158643 0.6613774 0.3541277 0.6611909 0.2027074 0.9492064 0.2406594 0.7159234 0.2030709 0.6679939 0.5336234 0.6177659 0.5775911 0.04207932 0.9978265 0.05071127 0.5740861 0.5079181 0.6422183 0.3789463 0.8127663 0.4425048 0.09188818 0.9876652 0.1267835 0.3973002 0.7816362 0.4808299 0.6405002 0.3538116 0.6815988 0.6388934 0.314038 0.7022786 0.4708001 0.679512 0.5626816 0.250971 0.9118653 0.3248311 0.6213263 0.2899047 0.7279485 0.4835199 0.5968124 0.6403307 0.2464355 0.8994429 0.3609324 0.5330186 0.5081825 0.6764923 0.1073597 0.9791131 0.1726599 0.3583189 0.7784969 0.5153157 0.5720705 0.336084 0.7481864 0.3745296 0.7363268 0.5635162 0.5658389 0.3175441 0.7609155 0.4575536 0.6125591 0.6445278 0.2101845 0.91585 0.3421131 0.470721 0.5100504 0.7199101 0.5349259 0.3161021 0.7835394 0.5300713 0.2780662 0.801064 0.2065985 0.8955393 0.3941148 0.202244 0.9033535 0.3782193 0.08306032 0.9822099 0.1684188 0.327277 0.7376606 0.5905478 0.3273872 0.7371011 0.591185 0.4018678 0.5320482 0.7452698 0.4018773 0.5418186 0.7381919 0.0569871 0.9888763 0.1373909 0.4409418 0.3444631 0.8288038 0.4784885 0.2680966 0.8361657 0.1845821 0.8850942 0.4272444 0.2711099 0.7342216 0.6224292 0.2429043 0.7735428 0.5853452 0.4061571 0.2991266 0.8634581 0.1313029 0.9167135 0.3773539 0.3014311 0.6167478 0.7271599 0.3343685 0.5587936 0.7589121 0.06834107 0.9778601 0.1977856 0.3590417 0.3771092 0.8537434 0.3753361 0.31779 0.8707079 0.3643074 0.2341829 0.9013537 0.1319286 0.90666 0.4007024 0.2733304 0.5897331 0.7599378 0.296286 0.4500275 0.842431 0.1913463 0.7747758 0.6025853 0.1898787 0.761756 0.6194142 0.229344 0.6444898 0.7294068 0.09856498 0.8866167 0.4518803 0.1569328 0.7773231 0.6092134 0.268992 0.3518376 0.8965789 0.3039914 0.239171 0.9221641 0.2019972 0.5656996 0.7994881 0.1004884 0.8855079 0.4536274 0.2207014 0.4305093 0.8751872 0.03320962 0.9796194 0.1980985 0.2425988 0.3675814 0.8977916 0.1371116 0.7212845 0.6789324 0.03898638 0.9607754 0.2745741 0.2207058 0.2126259 0.951882 0.153647 0.6407771 0.7521951 0.07953053 0.8329213 0.5476469 0.1001332 0.7662631 0.6346765 0.0307545 0.9454934 0.3241859 0.1244421 0.5629712 0.8170543 0.001123011 0.9993281 0.03663486 0.05172348 0.8574952 0.5118855 0.1503682 0.4155859 0.8970384 0.1375358 0.3343227 0.9323692 0.07238215 0.6690194 0.739712 0.1655864 0.2232495 0.960594 0.0870701 0.592112 0.8011381 0.07284468 0.5253626 0.8477547 0.02281993 0.8165248 0.5768592 0.09632521 0.3353309 0.9371632 0.08988487 0.3443944 0.9345124 -0.002373397 0.9457861 0.3247815 0.03904515 0.711888 0.7012069 0.00813955 0.827709 0.5610985 0.0401023 0.2982943 0.9536312 -0.007234871 0.9497925 0.312797 0.00378555 0.6337097 0.7735618 0.01529484 0.5345562 0.8449946 -0.0128799 0.9885329 0.150456 -6.79409e-4 0.4572343 0.889346 -0.02223843 0.8020536 0.596838 0.009731352 0.3208055 0.9470951 -0.03836822 0.7509338 0.659262 -0.02875125 0.6610376 0.7498018 -0.01285129 0.254991 0.966858 -0.04949641 0.9069888 0.4182361 -0.06713187 0.5236858 0.8492624 -0.03407496 0.9791752 0.2001371 -0.06348079 0.9155061 0.3972642 -0.06162244 0.9047978 0.4213593 -0.07986289 0.5085974 0.8572926 -0.08045053 0.5064747 0.8584935 -0.09517133 0.8116598 0.5763252 -0.08972799 0.7502693 0.6550153 -0.09786808 0.2772406 0.9558032 -0.09312659 0.2910471 0.9521655 -0.1102164 0.6768084 0.7278618 -0.04946333 0.9843848 0.1689377 -0.1260281 0.267154 0.9553773 -0.1595307 0.6065072 0.7789089 -0.1670912 0.4955078 0.8523806 -0.04945671 0.9844122 0.1687803 -0.1874087 0.4119274 0.8917365 -0.159752 0.7712183 0.6161994 -0.183997 0.3323953 0.9250181 -0.1839466 0.6605855 0.7278671 -0.2099918 0.2164822 0.9534353 -0.1100547 0.9163106 0.3850494 -0.1369335 0.8907892 0.4332944 -0.1690427 0.8139269 0.5558306 -0.2346439 0.5990315 0.765574 -0.2544688 0.1576375 0.9541469 -0.267182 0.4306052 0.8620865 -0.2625485 0.412087 0.8724979 -0.22737 0.7459663 0.6259691 -0.1068069 0.9626407 0.2488275 -0.2573679 0.6647071 0.7013745 -0.2791624 0.2192567 0.9348769 -0.1608679 0.9104661 0.3810158 -0.01188659 0.9995679 0.02688354 -0.311212 0.3999273 0.8620936 -0.3432822 0.2575099 0.903242 -0.2992007 0.6167815 0.7280519 -0.3219795 0.1710917 0.931159 -0.2143926 0.8702802 0.4434503 -0.333667 0.4974608 0.8007492 -0.09118515 0.9835039 0.1562225 -0.2518519 0.7934495 0.5540838 -0.316398 0.6878232 0.6532929 -0.3920071 0.2124844 0.895087 -0.2235864 0.8729547 0.4335427 -0.1002137 0.9809263 0.1665555 -0.3886349 0.4196591 0.8202738 -0.1678377 0.9474025 0.2725055 -0.3525159 0.65974 0.6636834 -0.4052915 0.2447352 0.8808198 -0.3738915 0.6238561 0.6863008 -0.2816306 0.8343 0.473949 -0.4207442 0.4670009 0.7777432 -0.4363076 0.4402683 0.784729 -0.3218979 0.7856587 0.5283202 -0.4765068 0.167091 0.8631465 -0.4708213 0.1872037 0.8621382 -0.2522296 0.8990015 0.3580176 -0.1247729 0.9794867 0.158233 -0.372417 0.7430744 0.556009 -0.4270582 0.6307177 0.6479325 -0.2659578 0.8944691 0.3594322 -0.4699782 0.5635721 0.6793431 -0.4874516 0.4393098 0.7545845 -0.3868347 0.7690659 0.5088187 -0.3968551 0.7607169 0.5136302 -0.5461185 0.2769268 0.7906113 -0.481851 0.621003 0.6182031 -0.5389412 0.192251 0.820111 -0.2514526 0.9207116 0.2984321 -0.4939357 0.5628467 0.6627452 -0.5594916 0.4329874 0.7067468 -0.5606182 0.2767829 0.7804477 -0.262135 0.9168162 0.3012197 -0.6051104 0.1789534 0.7757689 -0.07248002 0.9948133 0.07136648 -0.3592606 0.8527828 0.379069 -0.4303789 0.7698929 0.4712102 -0.5884554 0.4074077 0.6983833 -0.4582623 0.7423635 0.488766 -0.6356233 0.2419938 0.7330908 -0.5287199 0.6083342 0.5919332 -0.5864725 0.5130034 0.6267995 -0.171884 0.9739393 0.1479805 -0.4957668 0.7219879 0.4826478 -0.2302407 0.950411 0.2090652 -0.6487261 0.2207547 0.7283006 -0.5786701 0.6109843 0.5402213 -0.3419684 0.893208 0.2919541 -0.3854478 0.8548885 0.3472692 -0.6176836 0.4915506 0.6138771 -0.6386484 0.451638 0.623018 -0.4655579 0.7838381 0.4109181 -0.6773529 0.2789213 0.680732 -0.7159834 0.1843882 0.6733267 -0.6899788 0.3990792 0.6038751 -0.540691 0.7269662 0.4232887 -0.6113639 0.614028 0.4992033 -0.7372455 0.2268171 0.6364144 -0.3874342 0.8780189 0.2810298 -0.4662551 0.8217309 0.3276652 -0.6832503 0.4987856 0.5332749 -0.5354551 0.7458876 0.3961561 -0.2221565 0.9633943 0.1500599 -0.3175002 0.9258998 0.2047027 -0.7669015 0.1680356 0.6193756 -0.7163572 0.4621372 0.5227442 -0.1395528 0.9872481 0.07659184 -0.7787249 0.2845068 0.5591453 -0.6412675 0.6479802 0.4109716 -0.3437217 0.9160118 0.2068284 -0.4721804 0.8414469 0.262703 -0.7112316 0.5292794 0.4626154 -0.4997777 0.8165504 0.2889077 -0.6157194 0.7042277 0.3534871 -0.8211099 0.2026643 0.5335784 -0.7565917 0.4718856 0.4526511 -0.1915683 0.9774013 0.08937835 -0.2827403 0.9498688 0.1334436 -0.8260695 0.2785935 0.489893 -0.6835662 0.6416501 0.3478827 -0.383769 0.9087635 0.1639221 -0.7588589 0.5048633 0.4113954 -0.4828414 0.8425699 0.2386215 -0.5953146 0.7611337 0.2574412 -0.8271096 0.3927921 0.4020002 -0.6854833 0.6536365 0.3207367 -0.8642529 0.2265363 0.449164 -0.8751119 0.1856369 0.4468982 -0.748172 0.5801751 0.3219247 -0.4248431 0.891873 0.1551477 -0.1523364 0.9869454 0.05227231 -0.5890556 0.7746273 0.2301441 -0.82973 0.4157582 0.3724156 -0.4195812 0.8963772 0.1430369 -0.8745097 0.3345003 0.3512012 -0.6407185 0.7360051 0.2185783 -0.2960593 0.9518602 0.07944369 -0.9022322 0.2057179 0.3790213 -0.7759731 0.5725302 0.2647171 -0.04139059 0.9991052 0.008702397 -0.7765654 0.571776 0.2646101 -0.5922834 0.7906379 0.1552168 -0.876168 0.3775291 0.2996689 -0.9042369 0.3198162 0.2829722 -0.5962515 0.788393 0.151396 -0.6518927 0.7436842 0.1482224 -0.9161978 0.3039423 0.2611524 -0.3205767 0.9452382 0.06128185 -0.9401258 0.2358228 0.2460715 -0.7945876 0.5776587 0.1869259 -0.4224457 0.9039237 0.06679463 -0.8217869 0.5398293 0.1823478 -0.1503241 0.988505 0.01614195 -0.4304094 0.9003127 0.06468987 -0.8492147 0.5047495 0.1551203 -0.8643198 0.4799886 0.1502075 -0.6696727 0.7382922 0.08039355 -0.6685243 0.7392955 0.08073151 -0.9571214 0.2315442 0.1740862 -0.9488973 0.2702972 0.1628912 -0.6895796 0.7216174 0.06122422 -0.4179995 0.9082354 0.01962202 -0.4996905 0.8661658 0.00815165 -0.875053 0.4797646 0.06409472 -0.8612817 0.5031276 0.07110977 -0.2850395 0.9584914 -0.00685054 -0.6551773 0.7551538 0.02203571 -0.957852 0.2752965 0.08204561 -0.9472469 0.3131242 0.06838566 -0.2623771 0.9649435 -0.006500601 -0.6937756 0.7201643 -0.006227791 -0.9550987 0.2931897 0.04273521 -0.4842976 0.8740841 -0.03785449 -0.4451799 0.8945953 -0.0389142 -0.8042737 0.5935564 -0.02889126 -0.8579726 0.5136679 -0.005327343 -0.5826221 0.8110759 -0.05203282 -0.1610893 0.986694 -0.02202939 -0.9345615 0.3555197 -0.01416707 -0.9515873 0.3042588 -0.04368269 -0.8074536 0.5887138 -0.03787797 -0.6179667 0.7830948 -0.06985616 -0.9186053 0.3840828 -0.09297859 -0.951271 0.3043648 -0.04945325 -0.7659546 0.6371544 -0.08571916 -0.7928621 0.5992113 -0.1109746 -0.09644538 0.995168 -0.01840752 -0.615472 0.7805227 -0.1094478 -0.9163807 0.3838151 -0.1137216 -0.9246628 0.3590053 -0.1269413 -0.3981333 0.9130758 -0.0882197 -0.7626757 0.628839 -0.151286 -0.4071375 0.9089959 -0.08925032 -0.5174022 0.8470481 -0.1216738 -0.2167747 0.9734433 -0.07359987 -0.9254761 0.353459 -0.1362379 -0.3185986 0.9429519 -0.09662628 -0.7745459 0.6096302 -0.1686117 -0.9633347 0.1891731 -0.1902626 -0.5623254 0.8121285 -0.1556845 -0.8760052 0.4390284 -0.1996723 -0.9010943 0.3648131 -0.2343944 -0.7072176 0.6771973 -0.2030941 -0.7203074 0.6553473 -0.227326 -0.9619752 0.1889074 -0.1972764 -0.8117299 0.5084381 -0.2873769 -0.900959 0.3628315 -0.2379625 -0.9317639 0.230039 -0.2808884 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.01498645 0.007621705 -0.004126071 0.01498681 0.02912169 -0.00408107 0.01568067 0.007621705 0.001274943 0.01567405 0.02912169 0.001273632 0.01556289 0.007621705 0.001199066 0.01556116 0.02912169 0.001195132 0.01550757 0.02912169 0.00107634 0.01550745 0.007621705 0.001073122 0.01681751 0.02912169 0.001359879 0.01553267 0.02912169 -7.93039e-4 0.01694262 0.02912169 0.001280546 0.01700824 0.02912169 0.001143813 0.01699668 0.02912169 -0.00126791 0.01526272 0.02912169 -0.002885758 0.01506799 0.02912169 -0.004264831 0.01673442 0.02912169 -0.003177821 0.01617217 0.02912169 -0.004597485 0.01642107 0.02912169 -0.004476249 0.01630073 0.02912169 -0.004583239 0.0168516 0.007621705 0.001353979 0.01554292 0.007621705 -6.78966e-5 0.01699161 0.007621705 0.001203119 0.01704114 0.007621705 -1.39976e-4 0.01545673 0.007621705 -0.001578688 0.01694887 0.007621705 -0.001735985 0.01523798 0.007621705 -0.003011345 0.01510548 0.007621705 -0.004285871 0.01670712 0.007621705 -0.003316342 0.01623082 0.007621705 -0.004603743 0.01640713 0.007621705 -0.004502356 + + + + + + + + + + -0.541409 -1.16438e-4 0.8407595 -0.5711299 1.06082e-4 0.8208597 -0.9113848 2.84061e-6 0.4115554 -0.9152567 -5.66226e-5 0.4028713 0 1 0 0 1 1.13969e-6 0 1 -2.51982e-6 0 1 4.14681e-6 0 -1 0 0 -1 5.15482e-7 0 -1 0 0 -1 0 0 -1 -1.31526e-6 0 -1 9.50932e-7 0 -1 -1.13677e-6 -0.9754698 -4.43914e-4 0.2201328 -0.9743844 -1.94625e-4 0.2248892 -0.9917817 -0.001172959 0.127937 -0.9885452 2.53707e-4 0.1509253 -0.9983764 0.001444399 0.05694413 -0.9999095 -9.29491e-4 -0.01342439 -0.9995179 9.28791e-6 -0.03105068 -0.2884466 -5.07273e-4 -0.9574959 -0.2718167 4.6865e-4 -0.962349 0.9720879 2.7666e-4 -0.2346172 0.9694634 -3.31052e-4 -0.2452359 0.9907039 7.59049e-4 -0.1360346 0.9885 -2.81532e-4 -0.151221 0.999987 0.001817226 -0.00478208 0.9983325 -9.63404e-4 -0.05771696 0.9993206 -6.69882e-4 0.03685086 -0.07521766 -3.93197e-4 0.9971671 -0.06736385 3.90628e-5 0.9977285 0.901562 4.97622e-4 0.4326499 0.732893 -7.78917e-4 0.6803436 0.5356041 6.16937e-4 0.8444691 0.1099829 5.89599e-4 -0.9939333 0.4985246 -7.95437e-4 -0.8668752 0.6644214 4.75109e-4 -0.747358 -0.9147102 8.62279e-4 -0.4041096 -0.8019676 -8.1262e-4 -0.5973672 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.0117222 0.007621705 -0.01015096 0.01173007 0.02912169 -0.01013833 0.0146417 0.007621705 -0.005629539 0.01461595 0.02912169 -0.005625903 0.01445543 0.007621705 -0.005693852 0.01443707 0.02912169 -0.005717396 0.0157566 0.02912169 -0.00607264 0.0139299 0.02912169 -0.006841063 0.01581627 0.02912169 -0.006265699 0.01518213 0.02912169 -0.007707476 0.01325881 0.02912169 -0.008052945 0.01394182 0.02912169 -0.009760081 0.01248455 0.02912169 -0.009201526 0.01169669 0.02912169 -0.01026618 0.01174122 0.02912169 -0.01040273 0.01261305 0.02912169 -0.01116985 0.01281613 0.02912169 -0.01115387 0.01569426 0.007621705 -0.006030976 0.01578241 0.007621705 -0.006118714 0.01581591 0.007621705 -0.006269752 0.01527827 0.007621705 -0.007499217 0.01359301 0.007621705 -0.007482767 0.01450258 0.007621705 -0.008897304 0.01261293 0.007621705 -0.009037971 0.01169884 0.007621705 -0.01028704 0.01359903 0.007621705 -0.01021629 0.01174443 0.007621705 -0.01040619 0.01256513 0.007621705 -0.01114141 0.01283127 0.007621705 -0.01114207 0.01268333 0.007621705 -0.01118004 + + + + + + + + + + -0.3263909 -5.49623e-4 0.9452347 -0.4552252 5.85649e-4 0.8903762 0 1 -5.88105e-6 0 1 0 0 1 1.7192e-6 0 1 6.54427e-6 0 1 -1.73314e-6 0 1 -1.7272e-6 0 1 2.21725e-5 0 1 -1.67984e-6 0 1 6.47215e-6 0 1 -2.7442e-5 0 -1 -5.47238e-6 0 -1 -2.65561e-7 0 -1 0 0 -1 -3.00264e-7 0 -1 3.83937e-7 0 -1 3.83347e-7 0 -1 3.68316e-6 0 -1 -4.45674e-5 -0.780754 -8.14862e-5 0.6248387 -0.7788418 1.19015e-4 0.6272205 -0.8291791 -7.00628e-4 0.5589829 -0.8748393 -7.50759e-4 0.484413 -0.8460265 9.89237e-4 0.5331399 -0.9114533 -3.28894e-4 0.4114032 -0.9007814 0.001152217 0.4342714 -0.6605769 4.80304e-4 -0.7507583 -0.667258 2.02709e-5 -0.7448267 0.7779637 9.27803e-4 -0.6283086 0.7697475 1.90766e-4 -0.6383486 0.824995 -0.001162588 -0.5651389 0.855883 0.00156784 -0.5171672 0.8744247 -7.89296e-4 -0.4851607 0.9153668 6.13411e-5 -0.402621 0.9162157 2.15754e-4 -0.4006856 0.364658 7.46457e-4 0.9311413 0.3563466 2.69147e-4 0.9343538 0.9554138 5.14962e-4 0.29527 0.9763128 -5.74243e-5 0.2163639 0.705271 -6.72314e-4 0.7089375 -0.3107171 -5.63871e-4 -0.9505023 0.07814884 7.29556e-4 -0.9969415 0.2485132 -3.57164e-4 -0.9686285 -0.967511 2.06235e-4 0.2528289 -0.9855346 -2.61757e-4 0.1694748 -0.9507291 2.07131e-4 -0.3100227 -0.9339069 -8.15777e-5 -0.3575164 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.006113767 0.007621705 -0.01423162 0.006137907 0.02912169 -0.01421386 0.01074469 0.007621705 -0.01141148 0.01074451 0.02912169 -0.01141095 0.01059669 0.007621705 -0.01137483 0.01059257 0.02912169 -0.01137512 0.01047897 0.007621705 -0.01141655 0.01047688 0.02912169 -0.01141798 0.01154673 0.02912169 -0.01228713 0.00961703 0.02912169 -0.01214641 0.01150721 0.02912169 -0.01250731 0.009587049 0.02912169 -0.01403355 0.008491456 0.02912169 -0.01295399 0.007241249 0.02912169 -0.01368641 0.006041109 0.02912169 -0.01438981 0.007930338 0.02912169 -0.01501929 0.006478071 0.02912169 -0.01547926 0.006743848 0.02912169 -0.01557707 0.006599307 0.02912169 -0.01557451 0.01152938 0.007621705 -0.0122534 0.009618878 0.007621705 -0.01214873 0.01153624 0.007621705 -0.01245874 0.01049667 0.007621705 -0.01336503 0.00838387 0.007621705 -0.01302331 0.009191393 0.007621705 -0.01428794 0.007127642 0.007621705 -0.01374542 0.006044924 0.007621705 -0.01441788 0.007804989 0.007621705 -0.01508432 0.006502747 0.007621705 -0.01551622 0.006692826 0.007621705 -0.01558887 + + + + + + + + + + 0.2406677 -2.24898e-5 0.9706076 0.2296027 5.81516e-5 0.9732845 -0.3475219 2.94579e-5 0.9376719 -0.3341895 -5.03599e-5 0.9425059 0 1 0 0 1 -9.63031e-6 0 1 -3.38077e-6 0 1 -4.08036e-6 0 -1 0 0 -1 0 0 -1 -7.58602e-7 0 -1 -4.18782e-7 0 -1 7.59319e-7 0 -1 -1.11728e-6 0 -1 1.02956e-5 -0.4324001 -2.61604e-4 0.9016819 -0.4312643 -1.97513e-4 0.9022257 -0.5054919 -2.53725e-4 0.8628314 -0.4983492 2.53724e-4 0.8669764 -0.5829465 -1.35007e-4 0.8125106 -0.5779575 2.5974e-4 0.8160669 -0.6463981 -1.35066e-4 0.7630003 -0.6481888 -1.20756e-5 0.7614797 -0.9281212 -4.25786e-4 -0.3722783 -0.923025 3.3648e-4 -0.38474 0.4254565 2.56441e-4 -0.9049789 0.4131456 -4.81534e-4 -0.9106649 0.5113331 7.58705e-4 -0.8593823 0.4980884 -2.81526e-4 -0.8671264 0.6222313 0.001983761 -0.7828311 0.577328 -9.63182e-4 -0.8165118 0.6571312 -8.15849e-4 -0.7537759 0.7375339 4.64262e-4 0.67531 0.7315183 -1.06248e-5 0.6818219 0.9842545 9.28695e-4 -0.1767545 0.9994482 -7.54559e-4 0.03320658 -0.6178079 6.42745e-4 -0.7863289 -0.3570139 -9.29126e-4 -0.9340987 -0.01769983 5.9014e-4 -0.9998432 -0.8761461 5.84464e-4 0.4820453 -0.938 -6.20903e-4 0.3466346 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -6.2838e-4 0.007621705 -0.01544636 -6.74027e-4 0.02912169 -0.0154525 0.004716694 0.007621705 -0.01492655 0.004709839 0.02912169 -0.01491302 0.004605114 0.007621705 -0.01482874 0.00453937 0.02912169 -0.01480519 0.004491686 0.007621705 -0.01481157 0.005056917 0.02912169 -0.01603394 0.003317713 0.02912169 -0.01511055 0.004965782 0.02912169 -0.01621389 0.004100978 0.02912169 -0.01646488 0.00253427 0.02912169 -0.01678282 0.001951634 0.02912169 -0.01534157 5.70867e-4 0.02912169 -0.01545232 -8.23035e-4 0.02912169 -0.01558762 6.13943e-4 0.02912169 -0.01695215 -7.58862e-4 0.02912169 -0.01692569 -8.89748e-4 0.02912169 -0.01676958 0.00505799 0.007621705 -0.01605361 0.004945874 0.007621705 -0.01622605 0.003643572 0.007621705 -0.01657521 0.00222218 0.007621705 -0.01531386 0.002067148 0.007621705 -0.01684033 4.42911e-4 0.007621705 -0.01545619 -7.53079e-4 0.007621705 -0.01549947 4.72809e-4 0.007621705 -0.01695632 -8.31808e-4 0.007621705 -0.01562279 -8.95445e-4 0.007621705 -0.01672279 -8.54226e-4 0.007621705 -0.01683795 -7.31941e-4 0.007621705 -0.01693284 + + + + + + + + + + 0.6591496 -2.63986e-4 0.752012 0.5344958 7.08053e-4 0.845171 0.1496469 -6.26071e-4 0.9887394 0 1 0 0 1 6.85124e-6 0 1 -1.53446e-6 0 1 -5.03963e-6 0 1 4.0661e-6 0 1 -3.45e-5 0 -1 0 0 -1 5.08579e-7 0 -1 1.68801e-7 0 -1 -2.37186e-7 0 -1 1.19671e-6 0.009137809 3.02811e-4 0.9999583 -1.43534e-4 -1.79263e-4 1 -0.07994401 2.77665e-4 0.9967994 -0.07971906 2.94905e-4 0.9968174 -0.1667263 -8.28174e-4 0.9860029 -0.2425029 2.49233e-4 0.9701507 -0.2160861 0.001778125 0.9763728 -0.9984107 3.87081e-4 0.05635476 -0.9983309 3.12968e-4 0.05775344 -0.01925218 3.21532e-4 -0.9998147 -0.01950657 3.06977e-4 -0.9998097 0.08784019 7.5886e-4 -0.9961343 0.07254344 -2.81529e-4 -0.9973652 0.1988502 7.97352e-4 -0.9800297 0.1658763 -9.63167e-4 -0.9861461 0.2787216 2.82876e-4 -0.9603719 0.2589749 -5.54392e-4 -0.965884 0.9552595 -2.21734e-4 0.2957691 0.9570785 1.22871e-4 0.2898288 0.8383038 -4.69206e-4 -0.5452032 0.8921336 4.58138e-4 -0.4517714 -0.9414701 -4.83394e-4 -0.3370964 -0.7663717 7.76964e-4 -0.642397 -0.6130624 -5.05751e-4 -0.7900343 -0.3916257 -5.70669e-4 0.9201245 -0.6718454 8.51744e-4 0.7406909 -0.8428711 -5.3557e-4 0.5381153 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.007333755 0.007621705 -0.01360768 -0.002241253 0.007621705 -0.01548248 -0.002241432 0.02912169 -0.01546323 -0.002283692 0.007621705 -0.01535999 -0.002299964 0.02912169 -0.01534086 -0.002389788 0.007621705 -0.01527184 -0.002394437 0.02912169 -0.01527011 -0.002412974 0.02912169 -0.01661372 -0.003872215 0.02912169 -0.01496505 -0.002513527 0.02912169 -0.01671129 -0.002619922 0.02912169 -0.01674437 -0.004147827 0.02912169 -0.01644665 -0.006424903 0.02912169 -0.0156942 -0.005849182 0.02912169 -0.01430779 -0.007334589 0.02912169 -0.01360714 -0.007525026 0.02912169 -0.01367247 -0.008073449 0.02912169 -0.01464951 -0.008092343 0.02912169 -0.01475828 -0.008027851 0.02912169 -0.01491254 -0.00241512 0.007621705 -0.01662021 -0.003519833 0.007621705 -0.01504939 -0.002579629 0.007621705 -0.01674318 -0.004341602 0.007621705 -0.01639628 -0.004973709 0.007621705 -0.01462912 -0.006609618 0.007621705 -0.01561707 -0.006321787 0.007621705 -0.01409703 -0.007522225 0.007621705 -0.01367002 -0.008083879 0.007621705 -0.01467472 -0.008025825 0.007621705 -0.01491361 -0.008085668 0.007621705 -0.01479119 + + + + + + + + + + 0.9448868 -2.85718e-4 0.3273974 0.9021568 2.97725e-4 0.4314081 0.5992122 6.6757e-5 0.8005903 0.6391847 -2.01554e-4 0.7690534 0 1 -9.18681e-5 0 1 -7.62136e-6 0 1 -6.4488e-5 0 1 0 0 1 -6.96144e-6 0 1 -2.33263e-6 0 1 1.01587e-6 0 1 3.15556e-5 0 1 1.88501e-5 0 1 1.1443e-5 0 -1 0 0 -1 -8.15434e-7 0 -1 6.11419e-6 0.4353621 -6.52925e-6 0.9002556 0.4266347 -5.12578e-4 0.904424 0.3671281 0.001048028 0.9301698 0.3154686 -0.00133568 0.9489351 0.2776835 7.83536e-4 0.9606724 0.2021816 -5.27352e-4 0.9793479 0.193145 -3.55459e-5 0.9811703 -0.8720179 -1.5172e-4 0.4894741 -0.8728819 -5.72582e-5 0.4879316 -0.4383212 5.41203e-4 -0.8988183 -0.444865 4.18857e-6 -0.8955977 -0.3137523 6.01755e-4 -0.9495047 -0.3249021 -6.01436e-4 -0.9457475 -0.1912732 -4.14173e-4 -0.9815368 -0.1931858 -5.5903e-4 -0.9811621 0.9890713 -5.4441e-5 -0.1474384 0.9885289 1.43371e-4 -0.151032 0.2971681 5.02273e-4 -0.9548251 0.5987182 -6.53259e-4 -0.8009595 0.6963607 1.46529e-4 -0.717692 -0.9852367 2.76923e-4 0.1711978 -0.9998813 -3.34387e-4 0.01540732 -0.9225593 3.03523e-4 -0.3858553 -0.898419 -6.1926e-5 -0.4391393 -0.3246134 6.73239e-5 0.9458468 -0.3139183 -3.677e-5 0.9494501 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.01251775 0.007621705 -0.009065032 -0.01252192 0.02912169 -0.009060561 -0.008740723 0.007621705 -0.01293122 -0.008760452 0.02912169 -0.01297384 -0.008733987 0.02912169 -0.01286703 -0.008749961 0.007621705 -0.01277685 -0.008780181 0.02912169 -0.01271557 -0.008801221 0.007621705 -0.0126987 -0.009372174 0.02912169 -0.01387554 -0.009996712 0.02912169 -0.0117821 -0.00950241 0.02912169 -0.01394587 -0.009647607 0.02912169 -0.01392507 -0.01088768 0.02912169 -0.01299756 -0.01261281 0.02912169 -0.01133167 -0.0114926 0.02912169 -0.01033228 -0.01272088 0.02912169 -0.009030461 -0.0136615 0.02912169 -0.009690225 -0.01370483 0.02912169 -0.009958505 -0.01372367 0.02912169 -0.009815275 -0.009382247 0.007621705 -0.0138868 -0.009499073 0.007621705 -0.01394152 -0.009630858 0.007621705 -0.01393371 -0.01104038 0.007621705 -0.0128681 -0.010315 0.007621705 -0.01149827 -0.01134741 0.007621705 -0.01048117 -0.01245266 0.007621705 -0.01149588 -0.01271122 0.007621705 -0.009027302 -0.01367664 0.007621705 -0.01001119 -0.01369208 0.007621705 -0.00972259 -0.01372379 0.007621705 -0.009886205 + + + + + + + + + + 0.9705734 4.14417e-4 -0.2408049 0.9982015 -4.92411e-4 0.05994749 0.9563959 5.12425e-4 0.2920734 0.8360406 -3.87506e-4 0.5486673 0 1 0 0 1 2.69112e-6 0 1 1.05514e-4 0 1 1.91108e-6 0 1 -5.67463e-6 0 1 5.74055e-6 0 1 -1.01588e-6 0 1 2.03394e-7 0 -1 -7.90539e-6 0 -1 0 0 -1 8.12774e-7 0 -1 5.49463e-6 0 -1 -6.31886e-7 0 -1 5.32056e-7 0.7772914 2.00647e-5 0.6291408 0.7708184 7.95046e-4 0.6370545 0.6959648 -8.23959e-4 0.7180755 0.7018246 -1.92472e-4 0.7123498 0.6087745 2.67438e-5 0.7933434 0.6213563 0.001144766 0.7835274 -0.5742522 -4.14839e-4 0.8186784 -0.5783019 -1.39892e-4 0.8158229 -0.7826632 4.97463e-4 -0.6224453 -0.7716044 -8.88514e-4 -0.6361023 -0.6946572 6.01708e-4 -0.7193408 -0.6968631 2.87697e-4 -0.7172042 -0.5989329 -1.44015e-4 -0.8007993 -0.6030606 -5.20662e-4 -0.7976952 0.8275542 -9.37974e-5 -0.5613859 0.8302535 -3.41498e-4 -0.5573861 -0.1421568 2.88547e-4 -0.9898442 -0.05923652 -2.11367e-4 -0.998244 0.4241829 -1.17094e-4 -0.9055765 0.475152 2.38347e-4 -0.8799037 -0.8953623 6.04197e-4 0.4453382 -0.9817329 -6.22676e-4 0.1902638 -0.9914615 4.34638e-4 -0.1304 -0.935624 -3.63309e-4 -0.3529984 0.1916014 -1.66844e-4 0.9814728 0.1497332 2.12951e-4 0.9887265 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.015217 0.007621705 -0.00273931 -0.0152176 0.02912169 -0.002734303 -0.01350194 0.007621705 -0.007838964 -0.01350134 0.02912169 -0.007838964 -0.01343584 0.007621705 -0.007651448 -0.01343625 0.02912169 -0.007648169 -0.0144965 0.02912169 -0.008421063 -0.01400536 0.02912169 -0.006527006 -0.01463812 0.02912169 -0.008414983 -0.01474493 0.02912169 -0.008344411 -0.01546353 0.02912169 -0.006965756 -0.01453441 0.02912169 -0.005246818 -0.01629495 0.02912169 -0.004716455 -0.01494967 0.02912169 -0.003925263 -0.01532077 0.02912169 -0.00262618 -0.01544189 0.02912169 -0.002595841 -0.01654136 0.02912169 -0.002787232 -0.01668328 0.02912169 -0.003001093 -0.01664233 0.02912169 -0.002877712 -0.01454168 0.007621705 -0.008434593 -0.01413804 0.007621705 -0.006259441 -0.01473331 0.007621705 -0.008359432 -0.01554495 0.007621705 -0.006782889 -0.01478588 0.007621705 -0.004499137 -0.01634985 0.007621705 -0.004523992 -0.01530617 0.007621705 -0.002634465 -0.01543426 0.007621705 -0.002595722 -0.01653808 0.007621705 -0.002785682 -0.01668304 0.007621705 -0.002984404 -0.01663213 0.007621705 -0.002864718 + + + + + + + + + + 0.9464077 6.67314e-5 -0.3229747 0.9431174 -2.60701e-5 -0.3324599 0 1 8.76565e-6 0 1 0 0 1 -8.52288e-7 0 1 -3.16455e-6 0 1 1.73332e-6 0 1 -1.72709e-6 0 1 8.35207e-7 0 -1 0 0 -1 2.52678e-7 0 -1 6.58337e-7 0 -1 0 0 -1 -7.8488e-6 0.9756196 -2.60594e-5 0.2194684 0.9712733 0.001048326 0.2379643 0.9540137 -7.32893e-4 0.2997621 0.9241817 -9.49893e-4 0.381952 0.9384612 0.00103563 0.3453834 0.8916985 1.29999e-4 0.4526301 0.8928347 -5.2127e-5 0.4503846 -0.1714857 4.34205e-5 0.9851866 -0.1696318 -5.39706e-5 0.9855075 -0.9753212 5.11745e-4 -0.2207903 -0.9773728 -1.76178e-4 -0.2115244 -0.9379737 6.01454e-4 -0.3467059 -0.9419876 -6.01371e-4 -0.335647 -0.8867608 -1.57377e-4 -0.4622287 -0.889089 -5.27809e-4 -0.4577341 0.5049323 -5.20288e-4 -0.8631589 0.4970504 -1.26193e-5 -0.8677218 -0.5515111 2.82993e-4 -0.8341675 -0.3652037 -7.91638e-4 -0.9309273 -0.04282945 7.16631e-4 -0.9990822 -0.6673916 1.34357e-4 0.7447071 -0.6431232 -4.41621e-5 0.7657628 -0.9203364 -1.99908e-4 0.391128 -0.9491302 2.32832e-4 0.3148839 0.7618125 -1.31471e-4 0.6477977 0.7235112 2.23969e-4 0.6903127 0.2428447 9.23207e-5 0.9700652 0.2898175 -1.73965e-4 0.957082 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.01491373 0.007621705 0.004142522 -0.014912 0.02912169 0.004155635 -0.01555651 0.007621705 -0.001175522 -0.01555591 0.02912169 -0.00117582 -0.01543718 0.007621705 -0.001023173 -0.01543557 0.02912169 -0.001018345 -0.01675432 0.02912169 -0.001273155 -0.0169081 0.02912169 -0.001142621 -0.01696914 0.02912169 4.54026e-4 -0.01543343 0.02912169 0.001148819 -0.01674228 0.02912169 0.002841293 -0.01518696 0.02912169 0.002970457 -0.01494455 0.02912169 0.004277944 -0.01503282 0.02912169 0.004372477 -0.01614403 0.02912169 0.004687607 -0.01635199 0.02912169 0.004545629 -0.01627963 0.02912169 0.004632949 -0.01670926 0.007621705 -0.001278519 -0.0168451 0.007621705 -0.001221418 -0.0169214 0.007621705 -0.001093804 -0.01696538 0.007621705 2.24701e-4 -0.01541942 0.007621705 0.00132972 -0.01687312 0.007621705 0.001820743 -0.01516222 0.007621705 0.003096103 -0.014934 0.007621705 0.004257678 -0.01502412 0.007621705 0.004367709 -0.01663136 0.007621705 0.003401041 -0.01613819 0.007621705 0.004687666 -0.01634591 0.007621705 0.004558861 -0.01626574 0.007621705 0.004642188 + + + + + + + + + + 0.7946467 7.64087e-5 -0.6070722 0.7873624 -3.06671e-5 -0.6164906 0 1 0 0 1 -1.41195e-5 0 1 1.93934e-6 0 1 6.49298e-7 0 1 2.94881e-5 0 1 -2.10462e-6 0 1 1.2168e-5 0 -1 8.7581e-6 0 -1 2.58479e-7 0 -1 0 0 -1 -6.28031e-7 0 -1 0 0 -1 2.84756e-7 0 -1 9.52179e-7 0 -1 -8.57402e-7 0 -1 -3.25457e-5 0.9729375 6.26143e-5 -0.2310687 0.9741288 -2.01351e-4 -0.2259939 0.9909697 -4.82898e-4 -0.134086 0.9895663 2.94908e-4 -0.1440783 0.9999996 -7.45768e-5 -9.97832e-4 0.9999714 5.87662e-4 -0.00755304 0.2728163 7.68532e-5 0.9620662 0.2760151 -1.00949e-4 0.9611533 -0.9747668 7.82734e-4 0.2232246 -0.9709188 -1.28741e-4 0.2394094 -0.9884994 -0.001162588 0.1512204 -0.9955143 0.001567542 0.09459877 -0.9983327 -7.89252e-4 0.05771744 -0.9992696 5.30869e-4 -0.03821146 -0.9994429 1.82124e-4 -0.03337317 0.08093488 4.18331e-4 -0.9967193 0.08900094 -1.76158e-5 -0.9960317 -0.8583935 -6.33353e-4 -0.5129916 -0.647152 8.9937e-4 -0.7623605 -0.3874101 -5.81358e-4 -0.9219073 -0.37396 1.56426e-4 0.9274448 -0.3358681 -8.98168e-5 0.941909 -0.7208172 -1.67979e-4 0.6931253 -0.7700604 1.73547e-4 0.6379709 0.984807 -1.85113e-4 0.1736522 0.9662883 2.31267e-4 0.2574626 0.7738543 -2.18111e-4 0.6333636 0.7310678 1.4459e-4 0.6823049 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.01165378 0.007621705 0.01022648 -0.01460063 0.007621705 0.00572139 -0.0145359 0.02912169 0.005710303 -0.01446503 0.007621705 0.005729973 -0.01435905 0.02912169 0.005805552 -0.01435619 0.007621705 0.005814492 -0.01564997 0.02912169 0.006134569 -0.01385414 0.02912169 0.006925702 -0.01572889 0.02912169 0.006257534 -0.01573252 0.02912169 0.006396114 -0.01489907 0.02912169 0.008168339 -0.01318311 0.02912169 0.008137643 -0.01386612 0.02912169 0.00984472 -0.01240873 0.02912169 0.009286344 -0.01164156 0.02912169 0.01024353 -0.01162558 0.02912169 0.01038628 -0.01167213 0.02912169 0.01049536 -0.01272976 0.02912169 0.01124584 -0.01252597 0.02912169 0.01124864 -0.01567137 0.007621705 0.006149172 -0.01574248 0.007621705 0.006341993 -0.0152024 0.007621705 0.007584095 -0.01351714 0.007621705 0.007567644 -0.01446253 0.007621705 0.008921205 -0.01275533 0.007621705 0.008800387 -0.01161938 0.007621705 0.0103594 -0.0135672 0.007621705 0.01024556 -0.01167267 0.007621705 0.0104956 -0.01254898 0.007621705 0.01126074 -0.0127505 0.007621705 0.01123064 + + + + + + + + + + 0.06300199 -7.05596e-4 -0.9980133 0.4742496 7.57636e-4 -0.8803902 0.6132209 -2.46069e-4 -0.7899114 0 1 1.21233e-5 0 1 0 0 1 2.83822e-5 0 1 -1.89281e-6 0 1 1.72694e-6 0 1 1.67392e-6 0 1 -2.57689e-5 0 -1 0 0 -1 -5.23571e-7 0 -1 -3.06393e-7 0 -1 4.01455e-7 0 -1 -4.14067e-7 0 -1 6.61489e-7 0 -1 2.41667e-6 0 -1 -3.53473e-6 0 -1 -5.22958e-6 0.7803155 5.24167e-5 -0.6253862 0.7914078 0.001058459 -0.6112877 0.8291808 -7.32831e-4 -0.5589802 0.8748444 -7.50784e-4 -0.4844037 0.8506609 7.20014e-4 -0.5257143 0.9116699 -4.96565e-5 -0.4109236 0.9020209 0.001249015 -0.4316907 0.6615836 -2.87427e-4 0.7498714 0.657687 -6.61796e-6 0.7532914 -0.7766646 9.45811e-4 0.6299138 -0.7698268 2.9155e-4 0.6382529 -0.8284646 -0.001077055 0.5600405 -0.8513565 0.001080811 0.5245865 -0.8749617 -8.12968e-4 0.4841915 -0.904924 0.001202583 0.4255715 -0.9170657 -5.79677e-4 0.3987358 -0.355893 -2.81109e-4 -0.9345268 -0.3709868 6.36234e-4 -0.928638 -0.9996472 5.28209e-4 -0.02655762 -0.9382855 -7.64895e-4 -0.3458608 -0.8418118 4.70728e-4 -0.539771 -0.01370275 5.76887e-4 0.999906 -0.1476898 -5.56999e-4 0.9890336 0.9681474 -3.51804e-4 -0.2503808 0.9937803 4.23687e-4 -0.1113575 0.9196673 -2.27934e-4 0.3926985 0.9313493 -1.86526e-5 0.3641269 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.006041347 0.007621705 0.01431381 -0.006079256 0.02912169 0.01428788 -0.01066392 0.007621705 0.01149255 -0.01068341 0.02912169 0.01150721 -0.01055467 0.02912169 0.01145952 -0.01052731 0.007621705 0.01146095 -0.01041567 0.02912169 0.01149237 -0.01041311 0.007621705 0.01149433 -0.01146918 0.02912169 0.01236796 -0.009541273 0.02912169 0.01223117 -0.01144349 0.02912169 0.01256829 -0.0107851 0.02912169 0.013152 -0.009511411 0.02912169 0.01411819 -0.008415758 0.02912169 0.01303869 -0.007165372 0.02912169 0.01377123 -0.005991518 0.02912169 0.01439237 -0.007854819 0.02912169 0.01510393 -0.005975484 0.02912169 0.014535 -0.00642848 0.02912169 0.01560205 -0.006619155 0.02912169 0.01567381 -0.01145255 0.007621705 0.01233637 -0.009543061 0.007621705 0.01223349 -0.01146155 0.007621705 0.01254171 -0.01008379 0.007621705 0.01371568 -0.008308172 0.007621705 0.01310807 -0.008060574 0.007621705 0.01500308 -0.007051765 0.007621705 0.01383024 -0.00596857 0.007621705 0.01449841 -0.006429672 0.007621705 0.01560437 -0.006621301 0.007621705 0.01567292 + + + + + + + + + + -0.3474934 3.24041e-4 -0.9376824 -0.225396 -3.52709e-4 -0.9742671 0.2300741 2.26792e-4 -0.9731731 0.2802437 -5.30196e-5 -0.9599289 0 1 0 0 1 -8.62983e-6 0 1 2.2362e-5 0 1 -3.3804e-6 0 1 3.4446e-6 0 1 -4.16345e-6 0 -1 0 0 -1 1.03491e-6 0 -1 1.20189e-5 0 -1 -9.35468e-7 0 -1 8.74088e-7 0.4316736 -3.25391e-4 -0.9020298 0.429566 -2.08664e-4 -0.9030354 0.5054908 -2.53713e-4 -0.8628319 0.4983485 2.53696e-4 -0.8669768 0.5829432 -1.34975e-4 -0.812513 0.5779541 2.5978e-4 -0.8160693 0.6454038 -1.35028e-4 -0.7638416 0.6474719 9.2632e-6 -0.7620893 0.9204985 -9.62414e-6 0.3907462 0.9229925 -3.57164e-4 0.3848179 -0.4188004 -2.50564e-4 0.9080783 -0.4219273 4.41235e-6 0.9066297 -0.511349 8.63686e-4 0.8593728 -0.5368432 -0.001502633 0.8436807 -0.6043758 0.001174688 0.7966986 -0.6633747 -3.68523e-4 0.7482873 -0.6485763 -0.001199185 0.7611486 -0.7385304 4.20101e-4 -0.67422 -0.7305784 -1.96453e-4 -0.6828288 -0.9918866 6.77223e-4 0.1271246 -0.9990425 -7.06085e-4 -0.04374849 0.3521971 8.21741e-5 0.9359259 0.3367244 -7.22885e-5 0.9416034 0.7656998 5.75076e-4 -0.6431978 0.9303241 -8.16586e-4 -0.3667376 0.993777 5.10631e-4 -0.1113873 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 7.40541e-4 0.007621705 0.01553577 7.31492e-4 0.02912169 0.01553404 -0.004631936 0.007621705 0.01499468 -0.004627704 0.02912169 0.01498675 -0.004511237 0.007621705 0.01490819 -0.004451096 0.02912169 0.01489031 -0.004415988 0.007621705 0.01489633 -0.004978895 0.02912169 0.01609355 -0.003304243 0.02912169 0.01518034 -0.004943847 0.02912169 0.01622885 -0.004851043 0.02912169 0.01631987 -0.00402522 0.02912169 0.01654964 -0.002458512 0.02912169 0.01686751 -0.001939654 0.02912169 0.01541954 -4.95329e-4 0.02912169 0.01553702 8.43805e-4 0.02912169 0.01560217 9.06836e-4 0.02912169 0.01570284 -5.38235e-4 0.02912169 0.01703685 9.65502e-4 0.02912169 0.01685428 8.34617e-4 0.02912169 0.01701045 -0.004981935 0.007621705 0.0161255 -0.004881262 0.007621705 0.01630455 -0.003567755 0.007621705 0.01665997 -0.002530097 0.007621705 0.01533204 -0.001991391 0.007621705 0.01692509 -7.03218e-4 0.007621705 0.01553547 8.94437e-4 0.007621705 0.01566076 -3.97083e-4 0.007621705 0.01704108 9.64235e-4 0.007621705 0.01686316 8.26145e-4 0.007621705 0.01701247 + + + + + + + + + + -0.5824531 -1.85628e-4 -0.8128643 -0.4792021 6.10574e-4 -0.8777044 -0.1238176 -4.7931e-4 -0.9923049 0 1 -1.12399e-5 0 1 -2.42851e-5 0 1 0 0 1 -1.15479e-5 0 1 -1.29629e-4 0 1 -4.1763e-6 0 1 3.44992e-5 0 -1 0 0 -1 6.15264e-7 0 -1 -7.69141e-7 0 -1 5.76345e-7 0 -1 -1.10291e-6 2.10022e-4 -7.98753e-5 -1 -0.002427458 9.62111e-5 -0.9999971 0.08106285 -7.11335e-4 -0.9967088 0.1106678 0.001006543 -0.993857 0.1726861 -7.32798e-4 -0.9849767 0.245167 1.28859e-4 -0.9694809 0.2251121 0.001229941 -0.9743321 0.9987047 -7.98903e-5 -0.05088335 0.9983194 -4.62385e-4 -0.05795127 0.01925545 3.21639e-4 0.9998146 0.02334582 8.68508e-5 0.9997275 -0.08784073 7.58831e-4 0.9961342 -0.0725432 -2.81506e-4 0.9973653 -0.1988543 7.97322e-4 0.9800288 -0.1658741 -9.63214e-4 0.9861465 -0.2680312 -3.09477e-4 0.9634102 -0.2611671 -6.0414e-4 0.9652934 -0.9531668 -3.14934e-4 -0.3024452 -0.9552819 7.73817e-5 -0.2956968 -0.7002413 4.76181e-4 0.7139061 -0.8716187 -8.10559e-4 0.490184 -0.967985 5.09756e-4 0.2510079 0.7663701 2.20413e-4 0.6423993 0.7341833 -2.24069e-4 0.6789513 0.5184175 1.49812e-4 -0.8551276 0.6304696 -6.32035e-4 -0.7762138 0.8476106 5.48979e-4 -0.5306187 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.007364153 0.007621705 0.01370602 0.007367193 0.02912169 0.01370477 0.002317011 0.007621705 0.01556724 0.002321004 0.02912169 0.0155099 0.002358436 0.007621705 0.01544654 0.002454876 0.02912169 0.01536005 0.002456665 0.007621705 0.01536172 0.002491116 0.02912169 0.01670438 0.003657579 0.02912169 0.01511776 0.002651274 0.02912169 0.01682692 0.003539323 0.02912169 0.01667785 0.005088984 0.02912169 0.0162844 0.005674898 0.02912169 0.01449954 0.007503747 0.02912169 0.01370573 0.006892561 0.02912169 0.01560378 0.00761938 0.02912169 0.01377981 0.008173525 0.02912169 0.01480972 0.00810033 0.02912169 0.01500004 0.002476632 0.007621705 0.01666355 0.002550363 0.007621705 0.01677149 0.002687096 0.007621705 0.01682949 0.003999054 0.007621705 0.01657879 0.004357993 0.007621705 0.01493215 0.005941808 0.007621705 0.01599705 0.006092429 0.007621705 0.01432269 0.007506072 0.007621705 0.01370531 0.007622003 0.007621705 0.01378375 0.008050203 0.007621705 0.01503962 0.008166193 0.007621705 0.01477915 0.008143544 0.007621705 0.0149334 + + + + + + + + + + -0.9457915 -6.89874e-4 -0.3247738 -0.7457503 6.64375e-4 -0.6662253 -0.6538677 -1.11466e-4 -0.756609 0 1 3.07725e-5 0 1 4.34263e-6 0 1 -3.56882e-6 0 1 -3.42581e-5 0 1 2.30145e-6 0 1 0 0 1 -9.08974e-5 0 1 -2.40644e-6 0 1 -2.0678e-6 0 1 3.91942e-5 0 -1 0 0 -1 6.11084e-7 0 -1 -7.05447e-6 0 -1 -1.32592e-6 0 -1 -9.48398e-6 -0.4363106 8.64979e-6 -0.8997962 -0.4250939 -8.10139e-4 -0.9051489 -0.2929968 -0.001291811 -0.9561126 -0.331514 0.001322209 -0.9434494 -0.1975098 -9.11824e-5 -0.980301 -0.2203652 0.001240909 -0.9754167 0.8806173 3.74939e-4 -0.4738284 0.8774257 2.03592e-5 -0.4797126 0.4471357 6.04939e-4 0.894466 0.4134621 -0.00162959 0.91052 0.3530712 0.001499354 0.9355954 0.2460669 7.97131e-4 0.9692525 0.2868689 -0.001425743 0.9579688 0.1655762 3.94352e-4 0.9861969 0.1876989 -5.10655e-4 0.9822265 -0.990015 3.98109e-4 0.1409617 -0.9895671 5.68377e-4 0.1440727 -0.3907552 -5.40953e-4 0.9204944 -0.6077226 8.03242e-4 0.794149 -0.8256958 -5.15799e-4 0.5641156 0.9893691 -5.42639e-4 0.1454252 0.9333565 7.63276e-4 0.35895 0.7512255 -5.35832e-4 0.6600455 0.007175445 2.18579e-5 -0.9999743 -0.005151748 -5.7754e-5 -0.9999868 0.5396557 7.51465e-5 -0.8418858 0.5605063 -8.23047e-5 -0.8281502 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.01256287 0.007621705 0.009178578 0.01261085 0.02912169 0.009134829 0.008804857 0.007621705 0.01298147 0.008809983 0.02912169 0.01299971 0.008853137 0.02912169 0.01280337 0.008863985 0.007621705 0.01279234 0.009469747 0.02912169 0.01398271 0.009789526 0.02912169 0.0120936 0.009664833 0.02912169 0.01403427 0.01041048 0.02912169 0.01351118 0.01163583 0.02912169 0.01248443 0.01082724 0.02912169 0.01117604 0.01181972 0.02912169 0.01011991 0.01281219 0.02912169 0.009121775 0.01296555 0.02912169 0.01108866 0.01374757 0.02912169 0.009785234 0.01378548 0.02912169 0.01003384 0.01379787 0.02912169 0.009904503 0.009471356 0.007621705 0.01398479 0.009791374 0.007621705 0.01209586 0.009671032 0.007621705 0.01403284 0.01078188 0.007621705 0.01322227 0.01091879 0.007621705 0.01108658 0.01197206 0.007621705 0.01215517 0.01190251 0.007621705 0.01002228 0.01267206 0.007621705 0.009117543 0.01281821 0.007621705 0.009124934 0.01305681 0.007621705 0.0109809 0.01375389 0.007621705 0.009791493 0.01380383 0.007621705 0.009988605 + + + + + + + + + + -0.9767099 4.1586e-4 -0.214564 -0.954476 -3.27698e-4 -0.2982877 0 1 4.45072e-6 0 1 0 0 1 6.47537e-6 0 1 3.06414e-6 0 1 -1.73267e-6 0 -1 0 0 -1 7.58647e-7 0 -1 7.59405e-7 -0.7874996 5.03403e-4 -0.6163152 -0.7796981 -1.59876e-4 -0.6261558 -0.7287178 -2.5373e-4 -0.6848141 -0.7343461 2.53818e-4 -0.6787752 -0.6624193 -1.34984e-4 -0.7491333 -0.6669982 2.5982e-4 -0.7450593 -0.6040541 -1.35116e-4 -0.7969434 -0.6005066 1.07736e-4 -0.7996199 0.5785554 -6.45581e-5 -0.8156433 0.5802013 4.39655e-5 -0.8144733 0.7895175 2.76738e-4 0.6137282 0.7989247 -5.83818e-4 0.6014308 0.7240414 7.58812e-4 0.6897561 0.734542 -2.81562e-4 0.6785632 0.6422342 7.97268e-4 0.7665081 0.6675784 -9.63204e-4 0.7445389 0.5742992 1.12207e-4 0.8186456 0.5894179 -6.70269e-4 0.8078281 -0.830333 -9.07604e-6 0.5572677 -0.8329579 -2.6986e-4 0.5533363 -0.2553556 7.39857e-5 0.9668472 -0.2338129 -1.32155e-4 0.9722816 0.9212758 1.60147e-4 -0.3889099 0.9694305 -6.92823e-4 -0.2453652 0.9954196 6.48453e-4 0.09560078 -0.4878147 -6.875e-4 -0.8729469 -0.06458562 6.17827e-4 -0.997912 0.05040824 -1.31572e-4 -0.9987287 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.01530694 0.007621705 0.002787768 0.01528567 0.02912169 0.00284183 0.01360648 0.007621705 0.007947564 0.01355588 0.02912169 0.007902741 0.01352745 0.007621705 0.007837057 0.01352006 0.02912169 0.007704973 0.01352524 0.007621705 0.007697224 0.01460045 0.02912169 0.008514583 0.014081 0.02912169 0.006611883 0.01479452 0.02912169 0.008459508 0.01553928 0.02912169 0.007050514 0.01461017 0.02912169 0.005331516 0.01637071 0.02912169 0.004801332 0.01502537 0.02912169 0.00401014 0.01535093 0.02912169 0.002744317 0.01548659 0.02912169 0.002680063 0.01662886 0.02912169 0.00287652 0.01675921 0.02912169 0.003073215 0.01671665 0.02912169 0.002963244 0.01454597 0.007621705 0.008495509 0.01467365 0.007621705 0.008510887 0.01481306 0.007621705 0.008439302 0.01543641 0.007621705 0.007255494 0.01437276 0.007621705 0.005948185 0.0160458 0.007621705 0.005777418 0.01497763 0.007621705 0.004212439 0.01547443 0.007621705 0.002680957 0.01651364 0.007621705 0.004248797 0.01665467 0.007621705 0.002887666 0.01675862 0.007621705 0.003062784 + + + + + + + + + + -0.8133953 -7.01647e-4 0.5817109 -0.9840064 7.5544e-4 0.1781315 -0.9998726 -2.46376e-4 0.01596295 0 1 1.51536e-5 0 1 -1.72919e-6 0 1 0 0 1 3.91364e-6 0 1 1.73304e-6 0 1 8.63646e-7 0 1 -1.03386e-6 0 1 -4.72224e-6 0 1 -2.51705e-5 0 1 8.44379e-7 0 1 -1.61736e-6 0 -1 0 0 -1 5.50228e-7 0 -1 3.23499e-6 0 -1 -1.92282e-7 0 -1 -5.56049e-7 0 -1 -1.36863e-6 -0.9743066 -3.9737e-4 -0.2252255 -0.9760693 1.22829e-4 -0.2174597 -0.9540135 -7.00606e-4 -0.299763 -0.9241794 -7.50777e-4 -0.3819578 -0.9443143 9.89134e-4 -0.3290435 -0.8896868 -5.00111e-5 -0.4565714 -0.89991 0.001249015 -0.436074 0.1695096 -3.08037e-4 -0.9855285 0.1725156 -1.39662e-4 -0.9850069 0.975644 8.49648e-4 0.2193585 0.9793317 -1.27057e-4 0.2022608 0.9562199 -0.001162588 0.2926471 0.9379706 0.00156778 0.3467116 0.9245087 -7.89229e-4 0.3811602 0.8840875 3.23923e-4 0.4673212 0.8848236 2.08787e-4 0.4659262 -0.5054469 5.14639e-4 0.8628575 -0.5038248 6.15488e-4 0.8638057 0.4566184 -4.41691e-4 0.8896626 0.2731299 7.6274e-4 0.9619769 -0.1194478 -5.78746e-4 0.9928404 0.7026698 4.74984e-4 -0.711516 0.8599343 -6.85301e-4 -0.5104045 0.9325649 1.47827e-4 -0.3610023 -0.8311114 5.76399e-4 -0.5561058 -0.5376513 -6.03587e-4 -0.8431672 -0.4281919 2.03603e-4 -0.9036878 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.0162611 0.02962172 -0.006337702 -0.01681894 0.02962172 -0.004684209 -0.01638752 0.007621705 -0.006035625 -0.01701438 0.007621705 -0.003912746 -0.01721698 0.02962172 -0.002905964 -0.01732343 0.007621705 -0.002195298 -0.01742482 0.02962172 -0.001173317 -0.01747578 0.007621705 -5.13351e-5 -0.01745909 0.02962172 5.71426e-4 -0.01733875 0.007621705 0.002157986 -0.01726138 0.02962172 0.002776026 -0.01704174 0.007621705 0.00387758 -0.01678746 0.02962172 0.0048725 -0.01657503 0.007621705 0.005559146 -0.01605188 0.02962172 0.006960153 -0.01594316 0.007621705 0.007185757 -0.01495522 0.007621705 0.009094595 -0.01484113 0.02962172 0.00928092 -0.01343864 0.007621705 0.01122808 -0.01359009 0.02962172 0.01102876 -0.0124284 0.02962172 0.01233112 -0.01191353 0.007621705 0.01283246 -0.01114296 0.02962172 0.01351124 -0.01058059 0.007621705 0.01395887 -0.009359002 0.02962172 0.01482188 -0.009443581 0.007621705 0.01475125 -0.008252501 0.007621705 0.01545965 -0.007473587 0.02962172 0.01585376 -0.006746649 0.007621705 0.01617717 -0.005524218 0.02962172 0.01664632 -0.005107402 0.007621705 0.01677614 -0.003841042 0.02962172 0.01710706 -0.003415107 0.007621705 0.0172016 -0.002479434 0.02962172 0.01736533 -0.001766145 0.007621705 0.01745408 -8.19142e-4 0.02962172 0.0175246 3.80989e-4 0.007621705 0.01755291 9.2605e-4 0.02962172 0.0175268 0.002586185 0.007621705 0.0173608 0.002738595 0.02962172 0.01733773 0.004297792 0.007621705 0.01702105 0.004447102 0.02962172 0.01698291 0.00596702 0.007621705 0.01651257 0.006449818 0.02962172 0.01633703 0.007647991 0.007621705 0.01580876 0.008035361 0.02962172 0.01560801 0.009180068 0.02962172 0.01497268 0.009178102 0.007621705 0.01496946 0.01062107 0.007621705 0.01398831 0.0106188 0.02962172 0.01398533 0.01189917 0.02962172 0.01291608 0.01201206 0.007621705 0.01281112 0.01339393 0.02962172 0.01137161 0.0135343 0.007621705 0.01120406 0.01475274 0.02962172 0.009527444 0.01474958 0.007621705 0.009525358 0.01558685 0.007621705 0.008083045 0.01565706 0.02962172 0.007945775 0.01616972 0.007621705 0.006825625 0.01633679 0.02962172 0.006422638 0.01666063 0.007621705 0.005529403 0.01659202 0.02962172 0.006050944 0.01675552 0.007621705 0.005560874 0.01718753 0.02962172 0.004020214 0.01709747 0.007621705 0.004370093 0.01739132 0.007621705 0.003007411 0.01749837 0.02962172 0.002292931 0.01760035 0.007621705 0.00126481 0.0176357 0.02962172 5.43296e-4 0.0176348 0.007621705 -4.89892e-4 0.01761519 0.02962172 -8.50562e-4 0.01751381 0.02962172 -0.002085149 0.01749438 0.007621705 -0.002238988 0.01728576 0.02962172 -0.003460347 0.01728576 0.007621705 -0.003460347 0.0170015 0.02962172 -0.004666149 0.01695936 0.007621705 -0.00481534 0.0165711 0.02962172 -0.005991876 0.0165711 0.007621705 -0.005991876 0.01611024 0.02962172 -0.007141888 0.01604634 0.007621705 -0.007283151 0.01531511 0.02962172 -0.00870639 0.01548707 0.007621705 -0.008388638 0.01477569 0.007621705 -0.009587347 0.01436805 0.02962172 -0.0101841 0.01344996 0.007621705 -0.01137554 0.0132786 0.02962172 -0.01156008 0.01205754 0.02962172 -0.01282083 0.01194381 0.007621705 -0.01292622 0.01071703 0.02962172 -0.01395368 0.01059335 0.007621705 -0.0140472 0.009573519 0.02962172 -0.01475054 0.009573519 0.007621705 -0.01475054 0.008511781 0.02962172 -0.01538902 0.008375525 0.007621705 -0.01546305 0.007262229 0.02962172 -0.01600652 0.007262229 0.007621705 -0.01600652 0.006117105 0.02962172 -0.01647967 0.005971372 0.007621705 -0.01653254 0.004441916 0.02962172 -0.01700282 0.004291653 0.007621705 -0.01704096 0.002722859 0.02962172 -0.01735663 0.002569556 0.007621705 -0.01737964 9.77207e-4 0.02962172 -0.01753753 8.22357e-4 0.007621705 -0.0175451 -7.77875e-4 0.02962172 -0.01754367 -9.32719e-4 0.007621705 -0.0175358 -0.002524673 0.02962172 -0.01737511 -0.002166092 0.007621705 -0.01741904 -0.003541767 0.007621705 -0.0171948 -0.004246294 0.02962172 -0.01703333 -0.005240321 0.007621705 -0.01675271 -0.005925118 0.02962172 -0.01652199 -0.007320761 0.007621705 -0.01596081 -0.007215023 0.02962172 -0.01599365 -0.008394777 0.02962172 -0.01540964 -0.009221196 0.007621705 -0.01493108 -0.009828269 0.02962172 -0.01453822 -0.01060342 0.007621705 -0.01398032 -0.01094776 0.02962172 -0.01370805 -0.01194941 0.007621705 -0.0128538 -0.01194685 0.02962172 -0.01285105 -0.013121 0.02962172 -0.01165288 -0.01322346 0.007621705 -0.01153653 -0.01400107 0.02962172 -0.01057207 -0.01431047 0.007621705 -0.01015859 -0.01471704 0.02962172 -0.009561061 -0.01543587 0.007621705 -0.008366346 -0.01563721 0.02962172 -0.007976174 -0.01618617 0.007621705 -0.006779611 -0.0163542 0.02962172 -0.006374299 -0.01665371 0.007621705 -0.005549132 -0.01678478 0.02962172 -0.00513035 -0.01711183 0.007621705 -0.003935337 -0.01714617 0.02962172 -0.003784179 -0.01736783 0.007621705 -0.002565264 -0.01736783 0.02962172 -0.002565264 -0.01751315 0.007621705 -0.001334905 -0.0175246 0.02962172 -0.001180291 -0.01756209 0.007621705 5.80288e-5 -0.01756209 0.02962172 5.80288e-5 -0.01752239 0.007621705 0.001296281 -0.01751065 0.02962172 0.001450896 -0.01736319 0.007621705 0.002680957 -0.01736319 0.02962172 0.002680957 -0.01713937 0.007621705 0.003899455 -0.01710474 0.02962172 0.004050552 -0.01677554 0.007621705 0.005245029 -0.01677554 0.02962172 0.005245029 -0.01637262 0.007621705 0.006416499 -0.01631587 0.02962172 0.006560802 -0.01565641 0.007621705 0.008018851 -0.01558554 0.02962172 0.008156716 -0.01478421 0.007621705 0.009541869 -0.01469999 0.02962172 0.009671986 -0.01398217 0.007621705 0.0106818 -0.01398217 0.02962172 0.0106818 -0.01320284 0.007621705 0.01164489 -0.01310014 0.02962172 0.011761 -0.01168757 0.007621705 0.01318639 -0.01152265 0.02962172 0.01333165 -0.01022326 0.007621705 0.01434159 -0.009865581 0.02962172 0.01459556 -0.009194672 0.007621705 0.01503217 -0.008436024 0.02962172 0.01547372 -0.00729227 0.007621705 0.01605862 -0.006786942 0.02962172 0.01627284 -0.005136966 0.007621705 0.01687175 -0.005135834 0.02962172 0.01686817 -0.003863215 0.02962172 0.01720458 -0.003434777 0.007621705 0.01729971 -0.002493917 0.02962172 0.01746433 -0.001776456 0.007621705 0.01755356 -8.24001e-4 0.02962172 0.01762449 -3.85245e-4 0.007621705 0.01763725 4.92314e-4 0.02962172 0.01763647 0.001369595 0.007621705 0.01760286 0.001883506 0.02962172 0.01755034 0.003465592 0.007621705 0.01731044 0.003617584 0.02962172 0.01727956 0.005558252 0.007621705 0.01676893 0.005766451 0.02962172 0.01669877 0.00729078 0.007621705 0.01607841 0.007689535 0.02962172 0.01589566 0.008470535 0.007621705 0.01549434 0.009232103 0.02962172 0.0150581 0.009903967 0.007621705 0.01462298 0.01067918 0.02962172 0.01406508 0.0113067 0.007621705 0.01356816 0.01196688 0.02962172 0.01298969 0.01233804 0.007621705 0.01263064 0.01295018 0.02962172 0.01200193 0.01324683 0.007621705 0.01167845 0.01381045 0.02962172 0.01100552 0.01407682 0.007621705 0.01065683 0.01483672 0.02962172 0.009581804 0.01483356 0.007621705 0.009579777 0.01567578 0.007621705 0.008128821 0.01574635 0.02962172 0.007990837 0.01626193 0.007621705 0.006864368 0.0168718 0.02962172 0.004842638 0.01712435 0.007621705 0.003847122 0.01734191 0.02962172 0.002745389 0.01741826 0.007621705 0.002126932 0.01753574 0.02962172 5.40264e-4 0.01755136 0.007621705 -8.2518e-5 0.01749837 0.02962172 -0.001204252 0.01739513 0.007621705 -0.002226412 0.01722288 0.02962172 -0.003335952 0.01708304 0.007621705 -0.003943204 0.01665073 0.02962172 -0.005474388 0.01645243 0.007621705 -0.006065011 0.01585775 0.02962172 -0.007472157 0.01557242 0.007621705 -0.008026123 0.01456099 0.02962172 -0.009746193 0.01443773 0.007621705 -0.009926617 0.01320338 0.02962172 -0.01149415 0.01310127 0.007621705 -0.01160967 0.01198929 0.02962172 -0.0127477 0.01187616 0.007621705 -0.01285248 0.01033723 0.02962172 -0.01412302 0.01015973 0.007621705 -0.01425045 0.008463501 0.02962172 -0.0153014 0.00832808 0.007621705 -0.01537501 0.006894111 0.02962172 -0.01606398 0.006319999 0.007621705 -0.0163061 0.005256414 0.02962172 -0.01666659 0.004267275 0.007621705 -0.01694393 0.003566801 0.02962172 -0.01710313 0.002555012 0.007621705 -0.01728063 0.001440227 0.02962172 -0.01741528 8.17854e-4 0.007621705 -0.0174452 -0.00117737 0.02962172 -0.01742935 -0.001395225 0.007621705 -0.01741278 -0.003767848 0.02962172 -0.01705306 -0.003980815 0.007621705 -0.01700425 -0.005891323 0.02962172 -0.01642781 -0.006374001 0.007621705 -0.01625233 -0.007868647 0.02962172 -0.0155853 -0.007959663 0.007621705 -0.01552325 -0.009168863 0.007621705 -0.01484584 -0.009772002 0.02962172 -0.01445549 -0.01054316 0.007621705 -0.01390051 -0.01088535 0.02962172 -0.01362997 -0.01188141 0.007621705 -0.01278042 -0.01219999 0.02962172 -0.01248216 -0.01314818 0.007621705 -0.01147067 -0.01360952 0.02962172 -0.01091986 -0.01422899 0.007621705 -0.01010054 -0.01463317 0.02962172 -0.009506583 -0.01534801 0.007621705 -0.008318483 -0.01554816 0.02962172 -0.007930696 + + + + + + + + + + 0.94753 -0.001055121 0.3196653 0.959062 0.001411259 0.2831929 0.975854 -0.001009166 0.218422 0.9841907 9.58261e-4 0.1771099 0.9928833 -9.58375e-4 0.119088 0.9974849 0.001302957 0.07086747 0.9998064 -0.001314997 0.01963633 0.9980818 9.94305e-4 -0.06190294 0.9960026 -9.9419e-4 -0.08931827 0.9854109 0.001315176 -0.1701876 0.9635695 9.58174e-4 -0.2674565 0.9753908 -0.001302957 -0.2204793 0.9321504 8.92941e-4 -0.3620704 0.943164 -0.00126332 -0.3323253 0.8880999 -3.25601e-4 -0.4596505 0.886599 -6.8044e-4 -0.4625384 0.8150516 6.80429e-4 -0.5793882 0.8131614 3.25461e-4 -0.5820382 0.7462676 -8.92658e-4 -0.6656455 0.7247869 0.001263201 -0.6889719 0.6762797 -9.5826e-4 -0.7366445 0.6454732 9.58227e-4 -0.7637824 0.5920718 -0.00126332 -0.8058843 0.5717201 4.38055e-4 -0.8204486 0.5111817 7.96132e-4 -0.8594725 0.4800885 -0.001282155 -0.8772191 0.4301744 9.42324e-4 -0.9027453 0.37664 -0.001173675 -0.926359 0.3431911 9.60149e-4 -0.9392651 0.2639929 -6.89355e-4 -0.9645245 0.243826 5.51297e-4 -0.9698188 0.1513462 9.19718e-4 -0.9884805 0.1863839 -6.1517e-4 -0.9824768 0.04597383 0.00122261 -0.9989419 0.09547883 -9.19649e-4 -0.9954311 0.001256763 -0.00121808 -0.9999986 -0.08677631 9.67414e-4 -0.9962274 -0.1037557 -3.2605e-4 -0.9946027 -0.1947068 3.18497e-4 -0.9808615 -0.2033386 -3.18431e-4 -0.9791085 -0.291401 3.18462e-4 -0.9566009 -0.3069282 -8.58363e-4 -0.9517323 -0.3861995 0.001114964 -0.9224146 -0.4177499 -9.35983e-4 -0.9085616 -0.4809215 1.69489e-4 -0.8767637 -0.4852929 5.65562e-4 -0.8743516 -0.5622924 1.69398e-4 -0.8269386 -0.5658206 -1.69502e-4 -0.8245285 -0.646006 3.26052e-4 -0.7633323 -0.6410016 -1.69416e-4 -0.7675396 -0.7260133 6.06175e-4 -0.6876806 -0.7185686 -3.70219e-4 -0.6954561 -0.8100028 1.69485e-4 -0.5864261 -0.805072 -6.17999e-4 -0.5931768 -0.8648577 1.69454e-4 -0.502017 -0.8681201 -3.26107e-4 -0.4963542 -0.9072617 2.71677e-4 -0.4205665 -0.9131877 -5.296e-4 -0.407539 -0.9351857 6.15022e-4 -0.3541573 0.9611615 4.53541e-4 0.2759863 0.959591 8.63336e-4 0.2813972 0.9775247 -6.4959e-4 0.2108201 0.9841893 9.63513e-4 0.1771175 0.9928843 -9.6339e-4 0.1190792 0.9969337 9.63589e-4 0.07824504 0.9998068 -9.63673e-4 0.01962947 0.9998915 6.4994e-4 -0.0147233 0.996794 -3.20405e-4 -0.0800113 0.9966457 -4.5352e-4 -0.08183729 0.9857231 0 -0.1683741 0.9865284 2.73356e-4 -0.1635903 0.9721921 -2.73232e-4 -0.234185 0.9733169 0 -0.2294651 0.9496178 0 -0.3134105 0.951127 2.73119e-4 -0.3088002 0.9264293 -2.72988e-4 -0.376469 0.9282442 0 -0.3719716 0.8923013 4.53554e-4 -0.4514404 0.8914722 3.20219e-4 -0.4530752 0.8599719 -6.49747e-4 -0.5103412 0.8419291 9.63769e-4 -0.5395873 0.8033043 -0.001270413 -0.5955676 0.7840155 8.97725e-4 -0.6207407 0.7173329 -3.72377e-4 -0.6967305 0.7183207 -2.42798e-4 -0.6957122 0.6387148 -3.2021e-4 -0.7694435 0.6454685 3.2046e-4 -0.7637869 0.5677356 0 -0.823211 0.5717228 2.73136e-4 -0.8204469 0.5111721 -2.73135e-4 -0.8594784 0.5153346 0 -0.8569891 0.4387009 0 -0.8986332 0.4430555 2.73181e-4 -0.8964942 0.3773613 -2.73196e-4 -0.9260661 0.3818493 0 -0.9242247 0.2896919 -3.20319e-4 -0.95712 0.2981108 3.20254e-4 -0.9545313 0.1929544 -3.20233e-4 -0.9812077 0.2015879 3.20261e-4 -0.9794704 0.09429991 -3.20266e-4 -0.9955438 0.1030661 3.20325e-4 -0.9946745 -0.005291283 -3.20287e-4 -0.9999861 0.003512442 3.20278e-4 -0.9999939 -0.09423488 4.53601e-4 -0.9955499 -0.0960676 3.2025e-4 -0.9953748 -0.1608849 -6.49767e-4 -0.9869731 -0.1947003 9.63731e-4 -0.9808624 -0.2518831 -9.63662e-4 -0.9677572 -0.2913909 9.63677e-4 -0.9566036 -0.3557384 -0.001270234 -0.9345848 -0.3790131 4.40584e-4 -0.9253913 -0.4436572 7.94818e-4 -0.8961963 -0.4764101 -0.001229524 -0.8792223 -0.5194513 9.2505e-4 -0.8544996 -0.566706 -9.25032e-4 -0.8239195 -0.5956455 6.18805e-4 -0.8032472 -0.6418283 -5.54543e-4 -0.7668483 -0.6510736 1.70541e-4 -0.7590146 -0.7142373 1.70497e-4 -0.6999037 -0.7187953 -3.27906e-4 -0.6952217 -0.78512 -5.99229e-4 -0.6193434 -0.7754315 2.73209e-4 -0.6314317 -0.8160766 6.1428e-4 -0.5779436 -0.8468809 -0.001208841 -0.5317813 -0.864811 9.89119e-4 -0.5020969 -0.9040287 -6.93241e-4 -0.4274712 -0.9127446 5.54595e-4 -0.4085303 -0.9347909 -5.96712e-4 -0.3551982 -0.9449926 5.96624e-4 -0.3270914 -0.9619898 -5.32698e-4 -0.2730851 -0.9657998 2.73346e-4 -0.2592893 -0.9829853 -2.7323e-4 -0.1836843 -0.9931002 0 -0.1172688 -0.983865 0 -0.1789132 -0.9936575 2.73228e-4 -0.1124494 -0.9993829 -2.7323e-4 -0.03512507 -0.9994861 0 0.03205603 -0.9995416 0 -0.03027653 -0.9993188 2.73104e-4 0.03690421 -0.9934557 -2.73233e-4 0.1142181 -0.9835451 0 0.1806634 -0.9928899 0 0.1190372 -0.982657 2.73356e-4 0.185433 -0.9653376 -2.73337e-4 0.2610048 -0.9456329 0 0.3252363 -0.9640602 0 0.2656841 -0.9440441 2.73116e-4 0.3298194 -0.9129456 -3.20249e-4 0.4080812 -0.9093164 3.20343e-4 0.4161052 -0.867777 -3.20348e-4 0.4969539 -0.863367 3.20253e-4 0.5045765 -0.8178505 -2.73227e-4 0.5754307 -0.8150491 0 0.5793919 -0.7773651 0 0.6290497 -0.7743046 2.73166e-4 0.632813 -0.7131592 -3.72257e-4 0.7010021 -0.7055732 6.09512e-4 0.7086369 -0.6193654 -5.41585e-4 0.7851027 -0.5574104 -5.22014e-4 0.830237 -0.6064541 6.80891e-4 0.7951182 -0.4748488 -0.001289248 0.8800665 -0.5234247 9.47716e-4 0.8520714 -0.43607 0.001254379 0.8999119 -0.352967 -0.001002252 0.9356353 -0.3391782 1.70462e-4 0.9407222 -0.2438284 -5.54491e-4 0.9698183 -0.2555609 1.70538e-4 0.966793 -0.1513421 -9.25019e-4 0.9884811 -0.1863938 6.18821e-4 0.982475 -0.06002682 -6.18731e-4 0.9981966 -0.0954777 9.25018e-4 0.9954312 0.01960235 -7.46554e-4 0.9998075 -0.009092867 3.98088e-4 0.9999586 0.06180447 9.3896e-4 0.998088 0.1381798 -8.63469e-4 0.9904068 0.1542809 3.20238e-4 0.988027 0.2505084 -3.72299e-4 0.9681144 0.2609142 6.09511e-4 0.9653619 0.3702394 -5.41505e-4 0.9289363 0.385367 6.80799e-4 0.9227632 0.4436588 -5.96529e-4 0.8961957 0.4771561 9.09453e-4 0.8788182 0.5194428 -0.001036584 0.8545047 0.565816 9.7218e-4 0.8245311 0.6010031 -9.09061e-4 0.7992463 0.6409952 9.47699e-4 0.7675443 0.6726599 -7.28069e-4 0.7399514 0.7087064 4.42348e-4 0.7055034 0.7234124 -3.98115e-4 0.690416 0.7569282 5.96543e-4 0.6534979 0.7761304 -5.96594e-4 0.6305723 0.8112127 5.54468e-4 0.584751 0.818237 -1.70474e-4 0.5748813 0.8648598 -1.70525e-4 0.5020138 0.8681214 3.27807e-4 0.4963519 0.9072626 -2.73126e-4 0.4205644 0.9166784 0.001019656 0.3996244 0.9351831 -9.38926e-4 0.3541633 -0.9471791 -9.19625e-4 -0.3207039 -0.9640451 9.58136e-4 -0.2657369 -0.9757816 -0.001303017 -0.2187434 -0.9857139 0.001315116 -0.1684234 -0.9961593 -9.94428e-4 -0.08755421 -0.9981901 9.94414e-4 -0.06013041 -0.9997698 -0.001315176 0.02141553 -0.9973567 0.001303017 0.07265126 -0.9917508 -0.001302897 0.1281747 -0.9838723 0.001315236 0.1788676 -0.9585545 9.94133e-4 0.284908 -0.966026 -9.94423e-4 0.2584433 -0.9294495 -0.001524329 0.3689463 -0.9123601 0.001524567 0.4093861 -0.8686817 -0.001207292 0.4953693 -0.858606 6.05924e-4 0.512636 -0.7897808 -6.06077e-4 0.6133891 -0.783132 3.70048e-4 0.6218554 -0.7183179 -3.18482e-4 0.695715 -0.7121632 3.18499e-4 0.7020139 -0.6398112 -3.70215e-4 0.7685321 -0.6315033 6.0606e-4 0.775373 -0.5323531 -6.06221e-4 0.8465222 -0.5232102 3.70184e-4 0.8522036 -0.4370497 -3.18426e-4 0.8994373 -0.4206486 9.94356e-4 0.9072231 -0.3453253 -0.001315236 0.9384822 -0.2967488 0.001303076 0.9549548 -0.2501724 -9.58122e-4 0.9682009 -0.1929451 9.58074e-4 0.9812092 -0.1452179 -0.001303017 0.9893988 -0.09429264 0.001315116 0.9955437 0.01463037 6.06019e-4 0.9998929 -0.005356967 -0.001206815 0.999985 0.1560785 6.80557e-4 0.9877445 0.1437445 -6.8031e-4 0.9896146 0.2997445 0.00103414 0.954019 0.2824446 -6.06066e-4 0.9592834 0.41775 8.33616e-4 0.9085617 0.3919974 -0.001261651 0.9199655 0.4887464 4.37994e-4 0.8724259 0.5104167 -0.001262903 0.8599263 0.56672 9.19636e-4 0.8239101 0.641838 5.51293e-4 0.7668401 0.5956398 -6.15221e-4 0.8032515 0.6576821 -6.89135e-4 0.7532953 0.7188014 9.83316e-4 0.6952148 0.742468 -0.001201629 0.6698805 0.7851241 9.58255e-4 0.6193377 0.8098778 -9.58199e-4 0.5865981 0.8468812 0.001201629 0.5317808 0.8648076 -9.83378e-4 0.5021024 0.9100831 9.74152e-4 0.4144248 0.9127461 3.646e-4 0.4085273 0 1 0 0 1 -9.92664e-6 0 1 1.11084e-5 0 1 -2.09783e-6 0 1 2.47764e-5 0 1 -1.12503e-5 0 1 6.59992e-6 0 1 8.55813e-6 0 1 4.67333e-5 0 1 -1.67464e-5 0 1 -2.74365e-5 0 1 -1.31531e-5 0 1 6.09954e-6 0 1 -1.57868e-5 0 1 6.08047e-6 0 1 -1.04347e-5 0 1 -1.3134e-5 0 1 5.22343e-5 0 1 2.49824e-6 0 1 -3.32357e-5 0 1 7.82528e-6 0 1 -2.47752e-5 0 1 1.55349e-5 0 1 4.86483e-5 0 1 -2.60814e-6 0 1 -1.57872e-5 0 1 -2.76564e-5 0 1 9.35585e-6 0 1 3.93979e-5 0 1 -5.22377e-5 0 1 -1.02899e-5 0 1 -3.63564e-5 0 1 2.00478e-5 0 1 -3.38974e-5 0 1 -3.32139e-5 0 1 -1.16703e-5 0 1 -1.29691e-5 0 1 4.17371e-5 0 1 4.21007e-5 0 1 -2.30634e-5 0 1 -1.05935e-5 0 1 5.96447e-6 0 1 -6.87517e-5 0 1 -8.37198e-6 0 1 -2.80679e-5 0 1 -2.48402e-6 0 1 1.71168e-5 0 1 -8.6074e-6 0 1 2.67287e-5 0 1 2.65264e-5 0 1 -1.71186e-5 0 1 4.44877e-6 0 1 1.20068e-5 0 1 1.90883e-5 0 1 -6.60031e-6 0 1 -7.01597e-6 0 1 -4.11469e-6 0 1 -4.07324e-5 0 1 3.33851e-5 0 1 4.29749e-6 0 1 3.38897e-5 0 1 8.95137e-6 0 1 -3.26473e-6 0 1 1.19307e-6 0 1 -2.34734e-5 0 1 6.59979e-6 0 1 2.46919e-5 0 1 6.13314e-6 0 1 6.32391e-6 0 1 -1.40303e-5 0 1 -1.55335e-5 0 1 -3.09693e-6 0 -1 0 0 -1 4.13296e-6 0 -1 -4.28577e-6 0 -1 -6.79325e-6 0 -1 4.27973e-6 0 -1 -4.08342e-6 0 -1 6.0028e-6 0 -1 1.52246e-5 0 -1 -1.82538e-6 0 -1 5.77914e-6 0 -1 3.54143e-6 0 -1 3.70172e-6 0 -1 -5.11574e-7 0 -1 5.42711e-6 0 -1 -3.41177e-6 0 -1 3.91276e-6 0 -1 -3.26493e-6 0 -1 2.77105e-6 0 -1 1.83634e-6 0 -1 1.18196e-5 0 -1 9.70957e-6 0 -1 -5.98358e-6 0 -1 -1.23262e-5 0 -1 -4.29305e-7 0 -1 8.37275e-6 0 -1 3.62825e-6 0 -1 -9.18146e-7 0 -1 5.76175e-7 0 -1 7.90569e-7 0 -1 -4.08817e-6 0 -1 7.01695e-6 0 -1 7.30879e-7 0 -1 7.06864e-6 0 -1 2.60841e-6 0 -1 -1.46166e-6 0 -1 -1.45636e-6 0 -1 7.90519e-7 0 -1 5.18635e-6 0 -1 8.24952e-7 0 -1 -4.65357e-6 0 -1 3.54174e-6 0 -1 -1.30577e-5 0 -1 1.19293e-6 0 -1 1.10173e-5 0 -1 -5.1435e-7 0 -1 3.75003e-6 0 -1 -7.24865e-7 0 -1 -5.18715e-6 0 -1 -3.56641e-6 0 -1 -1.6138e-6 0 -1 -8.65651e-6 0 -1 5.70686e-7 0 -1 -1.03739e-5 0 -1 5.83505e-6 0 -1 -4.13339e-6 0 -1 1.414e-5 0 -1 -9.9934e-6 0 -1 3.72566e-6 0 -1 9.30585e-6 0 -1 -5.01136e-6 0 -1 1.16076e-5 0 -1 -1.30404e-6 0 -1 -1.03746e-5 0 -1 -3.05197e-6 0 -1 7.10895e-6 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo/models/mini_talon_vtail/model.config b/Gazebo/models/mini_talon_vtail/model.config new file mode 100644 index 00000000..659e7d62 --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/model.config @@ -0,0 +1,37 @@ + + + Mini Talon V-Tail + 1.0 + model.sdf + + + Alessandro Bacchini + + + + Seth Schaffer + + + + Rhys Mainwaring + rhys.mainwaring@me.com + + + + X-UAV Mini Talon V-Tail. + + Original CAD model by Alessandro Bacchini, + retrieved from GradCAD 04 July 2023. + + https://grabcad.com/alessandro.bacchini-2 + https://grabcad.com/library/mini-talon-x-uav-1 + + + Motor model by Seth Schaffer, + retrieved from GradCAD 04 July 2023. + + https://grabcad.com/seth.schaffer-1 + https://grabcad.com/library/configurable-propdrive-v2-brushless-motor-with-mount-plate-solidworks-2019-1 + + + diff --git a/Gazebo/models/mini_talon_vtail/model.sdf b/Gazebo/models/mini_talon_vtail/model.sdf new file mode 100644 index 00000000..8a6f8f97 --- /dev/null +++ b/Gazebo/models/mini_talon_vtail/model.sdf @@ -0,0 +1,992 @@ + + + + + + + 0 0 0 0 0 0 + 1.8 + + 0.024607948 + 0 + 0 + 0.086155637 + 0 + 0.103828985 + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_fuselage_collision.stl + + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_left_wing_collision.stl + + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_right_wing_collision.stl + + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_left_tail_collision.stl + + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_right_tail_collision.stl + + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_fuselage.dae + + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_forward_deck.dae + + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_left_wing.dae + + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_right_wing.dae + + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_left_tail.dae + + + + + + 0 0 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_right_tail.dae + + + + + + -0.41 0 -0.03 0 90 0 + + + model://mini_talon_vtail/meshes/propdrive_3536_frontplate.dae + + + + + + 0 0.27 0.029 0 0 0 + + + 0.015 + + + + 1 0 0 1 + 1 0 0 1 + 0.1 0.1 0.1 1 + + + + + 0 -0.27 0.029 0 0 0 + + + 0.015 + + + + 0 1 0 1 + 0 1 0 1 + 0.1 0.1 0.1 1 + + + + + -0.33 0.08 0.051 0 0 0 + + + 0.01 + + + + 1 0 0 1 + 1 0 0 1 + 0.1 0.1 0.1 1 + + + + + -0.33 -0.08 0.051 0 0 0 + + + 0.01 + + + + 0 1 0 1 + 0 1 0 1 + 0.1 0.1 0.1 1 + + + + + + 0 0 0 180 0 0 + 1 + 1000.0 + + + 1 + 1 + + + + + 0.302018 0 -0.097974 90 0 0 + + 0.01 + + 1.01896E-06 + 0 + 0 + 1.01896E-06 + 0 + 1.71125E-06 + + + + + + model://mini_talon_vtail/meshes/mini_talon_main_wheel_collision.stl + + + + + + + model://mini_talon_vtail/meshes/mini_talon_main_wheel.dae + + + + + + 0 0 0 0 0 0 + base_link + main_wheel_link + + 0 0 1 + + -1.0e-16 + 1.0e+16 + + + 0.0001 + + + + + + -0.107 0.371 0.0174 0 0 0 + + 0.01 + + 4.68283E-05 + 0 + 0 + 2.54167E-06 + 0 + 4.93283E-05 + + + + + + model://mini_talon_vtail/meshes/mini_talon_left_aileron.dae + + + + + + + model://mini_talon_vtail/meshes/mini_talon_left_aileron.dae + + + + + + + 0.01 + + + + 1 0 1 1 + 1 0 1 1 + 0.1 0.1 0.1 1 + + + + + 0.015 0 0 0 0 0 + base_link + left_aileron_link + + 0 1 0 + + -0.523599 + 0.523599 + + + 0.0001 + + + + + + -0.107 -0.371 0.0174 0 0 0 + + 0.01 + + 4.68283E-05 + 0 + 0 + 2.54167E-06 + 0 + 4.93283E-05 + + + + 0.005 -0.002 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_right_aileron.dae + + + + + 0.005 -0.002 0 0 0 0 + + + model://mini_talon_vtail/meshes/mini_talon_right_aileron.dae + + + + + + + 0.01 + + + + 1 0 1 1 + 1 0 1 1 + 0.1 0.1 0.1 1 + + + + + 0.015 0 0 0 0 0 + base_link + right_aileron_link + + 0 1 0 + + -0.523599 + 0.523599 + + + 0.0001 + + + + + + -0.365 0.077 0.045 45 -10 6 + + 0.01 + + 1.97842E-05 + 0 + 0 + 3.02083E-06 + 0 + 2.27633E-05 + + + + + + model://mini_talon_vtail/meshes/mini_talon_left_ruddervator.dae + + + + + + + model://mini_talon_vtail/meshes/mini_talon_left_ruddervator.dae + + + + + + + 0.01 + + + + 1 0 1 1 + 1 0 1 1 + 0.1 0.1 0.1 1 + + + + + 0.01 0 0 0 0 0 + base_link + left_ruddervator_link + + 0 1 0 + + -0.523599 + 0.523599 + + + 0.0001 + + + + + + -0.365 -0.077 0.045 -45 -10 -6 + + 0.01 + + 1.97842E-05 + 0 + 0 + 3.02083E-06 + 0 + 2.27633E-05 + + + + + + model://mini_talon_vtail/meshes/mini_talon_right_ruddervator.dae + + + + + + + model://mini_talon_vtail/meshes/mini_talon_right_ruddervator.dae + + + + + + + 0.01 + + + + 1 0 1 1 + 1 0 1 1 + 0.1 0.1 0.1 1 + + + + + 0.01 0 0 0 0 0 + base_link + right_ruddervator_link + + 0 1 0 + + -0.523599 + 0.523599 + + + 0.0001 + + + + + + -0.41 0 -0.03 0 90 0 + + + 0.025 + + 9.75e-06 + 0 + 0 + 0.000166704 + 0 + 0.000167604 + + + + + 0 0 0.018 0 0 0 + + + 0.0175 + 0.036 + + + + + 0 0 -0.005 0 0 0 + + + 0.1 + 0.005 + + + + + + + model://mini_talon_vtail/meshes/propdrive_3536_motor_can.dae + + + + + 0 0 -0.005 0 180 0 + + + model://mini_talon_vtail/meshes/iris_prop_cw.dae + + + + 0.01 0.01 0.01 1 + 0.01 0.01 0.01 1 + 0.01 0.01 0.01 1 + + + + + 0 0 0 0 180 0 + base_link + motor_link + + 0 0 1 + + -1.0e-16 + 1.0e+16 + + + 0.004 + + + + + + + + + + + left_aileron_joint + 0.0 + /left_aileron_joint/cmd_pos + 2 + 0.01 + 0.0001 + 1 + -1 + 100 + -100 + + + + + right_aileron_joint + 0.0 + /right_aileron_joint/cmd_pos + 2 + 0.01 + 0.0001 + 1 + -1 + 100 + -100 + + + + + left_ruddervator_joint + 0.0 + /left_ruddervator_joint/cmd_pos + 2 + 0.01 + 0.0001 + 1 + -1 + 100 + -100 + + + + + right_ruddervator_joint + 0.0 + /right_ruddervator_joint/cmd_pos + 2 + 0.01 + 0.0001 + 1 + -1 + 100 + -100 + + + + + + + + 0.3 + 1.4 + 4.25 + 0.10 + 0.00 + -0.025 + 0.0 + 0.0 + 0.02 + 1.2041 + 0.084 0 0 + 0 -1 0 + 0 0 1 + motor_link + + + 0.3 + 1.4 + 4.25 + 0.10 + 0.00 + -0.025 + 0.0 + 0.0 + 0.02 + 1.2041 + -0.084 0 0 + 0 1 0 + 0 0 1 + motor_link + + + + + 0.13 + 3.7 + 0.06417112299 + 0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + 0 0.27 0.029 + 0.16 + 1.2041 + 1 0 0 + 0 0 1 + base_link + + + + + 0.13 + 3.7 + 0.06417112299 + 0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + 0 -0.27 0.029 + 0.16 + 1.2041 + 1 0 0 + 0 0 1 + base_link + + + + + 0.13 + 3.7 + 0.06417112299 + 0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + 0 0.27 0.029 + 0.011 + 1.2041 + 1 0 0 + 0 0 1 + base_link + left_aileron_joint + -4.0 + + + + + 0.13 + 3.7 + 0.06417112299 + 0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + 0 -0.27 0.029 + 0.011 + 1.2041 + 1 0 0 + 0 0 1 + base_link + right_aileron_joint + -4.0 + + + + + 0.13 + 3.7 + 0.06417112299 + 0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + -0.33 0.08 0.051 + 0.025 + 1.2041 + 1 0 0 + 0 1 1 + base_link + + + + + 0.13 + 3.7 + 0.06417112299 + 0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + -0.33 -0.08 0.051 + 0.025 + 1.2041 + 1 0 0 + 0 -1 1 + base_link + + + + + 0.13 + 3.7 + 0.06417112299 + 0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + -0.33 0.08 0.051 + 0.007 + 1.2041 + 1 0 0 + 0 1 1 + base_link + left_ruddervator_joint + -6.0 + + + + + 0.13 + 3.7 + 0.06417112299 + 0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + -0.33 -0.08 0.051 + 0.007 + 1.2041 + 1 0 0 + 0 -1 1 + base_link + right_ruddervator_joint + -6.0 + + + + + 127.0.0.1 + 9002 + 5 + 1 + 0 + + + 0 0 0 3.141593 0 0 + 0 0 0 3.141593 0 1.57079632 + + + base_link::imu_sensor + + + + left_aileron_joint + -1.0471976 + -0.5 + 1000 + 2000 + COMMAND + /left_aileron_joint/cmd_pos + + + + right_aileron_joint + 1.0471976 + -0.5 + 1000 + 2000 + COMMAND + /right_aileron_joint/cmd_pos + + + + + left_ruddervator_joint + 1.0471976 + -0.5 + 1000 + 2000 + COMMAND + /left_ruddervator_joint/cmd_pos + + + + + motor_joint + 830 + 0 + 1000 + 2000 + + + VELOCITY + 0.20 + 0 + 0 + 1 + -1 + 5.0 + -5.0 + + + + + + right_ruddervator_joint + 1.0471976 + -0.5 + 1000 + 2000 + COMMAND + /right_ruddervator_joint/cmd_pos + + + + + + + + + diff --git a/Gazebo/worlds/vtail_runway.sdf b/Gazebo/worlds/vtail_runway.sdf new file mode 100755 index 00000000..f822ee53 --- /dev/null +++ b/Gazebo/worlds/vtail_runway.sdf @@ -0,0 +1,115 @@ + + + + + 0.001 + 1 + + + + + + + + + + + + + + + 1.0 1.0 1.0 + 0.8 0.8 0.8 + + + + + -35.363262 + 149.165237 + 584 + 0 + EARTH_WGS84 + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + + 1 + + + 0 + 5 0 0.1 0 0 0 + + + 10 0.01 0.01 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + 0.5 0.5 0.5 1 + + + + 0 + 0 5 0.1 0 0 0 + + + 0.01 10 0.01 + + + + 0 1 0 1 + 0 1 0 1 + 0 1 0 1 + 0.5 0.5 0.5 1 + + + + 0 + 0 0 5.1 0 0 0 + + + 0.01 0.01 10 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + 0.5 0.5 0.5 1 + + + + + + + model://runway + + + + 0 0 0.2 0 0 90 + model://mini_talon_vtail + + + +